1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 20:10:18 +03:00

Merge remote-tracking branch 'upstream/master' into blackbox-flash

This commit is contained in:
Nicholas Sherlock 2015-02-21 12:52:26 +13:00
commit f6c9f7cc4a
16 changed files with 457 additions and 115 deletions

View file

@ -16,7 +16,7 @@ The MultiWii software, from which baseflight originated, violates many good soft
Cleanflight also has additional features not found in baseflight.
* Multi-color RGB LED Strip support (each LED can be a different color using variable length WS2811 Addressable RGB strips - use for Orientation Indicators, Low Battery Warning, Flight Mode Status, etc)
* OneShot ESC support.
* Oneshot ESC support.
* Support for additional targets that use the STM32F3 processors (baseflight only supports STM32F1).
* Support for the TauLabs Sparky board (~$35 STM32F303 I2C sensors, based board with acc/gyro/compass and baro!)
* Support for the OpenPilot CC3D board. (~$20 STM32F103 board, SPI acc/gyro)

View file

@ -3,6 +3,7 @@
filename=Manual
doc_files=(
'Introduction.md'
'Safety.md'
'Installation.md'
'Configuration.md'
'Cli.md'

View file

@ -100,9 +100,14 @@ The virtual sensor uses the throttle position to calculate as estimated current
| Setting | Description |
| ----------------------------- | -------------------------------------------------------- |
| `current_meter_scale` | The throttle scaling factor [centiamps, i.e. 1/100th A] |
| `current_meter_offset` | The current at zero throttle [centiamps, i.e. 1/100th A] |
| `current_meter_offset` | The current at zero throttle (while armed) [centiamps, i.e. 1/100th A] |
If you know your current at zero throttle (Imin) and maximum throttle(Imax) you can calculate the scaling factors using the following formulas where Tmax is maximum throttle offset (i.e. for `max_throttle` = 1850, Tmax = 1850 - 1000 = 850):
There are two simple methods to tune the parameters depending in whether it is possible to measure current draw for your craft.
#### Tuning Using Battery Charger Measurement
It may be difficult to adjust `current_meter_offset` using this method unless you can measure the actual current draw with the craft armed at minimum throttle. Adjust `current_meter_scale` until the mAh draw reported by Cleanflight matches the charging data given by your battery charger after the flight (if the mAh draw is lower than reported by your battery charger, increase `current_meter_scale`, and vice-versa).
#### Tuning Using Actual Current Measurements
If you know your crafts current draw at zero throttle while armed (Imin) and maximum throttle(Imax) you can calculate the scaling factors using the following formulas where Tmax is maximum throttle offset (i.e. for `max_throttle` = 1850, Tmax = 1850 - 1000 = 850):
```
current_meter_scale = (Imax - Imin) * 100000 / (Tmax + (Tmax * Tmax / 50))
current_meter_offset = Imin * 100

View file

@ -24,3 +24,9 @@ Here are the hardware specifications:
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 for the ALIENWIIF1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The hardware bind pin is connected to pin 41 (PB5). The pin layout for the ALIENWIIF3 is similar to Sparky. The hardware bind pin is connected to pin 25 (PB12). The AlienWii32 firmware will be built as target ALIENWIIF1 or ALIENWIIF3. 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.
## Flashing the firmware
The AlienWii32 F1 board can be flashed like the Naze board or the related clones. All the different methods will work in the same way.
The AlienWii32 F3 board needs to be flashed via the USB port in DFU mode. Flashing via the Cleanflight GUI is not possible yet. The DFU mode can be activated via setting the BOOT0 jumper during power on of the board. The second method is to connect with an terminal program (i.e. Putty) to the board and enter the character "R" immediately after connecting. Details about the flashing process can be found in the related section of the Sparky documentation. The BOOT0 jumper should be removed and the board needs to be repowerd after firmware flashing. Please be aware, during reboot of the AlienWii F3 board, the GUI will disconnect and an manual reconnect is required.

View file

@ -77,7 +77,7 @@ The status bar will show the upload progress and confirm that the upload is comp
Disconnect and reconnect the board from USB and continue to configure it via the Cleanflight configurator as per normal
## Via Device Firmware Upload (DFU, USB) - Mac OS X
## Via Device Firmware Upload (DFU, USB) - Mac OS X / Linux
These instructions are for dfu-util, tested using dfu-util 0.7 for OSX from the OpenTX project.
@ -144,6 +144,13 @@ can't detach
Resetting USB to switch back to runtime mode
```
On Linux you might want to take care that the modemmanager isn't trying to use your sparky as modem getting it into bootloader mode while doing so. In doubt you probably want to uninstall it. It could also be good idea to get udev fixed. It looks like teensy did just that -> http://www.pjrc.com/teensy/49-teensy.rules (untested)
To make a full chip erase you can use a file created by
```
dd if=/dev/zero of=zero.bin bs=1 count=262144
```
This can be used by dfu-util.
## Via SWD

View file

@ -66,4 +66,185 @@ Compare the two backups to make sure you are happy with your restored settings.
Re-apply any new defaults as desired.
## CLI Command Reference
| Command | Description |
|----------------|------------------------------------------------|
| adjrange | show/set adjustment ranges settings |
| aux | show/set aux settings |
| cmix | design custom mixer |
| color | configure colors |
| defaults | reset to defaults and reboot |
| dump | print configurable settings in a pastable form |
| exit | |
| feature | list or -val or val |
| get | get variable value |
| gpspassthrough | passthrough gps to serial |
| help | |
| led | configure leds |
| map | mapping of rc channel order |
| mixer | mixer name or list |
| motor | get/set motor output value |
| profile | index (0 to 2) |
| rateprofile | index (0 to 2) |
| save | save and reboot |
| set | name=value or blank or * for list |
| status | show system status |
| version | |
## CLI Variable Reference
| Variable | Description/Units | Min | Max | Default | Type | Datatype |
|-------------------------------|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|--------|--------|---------------|--------------|----------|
| looptime | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). Default of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. | 0 | 9000 | 3500 | Master | UINT16 |
| emf_avoidance | Default value is 0 for 72MHz processor speed. Setting this to 1 increases the processor speed, to move the 6th harmonic away from 432MHz. | 0 | 1 | 0 | Master | UINT8 |
| mid_rc | This is an important number to set in order to avoid trimming receiver/transmitter. Most standard receivers will have this at 1500, however Futaba transmitters will need this set to 1520. A way to find out if this needs to be changed, is to clear all trim/subtrim on transmitter, and connect to GUI. Note the value most channels idle at - this should be the number to choose. Once midrc is set, use subtrim on transmitter to make sure all channels (except throttle of course) are centered at midrc value. | 1200 | 1700 | 1500 | Master | UINT16 |
| min_check | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. | 0 | 2000 | 1100 | Master | UINT16 |
| max_check | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. | 0 | 2000 | 1900 | Master | UINT16 |
| rssi_channel | | 0 | 18 | 0 | Master | INT8 |
| rssi_scale | | 1 | 255 | 30 | Master | UINT8 |
| input_filtering_mode | | 0 | 1 | 0 | Master | INT8 |
| min_throttle | These are min/max values (in us) that are sent to esc when armed. Defaults of 1150/1850 are OK for everyone, for use with AfroESC, they could be set to 1064/1864. | 0 | 2000 | 1150 | Master | UINT16 |
| max_throttle | These are min/max values (in us) that are sent to esc when armed. Defaults of 1150/1850 are OK for everyone, for use with AfroESC, they could be set to 1064/1864. | 0 | 2000 | 1850 | Master | UINT16 |
| min_command | This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once. | 0 | 2000 | 1000 | Master | UINT16 |
| servo_center_pulse | | 0 | 2000 | 1500 | Master | UINT16 |
| 3d_deadband_low | | 0 | 2000 | 1406 | Master | UINT16 |
| 3d_deadband_high | | 0 | 2000 | 1514 | Master | UINT16 |
| 3d_neutral | | 0 | 2000 | 1460 | Master | UINT16 |
| 3d_deadband_throttle | | 0 | 2000 | 50 | Master | UINT16 |
| motor_pwm_rate | Output frequency (in Hz) for motor pins. Defaults are 400Hz for motor. If setting above 500Hz, will switch to brushed (direct drive) motors mode. For example, setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported. Note, that in brushed mode, minthrottle is offset to zero. Default is 16000 for boards with brushed motors. | 50 | 32000 | 400 | Master | UINT16 |
| servo_pwm_rate | Output frequency (in Hz) servo pins. Default is 50Hz. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. | 50 | 498 | 50 | Master | UINT16 |
| retarded_arm | Disabled by default, enabling (setting to 1) allows disarming by throttle low + roll. This could be useful for non-acro tricopters, where default arming by yaw could move tail servo too much. | 0 | 1 | 0 | Master | UINT8 |
| disarm_kill_switch | Enabled by default. Disarms the motors independently of throttle value. Setting to 0 reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | 0 | 1 | 1 | Master | UINT8 |
| auto_disarm_delay | | 0 | 60 | 5 | Master | UINT8 |
| small_angle | If the copter tilt angle exceed this value the copter will refuse to arm. default is 25°. | 0 | 180 | 25 | Master | UINT8 |
| flaps_speed | | 0 | 100 | 0 | Master | UINT8 |
| fixedwing_althold_dir | | -1 | 1 | 1 | Master | INT8 |
| serial_port_1_scenario | | 0 | 11 | | Master | UINT8 |
| serial_port_2_scenario | | 0 | 11 | | Master | UINT8 |
| serial_port_3_scenario | | 0 | 11 | | Master | UINT8 |
| serial_port_4_scenario | | 0 | 11 | | Master | UINT8 |
| serial_port_5_scenario | | 0 | 11 | | Master | UINT8 |
| reboot_character | | 48 | 126 | 82 | Master | UINT8 |
| msp_baudrate | | 1200 | 115200 | 115200 | Master | UINT32 |
| cli_baudrate | | 1200 | 115200 | 115200 | Master | UINT32 |
| gps_baudrate | | 0 | 115200 | 115200 | Master | UINT32 |
| gps_passthrough_baudrate | | 1200 | 115200 | 115200 | Master | UINT32 |
| gps_provider | | 0 | 1 | 0 | Master | UINT8 |
| gps_sbas_mode | | 0 | 4 | 0 | Master | UINT8 |
| gps_auto_config | | 0 | 1 | 1 | Master | UINT8 |
| gps_auto_baud | | 0 | 1 | 0 | Master | UINT8 |
| gps_pos_p | | 0 | 200 | 15 | Profile | UINT8 |
| gps_pos_i | | 0 | 200 | 0 | Profile | UINT8 |
| gps_pos_d | | 0 | 200 | 0 | Profile | UINT8 |
| gps_posr_p | | 0 | 200 | 34 | Profile | UINT8 |
| gps_posr_i | | 0 | 200 | 14 | Profile | UINT8 |
| gps_posr_d | | 0 | 200 | 53 | Profile | UINT8 |
| gps_nav_p | | 0 | 200 | 25 | Profile | UINT8 |
| gps_nav_i | | 0 | 200 | 33 | Profile | UINT8 |
| gps_nav_d | | 0 | 200 | 83 | Profile | UINT8 |
| gps_wp_radius | | 0 | 2000 | 200 | Profile | UINT16 |
| nav_controls_heading | | 0 | 1 | 1 | Profile | UINT8 |
| nav_speed_min | | 10 | 2000 | 100 | Profile | UINT16 |
| nav_speed_max | | 10 | 2000 | 300 | Profile | UINT16 |
| nav_slew_rate | | 0 | 100 | 30 | Profile | UINT8 |
| serialrx_provider | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | 0 | 6 | 0 | Master | UINT8 |
| spektrum_sat_bind | | 0 | 10 | 0 | Master | UINT8 |
| telemetry_provider | Choose what type of telemetry to output. See Telemetry section. | 0 | 3 | 0 | Master | UINT8 |
| telemetry_switch | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | 0 | 1 | 0 | Master | UINT8 |
| telemetry_inversion | | 0 | 1 | 0 | Master | UINT8 |
| frsky_default_lattitude | | -90 | 90 | 0 | Master | FLOAT |
| frsky_default_longitude | | -180 | 180 | 0 | Master | FLOAT |
| frsky_coordinates_format | | 0 | 1 | 0 | Master | UINT8 |
| frsky_unit | | 0 | 1 | 0 | Master | UINT8 |
| battery_capacity | | 0 | 20000 | 0 | Master | UINT16 |
| vbat_scale | Result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 4095 = 12bit adc, 110 = 11:1 voltage divider (10k:1k) x 10 for 0.1V. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status"" in cli." | 0 | 255 | 110 | Master | UINT8 |
| vbat_max_cell_voltage | Maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V) | 10 | 50 | 43 | Master | UINT8 |
| vbat_min_cell_voltage | Minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V) | 10 | 50 | 33 | Master | UINT8 |
| vbat_warning_cell_voltage | | 10 | 50 | 35 | Master | UINT8 |
| current_meter_scale | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the Überdistro with a 0.25mOhm shunt. | -10000 | 10000 | 400 | Master | INT16 |
| current_meter_offset | This sets the output offset voltage of the current sensor in millivolts. | 0 | 3300 | 0 | Master | UINT16 |
| multiwii_current_meter_output | Default current output via MSP is in 0.01A steps. Setting this to 1 causes output in default multiwii scaling (1mA steps). | 0 | 1 | None defined! | Master | UINT8 |
| current_meter_type | | 0 | 2 | 1 | Master | UINT8 |
| align_gyro | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. Default of zero means the driver determines alignment (and this generally means it's configured for standard hardware). Default orientation of X forward, Y right, Z up is 1. After that, the numbers are as follows, and mean sensor is rotated. CW0_DEG=1, CW90_DEG=2, CW180_DEG=3, CW270_DEG=4, CW0_DEG_FLIP=5, CW90_DEG_FLIP=6, CW180_DEG_FLIP=7, CW270_DEG_FLIP=8. This should cover all orientations. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. | 0 | 8 | 0 | Master | UINT8 |
| align_acc | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. Default of zero means the driver determines alignment (and this generally means it's configured for standard hardware). Default orientation of X forward, Y right, Z up is 1. After that, the numbers are as follows, and mean sensor is rotated. CW0_DEG=1, CW90_DEG=2, CW180_DEG=3, CW270_DEG=4, CW0_DEG_FLIP=5, CW90_DEG_FLIP=6, CW180_DEG_FLIP=7, CW270_DEG_FLIP=8. This should cover all orientations. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. | 0 | 8 | 0 | Master | UINT8 |
| align_mag | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. Default of zero means the driver determines alignment (and this generally means it's configured for standard hardware). Default orientation of X forward, Y right, Z up is 1. After that, the numbers are as follows, and mean sensor is rotated. CW0_DEG=1, CW90_DEG=2, CW180_DEG=3, CW270_DEG=4, CW0_DEG_FLIP=5, CW90_DEG_FLIP=6, CW180_DEG_FLIP=7, CW270_DEG_FLIP=8. This should cover all orientations. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. | 0 | 8 | 0 | Master | UINT8 |
| align_board_roll | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc | -180 | 360 | 0 | Master | INT16 |
| align_board_pitch | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc | -180 | 360 | 0 | Master | INT16 |
| align_board_yaw | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc | -180 | 360 | 0 | Master | INT16 |
| max_angle_inclination | This setting controls max inclination (tilt) allowed in angle (level) mode. default 500 (50 degrees). | 100 | 900 | 500 | Master | UINT16 |
| gyro_lpf | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 5,10,20,42,98,188,256Hz, while MPU3050 doesn't allow 5Hz. If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. Values outside of supported range will usually be ignored by drivers, and will configure lpf to default value of 42Hz. | 0 | 256 | 42 | Master | UINT16 |
| moron_threshold | When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold (default of 32) means how much average gyro reading could differ before re-calibration is triggered. | 0 | 128 | 32 | Master | UINT8 |
| gyro_cmpf_factor | | 100 | 1000 | 600 | Master | UINT16 |
| gyro_cmpfm_factor | | 100 | 1000 | 250 | Master | UINT16 |
| alt_hold_deadband | | 1 | 250 | 40 | Profile | UINT8 |
| alt_hold_fast_change | | 0 | 1 | 1 | Profile | UINT8 |
| deadband | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | 0 | 32 | 0 | Profile | UINT8 |
| yaw_deadband | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | 0 | 100 | 0 | Profile | UINT8 |
| throttle_correction_value | The throttle_correction_value will be added to the throttle input. It will be maximal at the throttle_correction_angle and over, null when the copter is leveled and proportional in bewteen. The angle is set with 0.1 deg steps from 1 to 900, ie : 300 = 30.0 deg, 225 = 22.5 deg. | 0 | 150 | 0 | Profile | UINT8 |
| throttle_correction_angle | The throttle_correction_value will be added to the throttle input. It will be maximal at the throttle_correction_angle and over, null when the copter is leveled and proportional in bewteen. The angle is set with 0.1 deg steps from 1 to 900, ie : 300 = 30.0 deg, 225 = 22.5 deg. | 1 | 900 | 800 | Profile | UINT16 |
| yaw_control_direction | | -1 | 1 | 1 | Master | INT8 |
| yaw_direction | | -1 | 1 | 1 | Profile | INT8 |
| tri_unarmed_servo | On tricopter mix only, if this is set to 1, servo will always be correcting regardless of armed state. to disable this, set it to 0. | 0 | 1 | 1 | Profile | INT8 |
| default_rate_profile | Default = profile number | 0 | 2 | | Profile | UINT8 |
| rc_rate | | 0 | 250 | 90 | Rate Profile | UINT8 |
| rc_expo | | 0 | 100 | 65 | Rate Profile | UINT8 |
| thr_mid | | 0 | 100 | 50 | Rate Profile | UINT8 |
| thr_expo | | 0 | 100 | 0 | Rate Profile | UINT8 |
| roll_pitch_rate | | 0 | 100 | 0 | Rate Profile | UINT8 |
| yaw_rate | | 0 | 100 | 0 | Rate Profile | UINT8 |
| tpa_rate | | 0 | 100 | 0 | Rate Profile | UINT8 |
| tpa_breakpoint | | 1000 | 2000 | 1500 | Rate Profile | UINT16 |
| failsafe_delay | | 0 | 200 | 10 | Profile | UINT8 |
| failsafe_off_delay | | 0 | 200 | 200 | Profile | UINT8 |
| failsafe_throttle | | 1000 | 2000 | 1200 | Profile | UINT16 |
| failsafe_min_usec | | 100 | 2000 | 985 | Profile | UINT16 |
| failsafe_max_usec | | 100 | 3000 | 2115 | Profile | UINT16 |
| gimbal_flags | When feature SERVO_TILT is enabled, this can be a combination of the following numbers: 1=normal gimbal (default), 2=tiltmix gimbal, 4=in PPM (or SERIALRX) input mode, this will forward AUX1..4 RC inputs to PWM5..8 pins | 0 | 255 | 1 | Profile | UINT8 |
| acc_hardware | This is used to suggest which accelerometer driver should load, or to force no accelerometer in case gyro-only flight is needed. Default (0) will attempt to auto-detect among enabled drivers. Otherwise, to force a particular device, set it to 1 for ADXL345, 2 for MPU6050 integrated accelerometer, 3 for MMA8452, 4 for BMA280, or 5 to disable accelerometer alltogether - resulting in gyro-only operation. | 0 | 9 | 0 | Master | UINT8 |
| acc_lpf_factor | | 0 | 250 | 4 | Profile | UINT8 |
| accxy_deadband | | 0 | 100 | 40 | Profile | UINT8 |
| accz_deadband | | 0 | 100 | 40 | Profile | UINT8 |
| accz_lpf_cutoff | | 1 | 20 | 5 | Profile | FLOAT |
| acc_unarmedcal | | 0 | 1 | 1 | Profile | UINT8 |
| acc_trim_pitch | | -300 | 300 | 0 | Profile | INT16 |
| acc_trim_roll | | -300 | 300 | 0 | Profile | INT16 |
| baro_tab_size | | 0 | 48 | 21 | Profile | UINT8 |
| baro_noise_lpf | | 0 | 1 | 0.6 | Profile | FLOAT |
| baro_cf_vel | | 0 | 1 | 0.985 | Profile | FLOAT |
| baro_cf_alt | | 0 | 1 | 0.965 | Profile | FLOAT |
| mag_hardware | | 0 | 3 | 0 | Master | UINT8 |
| mag_declination | Current location magnetic declination in format. For example, -6deg 37min, = for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ | -18000 | 18000 | 0 | Profile | INT16 |
| pid_controller | | 0 | 4 | 0 | Profile | UINT8 |
| p_pitch | | 0 | 200 | 40 | Profile | UINT8 |
| i_pitch | | 0 | 200 | 30 | Profile | UINT8 |
| d_pitch | | 0 | 200 | 23 | Profile | UINT8 |
| p_roll | | 0 | 200 | 40 | Profile | UINT8 |
| i_roll | | 0 | 200 | 30 | Profile | UINT8 |
| d_roll | | 0 | 200 | 23 | Profile | UINT8 |
| p_yaw | | 0 | 200 | 85 | Profile | UINT8 |
| i_yaw | | 0 | 200 | 45 | Profile | UINT8 |
| d_yaw | | 0 | 200 | 0 | Profile | UINT8 |
| p_pitchf | | 0 | 100 | 2.5 | Profile | FLOAT |
| i_pitchf | | 0 | 100 | 0.6 | Profile | FLOAT |
| d_pitchf | | 0 | 100 | 0.06 | Profile | FLOAT |
| p_rollf | | 0 | 100 | 2.5 | Profile | FLOAT |
| i_rollf | | 0 | 100 | 0.6 | Profile | FLOAT |
| d_rollf | | 0 | 100 | 0.06 | Profile | FLOAT |
| p_yawf | | 0 | 100 | 8 | Profile | FLOAT |
| i_yawf | | 0 | 100 | 0.5 | Profile | FLOAT |
| d_yawf | | 0 | 100 | 0.05 | Profile | FLOAT |
| level_horizon | | 0 | 10 | 3 | Profile | FLOAT |
| level_angle | | 0 | 10 | 5 | Profile | FLOAT |
| sensitivity_horizon | | 0 | 250 | 75 | Profile | UINT8 |
| p_alt | | 0 | 200 | 50 | Profile | UINT8 |
| i_alt | | 0 | 200 | 0 | Profile | UINT8 |
| d_alt | | 0 | 200 | 0 | Profile | UINT8 |
| p_level | | 0 | 200 | 90 | Profile | UINT8 |
| i_level | | 0 | 200 | 10 | Profile | UINT8 |
| d_level | | 0 | 200 | 100 | Profile | UINT8 |
| p_vel | | 0 | 200 | 120 | Profile | UINT8 |
| i_vel | | 0 | 200 | 45 | Profile | UINT8 |
| d_vel | | 0 | 200 | 1 | Profile | UINT8 |
| blackbox_rate_num | | 1 | 32 | 1 | Master | UINT8 |
| blackbox_rate_denom | | 1 | 32 | 1 | Master | UINT8 |

View file

@ -5,13 +5,13 @@ Oneshot allows faster communication between the Flight Controller and the ESCs t
It does this in two ways:
1. Use a signal that varies between 125 µs and 250 µs (instead of the normal PWM timing of 1000µs to 2000µs)
1. Only send a 'shot' once per flight controller loop, and do this as soon as the flight controller has calculated the required speed of the motors.
## Supported ESCs
At present, only the FlyDuino KISS ESCs are able to use the Oneshot125 protocol.
FlyDuino KISS ESCs are able to use the Oneshot125 protocol out of the box. There is only one soldering needed.
BLHeli rev13.0 also supports Oneshot125 and will be automatically selected by the ESC without additional work.
## Supported Boards
@ -42,20 +42,13 @@ Then you can safely power up your ESCs again.
The process for calibrating oneshot ESCs is the same as any other ESC.
1. Ensure that your ESCs are not powered up.
1. Connect to the board using a USB cable, and change to the motor test page.
1. Set the motor speed to maximum using the main slider.
1. Connect power to your ESCs. They will beep.
1. Click on the slider to bring the motor speed down to zero. The ESCs will beep again, usually a couple of times.
1. Disconnect the power from your ESCs.
1. Re-connect power to your ESCs, and verify that moving the motor slider makes your motors spin up normally.
## References
* FlyDuino (<a href="http://flyduino.net/">http://flyduino.net/</a>)

View file

@ -16,18 +16,43 @@ Basically, the goal of the PID controller is to bring the craft's rotation rate
you're commanding with your sticks. An error is computed which is the difference between your target rotation rate and
the actual one measured by the gyroscopes, and the controller tries to bring this error to zero.
The P term controls the strength of the correction that is applied to bring the craft toward the target angle or
##PIDs
**The P term** controls the strength of the correction that is applied to bring the craft toward the target angle or
rotation rate. If the P term is too low, the craft will be difficult to control as it won't respond quickly enough to
keep itself stable. If it is set too high, the craft will rapidly oscillate/shake as it continually overshoots its
target.
The I term corrects small, long term errors. If it is set too low, the craft's attitude will slowly drift. If it is
**The I term** corrects small, long term errors. If it is set too low, the craft's attitude will slowly drift. If it is
set too high, the craft will oscillate (but with slower oscillations than with P being set too high).
The D term attempts to increase system stability by monitoring the rate of change in the error. If the error is
changing slowly (so the P and I terms aren't having enough impact on reaching the target) the D term causes an increase
in the correction in order to reach the target sooner. If the error is rapidly converging to zero, the D term causes the
strength of the correction to be backed off in order to avoid overshooting the target.
**The D term** attempts to increase system stability by monitoring the rate of change in the error. If the error is rapidly converging to zero, the D term causes the strength of the correction to be backed off in order to avoid overshooting the target.
##TPA and TPA Breakpoint
Note that TPA is set via CLI or on the PID TUNING tab of the GUI. tpa_breakpoint is set via CLI
Also note that TPA and tpa_breakpoint may not be used in certain PID Contorllers. Check the description on the individual controller.
TPA applies a PID value reduction in relation to full Throttle. It is used to apply dampening of PID values as full throttle is reached.
**TPA** = % of dampening that will occur at full throttle.
**tpa_breakpoint** = the point in the throttle curve at which TPA will begin to be applied.
An Example: With TPA = 50 (or .5 in the GUI) and tpa_breakpoint = 1500 (assumed throttle range 1000 - 2000)
* At 1500 on the throttle channel, the PIDs will begin to be dampened.
* At 3/4 throttle (1750), PIDs are reduced by approximately 25% (half way between 1500 and 2000 the dampening will be 50% of the total TPA value of 50% in this example)
* At full throttle (2000) the full amount of dampening set in TPA is applied. (50% reduction in this example)
![tpa example chart](https://cloud.githubusercontent.com/assets/1668170/6053290/655255dc-ac92-11e4-9491-1a58d868c131.png "TPA Example Chart")
**How and Why to use this?**
If you are getting oscillations starting at say 3/4 throttle, set tpa breakpoint = 1750 or lower (remember, this is assuming your throttle range is 1000-2000), and then slowly increase TPA until your oscillations are gone. Usually, you will want tpa breakpoint to start a little sooner then when your oscillations start so you'll want to experiment with the values to reduce/remove the oscillations.
## PID controllers
@ -71,6 +96,8 @@ need to be increased in order to perform like PID controller 0.
The LEVEL "D" setting is not used by this controller.
TPA is not used by this controller.
### PID controller 2, "LuxFloat"
PID Controller 2 is Lux's new floating point PID controller. Both controller 0 and 1 use integer arithmetic, which was

8
docs/Safety.md Normal file
View file

@ -0,0 +1,8 @@
# Safety
As many can attest, multirotors and RC models in general can be very dangerous, particularly on the test bench. Here are some simple golden rules to save you a trip to the local ER:
* **NEVER** arm your model with propellers fitted unless you intend to fly!
* **Always** remove your propellers if you are setting up for the first time, flashing firmware, or if in any doubt.
## Feature MOTOR_STOP
The default Cleanflight configuration has the MOTOR_STOP feature DISABLED by default. What this means is that as soon as the controller is armed, the propellers *WILL* begin spinning at low speed. It is recommended that this setting be retained as it provides a good visual indication that the craft is armed. You can read more about arming and setting the MOTOR_STOP feature if desired in the relevant sections of the manual.

View file

@ -47,3 +47,18 @@ http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
### Supported Hardware
NAZE, NAZE32PRO, CJMCU, SPARKY, EUSTM32F103RC, CC3D targets and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug
### Connecting a Spektrum-compatible satellite to a Flip32+ flight controller
The Flip32+ is wired in a rather strange way, i.e. the dedicated connector for the satellite module uses the same UART pins as the USB adapter. This means that you can't use that connector as it maps to UART1 which you really shouldn't assign to SERIAL_RX as that will break USB functionality.
In order to connect the satellite to a Flip32+, you have to wire the serial data pin to RC_CH4. This is the fourth pin from the top in the left column of the 3x6 header on the right side of the board. GND and +3.3V may either be obtained from the dedicated SAT connector or from any ground pin and pin 1 of the BOOT connector which also provides 3.3V.
#### Tested satellite transmitter combinations
| Satellite | Remote | Remark |
| -------------------- | -------------- | ------------------------------------------ |
| Orange R100 | Spektrum DX6i | Bind value 3 |
| Lemon RX DSM2/DSMX | Spektrum DX8 | |
| Lemon RX DSMX | Walkera Devo10 | Deviation firmware 4.01 up to 12 channels |
| Lemon RX DSM2 | Walkera Devo7 | Deviation firmware |

View file

@ -2,6 +2,12 @@
The code can be compiled with debugging information, you can then upload a debug version to a board via a JLink/St-Link debug adapter and step through the code in your IDE.
More information about the necessary hardware can and setting up the eclipse IDE can be found int the wiki:
https://github.com/cleanflight/cleanflight/wiki/Debugging-in-Eclipse
A guide for visual studio can be found here:
http://visualgdb.com/tutorials/arm/st-link/
## Compilation options
use `DEBUG=GDB` make argument.

View file

@ -0,0 +1,46 @@
### IO variables
`gyroData/8192*2000 = deg/s`
`gyroData/4 ~ deg/s`
`rcCommand` - `<-500 - 500>` nominal, but is scaled with `rcRate/100`, max +-1250
`inclination` - in 0.1 degree, default 50 degrees (500)
`axisPID` - output to mixer, will be added to throttle(`<1000-2000>`), output range is `<minthrottle, maxthrottle>` (default `<1150 - 1850>`)
### PID controller 0, "MultiWii" (default)
#### Leveling term
```
error = constrain(2*rcCommand[axis], limit +- max_angle_inclination) - inclination[axis]
P = constrain(P8[PIDLEVEL]/100 * error, limit +- 5 * D8[PIDLEVEL])
I = intergrate(error, limit +-10000) * I8[PIDLEVEL] / 4096
```
#### Gyro term
```
P = rcCommand[axis];
error = rcCommand[axis] * 10 * 8 / pidProfile->P8[axis] - gyroData[axis] / 4; (conversion so that error is in deg/s ?)
I = integrate(error, limit +-16000) / 10 / 8 * I8[axis] / 100 (conversion back to mixer units ?)
```
reset I term if
- axis rotation rate > +-64deg/s
- axis is YAW and rcCommand>+-100
##### Mode dependent mix(yaw is always from gyro)
- HORIZON - proportionally according to max deflection
- gyro - gyro term
- ANGLE - leveling term
#### Gyro stabilization
```
P = -gyroData[axis] / 4 * dynP8 / 10 / 8
D = -mean(diff(gyroData[axis] / 4), over 3 samples) * 3 * dynD8 / 32
```

View file

@ -98,6 +98,7 @@ static void cliProfile(char *cmdline);
static void cliRateProfile(char *cmdline);
static void cliReboot(void);
static void cliSave(char *cmdline);
static void cliServo(char *cmdline);
static void cliSet(char *cmdline);
static void cliGet(char *cmdline);
static void cliStatus(char *cmdline);
@ -212,6 +213,9 @@ const clicmd_t cmdTable[] = {
{ "profile", "index (0 to 2)", cliProfile },
{ "rateprofile", "index (0 to 2)", cliRateProfile },
{ "save", "save and reboot", cliSave },
#ifndef CJMCU
{ "servo", "servo config", cliServo },
#endif
{ "set", "name=value or blank or * for list", cliSet },
{ "status", "show system status", cliStatus },
{ "version", "", cliVersion },
@ -492,14 +496,18 @@ static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *
return ptr;
}
// Check if a string's length is zero
static bool isEmpty(const char *string)
{
return *string == '\0';
}
static void cliAux(char *cmdline)
{
int i, val = 0;
uint8_t len;
char *ptr;
len = strlen(cmdline);
if (len == 0) {
if (isEmpty(cmdline)) {
// print out aux channel settings
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
@ -548,11 +556,9 @@ static void cliAux(char *cmdline)
static void cliAdjustmentRange(char *cmdline)
{
int i, val = 0;
uint8_t len;
char *ptr;
len = strlen(cmdline);
if (len == 0) {
if (isEmpty(cmdline)) {
// print out adjustment ranges channel settings
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
adjustmentRange_t *ar = &currentProfile->adjustmentRanges[i];
@ -627,9 +633,7 @@ static void cliCMix(char *cmdline)
float mixsum[3];
char *ptr;
len = strlen(cmdline);
if (len == 0) {
if (isEmpty(cmdline)) {
cliPrint("Custom mixer: \r\nMotor\tThr\tRoll\tPitch\tYaw\r\n");
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
if (masterConfig.customMixer[i].throttle == 0.0f)
@ -713,12 +717,10 @@ static void cliCMix(char *cmdline)
static void cliLed(char *cmdline)
{
int i;
uint8_t len;
char *ptr;
char ledConfigBuffer[20];
len = strlen(cmdline);
if (len == 0) {
if (isEmpty(cmdline)) {
for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
printf("led %u %s\r\n", i, ledConfigBuffer);
@ -729,7 +731,7 @@ static void cliLed(char *cmdline)
if (i < MAX_LED_STRIP_LENGTH) {
ptr = strchr(cmdline, ' ');
if (!parseLedStripConfig(i, ++ptr)) {
printf("Parse error\r\n", MAX_LED_STRIP_LENGTH);
cliPrint("Parse error\r\n");
}
} else {
printf("Invalid led index: must be < %u\r\n", MAX_LED_STRIP_LENGTH);
@ -740,11 +742,9 @@ static void cliLed(char *cmdline)
static void cliColor(char *cmdline)
{
int i;
uint8_t len;
char *ptr;
len = strlen(cmdline);
if (len == 0) {
if (isEmpty(cmdline)) {
for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
printf("color %u %d,%u,%u\r\n", i, masterConfig.colors[i].h, masterConfig.colors[i].s, masterConfig.colors[i].v);
}
@ -754,7 +754,7 @@ static void cliColor(char *cmdline)
if (i < CONFIGURABLE_COLOR_COUNT) {
ptr = strchr(cmdline, ' ');
if (!parseColor(i, ++ptr)) {
printf("Parse error\r\n", CONFIGURABLE_COLOR_COUNT);
cliPrint("Parse error\r\n");
}
} else {
printf("Invalid color index: must be < %u\r\n", CONFIGURABLE_COLOR_COUNT);
@ -763,6 +763,78 @@ static void cliColor(char *cmdline)
}
#endif
static void cliServo(char *cmdline)
{
#ifdef CJMCU
UNUSED(cmdline);
#else
enum { SERVO_ARGUMENT_COUNT = 6 };
int16_t arguments[SERVO_ARGUMENT_COUNT];
servoParam_t *servo;
int i;
char *ptr;
if (isEmpty(cmdline)) {
// print out servo settings
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
servo = &currentProfile->servoConf[i];
printf("servo %u %d %d %d %d %d\r\n",
i,
servo->min,
servo->max,
servo->middle,
servo->rate,
servo->forwardFromChannel
);
}
} else {
int validArgumentCount = 0;
ptr = cmdline;
// Command line is integers (possibly negative) separated by spaces, no other characters allowed.
// If command line doesn't fit the format, don't modify the config
while (*ptr) {
if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
cliPrint("Parse error\r\n");
return;
}
arguments[validArgumentCount++] = atoi(ptr);
do {
ptr++;
} while (*ptr >= '0' && *ptr <= '9');
} else if (*ptr == ' ') {
ptr++;
} else {
cliPrint("Parse error\r\n");
return;
}
}
// Check we got the right number of args and the servo index is correct (don't validate the other values)
if (validArgumentCount != SERVO_ARGUMENT_COUNT || arguments[0] < 0 || arguments[0] >= MAX_SUPPORTED_SERVOS) {
cliPrint("Parse error\r\n");
return;
}
servo = &currentProfile->servoConf[arguments[0]];
servo->min = arguments[1];
servo->max = arguments[2];
servo->middle = arguments[3];
servo->rate = arguments[4];
servo->forwardFromChannel = arguments[5];
}
#endif
}
#ifdef USE_FLASHFS
static void cliFlashInfo(char *cmdline)
@ -898,11 +970,11 @@ static void cliDump(char *cmdline)
if (dumpMask & DUMP_MASTER) {
printf("\r\n# version\r\n");
cliPrint("\r\n# version\r\n");
cliVersion(NULL);
printf("\r\n# dump master\r\n");
printf("\r\n# mixer\r\n");
cliPrint("\r\n# dump master\r\n");
cliPrint("\r\n# mixer\r\n");
#ifndef USE_QUAD_MIXER_ONLY
printf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
@ -917,23 +989,23 @@ static void cliDump(char *cmdline)
yaw = masterConfig.customMixer[i].yaw;
printf("cmix %d", i + 1);
if (thr < 0)
printf(" ");
cliWrite(' ');
printf("%s", ftoa(thr, buf));
if (roll < 0)
printf(" ");
cliWrite(' ');
printf("%s", ftoa(roll, buf));
if (pitch < 0)
printf(" ");
cliWrite(' ');
printf("%s", ftoa(pitch, buf));
if (yaw < 0)
printf(" ");
cliWrite(' ');
printf("%s\r\n", ftoa(yaw, buf));
}
printf("cmix %d 0 0 0 0\r\n", i + 1);
}
#endif
printf("\r\n\r\n# feature\r\n");
cliPrint("\r\n\r\n# feature\r\n");
mask = featureMask();
for (i = 0; ; i++) { // disable all feature first
@ -948,7 +1020,7 @@ static void cliDump(char *cmdline)
printf("feature %s\r\n", featureNames[i]);
}
printf("\r\n\r\n# map\r\n");
cliPrint("\r\n\r\n# map\r\n");
for (i = 0; i < 8; i++)
buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
@ -956,10 +1028,10 @@ static void cliDump(char *cmdline)
printf("map %s\r\n", buf);
#ifdef LED_STRIP
printf("\r\n\r\n# led\r\n");
cliPrint("\r\n\r\n# led\r\n");
cliLed("");
printf("\r\n\r\n# color\r\n");
cliPrint("\r\n\r\n# color\r\n");
cliColor("");
#endif
printSectionBreak();
@ -967,28 +1039,32 @@ static void cliDump(char *cmdline)
}
if (dumpMask & DUMP_PROFILE) {
printf("\r\n# dump profile\r\n");
cliPrint("\r\n# dump profile\r\n");
printf("\r\n# profile\r\n");
cliPrint("\r\n# profile\r\n");
cliProfile("");
printf("\r\n# aux\r\n");
cliPrint("\r\n# aux\r\n");
cliAux("");
printf("\r\n# adjrange\r\n");
cliPrint("\r\n# adjrange\r\n");
cliAdjustmentRange("");
cliPrint("\r\n# servo\r\n");
cliServo("");
printSectionBreak();
dumpValues(PROFILE_VALUE);
}
if (dumpMask & DUMP_CONTROL_RATE_PROFILE) {
printf("\r\n# dump rates\r\n");
cliPrint("\r\n# dump rates\r\n");
printf("\r\n# rateprofile\r\n");
cliPrint("\r\n# rateprofile\r\n");
cliRateProfile("");
printSectionBreak();
@ -1185,12 +1261,11 @@ static void cliMotor(char *cmdline)
{
int motor_index = 0;
int motor_value = 0;
int len, index = 0;
int index = 0;
char *pch = NULL;
len = strlen(cmdline);
if (len == 0) {
printf("Usage:\r\nmotor index [value] - show [or set] motor value\r\n");
if (isEmpty(cmdline)) {
cliPrint("Usage:\r\nmotor index [value] - show [or set] motor value\r\n");
return;
}
@ -1219,7 +1294,7 @@ static void cliMotor(char *cmdline)
}
if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
printf("Invalid motor value, 1000..2000\r\n");
cliPrint("Invalid motor value, 1000..2000\r\n");
return;
}
@ -1229,11 +1304,9 @@ static void cliMotor(char *cmdline)
static void cliProfile(char *cmdline)
{
uint8_t len;
int i;
len = strlen(cmdline);
if (len == 0) {
if (isEmpty(cmdline)) {
printf("profile %d\r\n", getCurrentProfile());
return;
} else {
@ -1249,11 +1322,9 @@ static void cliProfile(char *cmdline)
static void cliRateProfile(char *cmdline)
{
uint8_t len;
int i;
len = strlen(cmdline);
if (len == 0) {
if (isEmpty(cmdline)) {
printf("rateprofile %d\r\n", getCurrentControlRateProfile());
return;
} else {
@ -1447,7 +1518,7 @@ static void cliGet(char *cmdline)
val = &valueTable[i];
printf("%s = ", valueTable[i].name);
cliPrintVar(val, 0);
printf("\r\n");
cliPrint("\r\n");
matchedCommands++;
}

View file

@ -28,7 +28,7 @@
#define USABLE_TIMER_CHANNEL_COUNT 11
// MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component.
// Using MPU6050 for the moment.
#define GYRO
#define USE_GYRO_MPU6050
@ -39,11 +39,13 @@
#define ACC_MPU6050_ALIGN CW270_DEG
// No baro support.
//#define BARO
//#define USE_BARO_MS5611
#define MAG
#define USE_MAG_AK8975
// No mag support for now (option to use MPU9150 in the future).
//#define MAG
//#define USE_MAG_AK8975
#define MAG_AK8975_ALIGN CW0_DEG_FLIP
@ -51,9 +53,9 @@
#define LED1
#define USE_VCP
#define USE_USART1 // Conn 1 - TX (PB6) RX PB7 (AF7)
#define USE_USART2 // Input - RX (PA3)
#define USE_USART3 // Servo out - 10/RX (PB11) 11/TX (PB10)
#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7)
#define USE_USART2 // Receiver - RX (PA3)
#define USE_USART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
#define SERIAL_PORT_COUNT 4
#define UART1_TX_PIN GPIO_Pin_6 // PB6
@ -63,14 +65,13 @@
#define UART1_TX_PINSOURCE GPIO_PinSource6
#define UART1_RX_PINSOURCE GPIO_PinSource7
#define UART2_TX_PIN GPIO_Pin_2 // PA2 - Clashes with PWM6 input.
#define UART2_TX_PIN GPIO_Pin_2 // PA2
#define UART2_RX_PIN GPIO_Pin_3 // PA3
#define UART2_GPIO GPIOA
#define UART2_GPIO_AF GPIO_AF_7
#define UART2_TX_PINSOURCE GPIO_PinSource2
#define UART2_RX_PINSOURCE GPIO_PinSource3
// Note: PA5 and PA0 are N/C on the sparky - potentially use for ADC or LED STRIP?
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
@ -89,41 +90,8 @@
#define BLACKBOX
#define SERIAL_RX
#define GPS
#define DISPLAY
#define LED_STRIP
#if 1
// LED strip configuration using PWM motor output pin 5.
#define LED_STRIP_TIMER TIM16
#define USE_LED_STRIP_ON_DMA1_CHANNEL3
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource6
#define WS2811_TIMER TIM16
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16
#define WS2811_DMA_CHANNEL DMA1_Channel3
#define WS2811_IRQ DMA1_Channel3_IRQn
#endif
#if 0
// Alternate LED strip pin
// FIXME DMA IRQ Transfer Complete is never called because the TIM17_DMA_RMP needs to be set in SYSCFG_CFGR1
#define LED_STRIP_TIMER TIM17
#define USE_LED_STRIP_ON_DMA1_CHANNEL7
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_1
#define WS2811_PIN GPIO_Pin_7 // TIM17_CH1
#define WS2811_PIN_SOURCE GPIO_PinSource7
#define WS2811_TIMER TIM17
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM17
#define WS2811_DMA_CHANNEL DMA1_Channel7
#define WS2811_IRQ DMA1_Channel7_IRQn
#endif
//#define DISPLAY
#define AUTOTUNE
#define SPEKTRUM_BIND
@ -131,11 +99,11 @@
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
// alternative defaults for AlienWii32 F3 target
#define ALIENWII32
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB12 (Pin 25)
#define BINDPLUG_PORT GPIOB
#define BINDPLUG_PIN Pin_12
// alternative defaults for AlienWii32 F3 target
#define ALIENWII32
#define BRUSHED_MOTORS
#define HARDWARE_BIND_PLUG

View file

@ -163,8 +163,8 @@
#ifdef ALIENWII32
#undef TARGET_BOARD_IDENTIFIER
#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienWii32 F1.
#define BRUSHED_MOTORS
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB5 (Pin 41)
#define BINDPLUG_PORT GPIOB
#define BINDPLUG_PIN Pin_5

View file

@ -39,6 +39,14 @@ TEST(BatteryTest, BatteryADCToVoltage)
batteryConfig_t batteryConfig;
// batteryInit() reads a bunch of fields including vbatscale, so set up the config with useful initial values:
memset(&batteryConfig, 0, sizeof(batteryConfig));
batteryConfig.vbatmaxcellvoltage = 43;
batteryConfig.vbatmincellvoltage = 33;
batteryConfig.vbatwarningcellvoltage = 35;
batteryConfig.vbatscale = VBAT_SCALE_DEFAULT;
batteryInit(&batteryConfig);
batteryAdcToVoltageExpectation_t batteryAdcToVoltageExpectations[] = {