Merge branch 'AlienWii32_defaults' of

https://github.com/MJ666/cleanflight into MJ666-AlienWii32_defaults

Conflicts:
	src/main/target/NAZE/target.h
This commit is contained in:
Dominic Clifton 2014-12-26 18:40:01 +00:00
commit 996d72eee5
8 changed files with 1737 additions and 1590 deletions

View File

@ -0,0 +1,24 @@
# Board - AlienWii32
The AlienWii32 is actually in prototype stage only a few samples exist. There is some more field testing ongoing. The information below is preliminary and will be updated as needed.
Here are the hardware specifications:
- STM32F103CBT6 MCU
- MPU6050 accelerometer/gyro sensor unit
- 8x 4.2A brushed ESCs, integrated, to run the strongest micro motors
- extra-wide traces on the PCB, for maximum power throughput
- USB port, integrated
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100 or Lemon RX)
- alternatively PPM receiver connection (i.e. Deltang Rx31)
- ground and 3.3V for the receiver
- hardware bind plug for easy binding
- motor connections are at the corners for a clean look with reduced wiring
- dimensions: 29x33mm
- direct operation from an single cell lipoly battery
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset).
Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different.
The pin layout is very similar as the NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The AlienWii32 firmware will be built with TARGET=NAZE and OPTIONS="AlienWii32". The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with an small Quadcopter. An preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienWii32. The mixer can be activated with "mixer custom" in the CLI. To use the AlienWii32 in an Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the Cleanflight configurator.

49
docs/Spektrum bind.md Normal file
View File

@ -0,0 +1,49 @@
# Spektrum bind support
Spektrum bind with hardware bind plug support.
The Spektrum bind code is actually enabled for the NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY, CC3D targets.
## Configure the bind code
The following parameters can be used to enable and configure this in the related target.h file:
SPEKTRUM_BIND Enables the Spektrum bind code
BIND_PORT GPIOA Defines the port for the bind pin
BIND_PIN Pin_3 Defines the bind pin (the satellite receiver is connected to)
This is to activate the hardware bind plug feature
HARDWARE_BIND_PLUG Enables the hardware bind plug feature
BINDPLUG_PORT GPIOB Defines the port for the hardware bind plug
BINDPLUG_PIN Pin_5 Defines the hardware bind plug pin
## Hardware
The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during building of the firmware. BINDPLUG_PORT and BINDPLUG_PIN also need to be defined (please see above). This is done automatically if the AlienWii32 firmware is build. The hardware bind plug is expected between the defined bind pin and ground.
## Function
The bind code will actually work for NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY targets (USART2) and CC3D target (USART3, flex port). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
If the hardware bind plug is configured the bind mode will only be activated if the plug is set during the firmware start-up. The value of the spektrum_sat_bind parameter will be permanently preserved. The bind plug should be always removed for normal flying.
If no hardware bind plug is used the spektrum_sat_bind parameter will trigger the bind process during the next hardware reset and will be automatically reset to "0" after this.
Please refer to the satellite receiver documentation for more details of the specific receiver in bind mode. Usually the bind mode will be indicated with some flashing LEDs.
## Table with spektrum_sat_bind parameter value
| Value | Receiver mode | Notes |
| ----- | ---------------| -------------------|
| 3 | DSM2 1024/22ms | |
| 5 | DSM2 2048/11ms | default AlienWii32 |
| 7 | DSMX 22ms | |
| 9 | DSMX 11ms | |
More detailed information regarding the satellite binding process can be found here:
http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
### Supported Hardware
NAZE, NAZE32PRO, CJMCU, SPARKY, EUSTM32F103RC, CC3D targets (AlienWii32 with hardware bind plug)

View File

@ -444,6 +444,71 @@ static void resetConf(void)
applyDefaultLedStripConfig(masterConfig.ledConfigs);
#endif
// alternative defaults AlienWii32 (activate via OPTIONS="ALIENWII32" during make for NAZE target)
#ifdef ALIENWII32
featureSet(FEATURE_RX_SERIAL);
featureSet(FEATURE_MOTOR_STOP);
featureSet(FEATURE_FAILSAVE);
masterConfig.serialConfig.serial_port_scenario[1] = lookupScenarioIndex(SCENARIO_SERIAL_RX_ONLY);
masterConfig.rxConfig.serialrx_provider = 1;
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.escAndServoConfig.minthrottle = 1000;
masterConfig.escAndServoConfig.maxthrottle = 2000;
masterConfig.motor_pwm_rate = 32000;
currentControlRateProfile->rcRate8 = 130;
currentControlRateProfile->rollPitchRate = 20;
currentControlRateProfile->yawRate = 60;
parseRcChannels("TAER1234", &masterConfig.rxConfig);
// { 1.0f, -0.5f, 1.0f, -1.0f }, // REAR_R
masterConfig.customMixer[0].throttle = 1.0f;
masterConfig.customMixer[0].roll = -0.5f;
masterConfig.customMixer[0].pitch = 1.0f;
masterConfig.customMixer[0].yaw = -1.0f;
// { 1.0f, -0.5f, -1.0f, 1.0f }, // FRONT_R
masterConfig.customMixer[1].throttle = 1.0f;
masterConfig.customMixer[1].roll = -0.5f;
masterConfig.customMixer[1].pitch = -1.0f;
masterConfig.customMixer[1].yaw = 1.0f;
// { 1.0f, 0.5f, 1.0f, 1.0f }, // REAR_L
masterConfig.customMixer[2].throttle = 1.0f;
masterConfig.customMixer[2].roll = 0.5f;
masterConfig.customMixer[2].pitch = 1.0f;
masterConfig.customMixer[2].yaw = 1.0f;
// { 1.0f, 0.5f, -1.0f, -1.0f }, // FRONT_L
masterConfig.customMixer[3].throttle = 1.0f;
masterConfig.customMixer[3].roll = 0.5f;
masterConfig.customMixer[3].pitch = -1.0f;
masterConfig.customMixer[3].yaw = -1.0f;
// { 1.0f, -1.0f, -0.5f, -1.0f }, // MIDFRONT_R
masterConfig.customMixer[4].throttle = 1.0f;
masterConfig.customMixer[4].roll = -1.0f;
masterConfig.customMixer[4].pitch = -0.5f;
masterConfig.customMixer[4].yaw = -1.0f;
// { 1.0f, 1.0f, -0.5f, 1.0f }, // MIDFRONT_L
masterConfig.customMixer[5].throttle = 1.0f;
masterConfig.customMixer[5].roll = 1.0f;
masterConfig.customMixer[5].pitch = -0.5f;
masterConfig.customMixer[5].yaw = 1.0f;
// { 1.0f, -1.0f, 0.5f, 1.0f }, // MIDREAR_R
masterConfig.customMixer[6].throttle = 1.0f;
masterConfig.customMixer[6].roll = -1.0f;
masterConfig.customMixer[6].pitch = 0.5f;
masterConfig.customMixer[6].yaw = 1.0f;
// { 1.0f, 1.0f, 0.5f, -1.0f }, // MIDREAR_L
masterConfig.customMixer[7].throttle = 1.0f;
masterConfig.customMixer[7].roll = 1.0f;
masterConfig.customMixer[7].pitch = 0.5f;
masterConfig.customMixer[7].yaw = -1.0f;
#endif
// copy first profile into remaining profile
for (i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));

View File

@ -132,3 +132,12 @@
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
// alternative defaults AlienWii32 (activate via OPTIONS="ALIENWII32" during make for NAZE target)
#ifdef ALIENWII32
#define BRUSHED_MOTORS
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB5 (Pin 41)
#define BINDPLUG_PORT GPIOB
#define BINDPLUG_PIN Pin_5
#endif