Skip to content

Commit

Permalink
Merge pull request #1374 from iNavFlight/development
Browse files Browse the repository at this point in the history
Release 1.6.1
  • Loading branch information
digitalentity authored Mar 9, 2017
2 parents 0def456 + ea671b1 commit 6c878ae
Show file tree
Hide file tree
Showing 9 changed files with 109 additions and 73 deletions.
2 changes: 1 addition & 1 deletion docs/Board - Paris Air Hero 32 F3.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# Board - Paris Air Hero 32 / Acro Naze 32 Mini

This is the AIR3 PARIS Sirius AirHERO 32 F3 board from MultiWiiCopter
Source: http://www.multiwiicopter.com/products/air-hero-32-f3-spi-flight-controller
Source: http://www.multiwiicopter.com/products/inav-air3-fixed-wing

## Sensors

Expand Down
65 changes: 41 additions & 24 deletions docs/Boards.md
Original file line number Diff line number Diff line change
@@ -1,37 +1,54 @@
# Flight controller hardware

The current focus is geared towards flight controller hardware that use the STM32F303 and legacy STM32F103 series processors. The core logic is separated from the hardware drivers, porting to other processors is possible.
The current focus is geared towards flight controller hardware that use the STM32F3, STM32F4, STM32F7 and legacy STM32F1 series processors. The core logic is separated from the hardware drivers, porting to other processors is possible.

The core set of supported flyable boards are:
### Boards based on F1 CPUs

* AlienWii32
* CC3D
* CJMCU
* Flip32+
* Naze32
* Sparky
* SPRacingF3
* [OpenPilot Revolution](Board%20-%20Revolution.md)
These boards are not recommended for new setups. They are very limited in memory and don't support many features of the INAV. In general F1 boards are limited to only UBLOX GPS protocol, don't have BLHeli Passthrough, don't have LEDSTRIP, only support a few felemetries (LTM and maybe FrSky) etc.

INAV also runs on the following developer boards:
### Boards based on F3/F4/F7 CPUs

* STM32F3Discovery
* Port103R
* EUSTM32F103RB
These boards are powerfull and in general support everything INAV is capable of. Limitations are qute rate and are usually caused by hardware design issues.

There is also limited support for the following boards which may be removed due to lack of users or commercial availability.
### Recommended boards

* Olimexino
* Naze32Pro
* STM32F3Discovery with Chebuzz F3 shield.
These boards are well tested with INAV and are known to be of good quality and reliability.

NOTE: Users are advised against purhasing boards that have CPUs with less than 256KB of EEPROM space - available features may be limited.
NOTE: Hardware developers should not design new boards that have CPUs with less than 256KB EEPROM space.
| Board name | CPU Family | Target name(s) | GPS | Compass | Barometer | Telemetry | RX | Blackbox |
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
| [PARIS Sirius™ AIR3](http://www.multiwiicopter.com/products/inav-air3-fixed-wing) | F3 | AIRHEROF3, AIRHEROF3_QUAD | All | All | All | All | All | SERIAL |
| [Airbot OMNIBUS AIO F3](http://shop.myairbot.com/index.php/flight-control/cleanflight-baseflight/omnibusv11.html) | F3 | OMNIBUS | All | All | All | All | All | SERIAL, SD |
| [Airbot OMNIBUS AIO F4](http://shop.myairbot.com/index.php/flight-control/cleanflight-baseflight/omnibusf4v2.html)| F4 | OMNIBUSF4, OMNIBUSF4PRO | All | All | All | All | All | SERIAL, SD, SPIFLASH |
| [Airbot F4 / Flip F4](http://shop.myairbot.com/index.php/flight-control/apm/airbotf4v1.html) | F4 | AIRBOTF4 | All | All | All | All | All | SERIAL, SPIFLASH |

Each board has it's pros and cons, before purchasing hardware the main thing to check is if the board offers enough serial ports and input/output pins for the hardware you want to use with it and that you can use them at the same time. On some boards some features are mutually exclusive.
### Other supported boards

Please see the board-specific chapters in the manual for wiring details.
These boards work with INAV but might be not well tested or of random quality.

There are off-shoots (forks) of the project that support the STM32F4 processors as found on the Revo and Quanton boards.
| Board name | CPU Family | Target name(s) | GPS | Compass | Barometer | Telemetry | RX | Blackbox |
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
| TBS Colibri Race | F3 | COLIBRI_RACE | All | All | All | All | All | SERIAL |
| FURY F3 | F3 | FURYF3, FURYF3_SPIFLASH | All | All | All | All | All | SERIAL, SD, SPIFLASH |
| RCExplorer F3FC Tricopter | F3 | RCEXPLORERF3 | All | All | All | All | All | SERIAL |
| Taulabs Sparky | F3 | SPARKY | All | All | All | All | All | SERIAL |
| SPRacing F3 | F3 | SPRACINGF3 | All | All | All | All | All | SERIAL, SPIFLASH |
| SPRacing F3 EVO | F3 | SPRACINGF3EVO | All | All | All | All | All | SERIAL, SD |
| SPRacing F3 MINI | F3 | SPRACINGF3MINI | All | All | All | All | All | SERIAL, SD |
| Taulabs Sparky 2 | F4 | SPARKY2, SPARKY2_OPBL | All | All | All | All | All | SERIAL, SPIFLASH |
| Taulabs QUANTON | F4 | QUANTON | All | All | All | All | All | SERIAL, SPIFLASH |
| BlueJay F4 | F4 | BLUEJAYF4 | All | All | All | All | All | SERIAL, SPIFLASH |
| F4BY | F4 | F4BY | All | All | All | All | All | SERIAL, SD |
| OpenPilot REVO | F4 | REVO, REVO_OPBL | All | All | All | All | All | SERIAL, SPIFLASH |

Where applicable the chapters also provide links to other hardware that is known to work with INAV, such as receivers, buzzers, etc.
### Not recommended for new setups

These boards will work with INAV but are either end-of-life, limited on features, rare or hard to get from a reliable source.

| Board name | CPU Family | Target name(s) | GPS | Compass | Barometer | Telemetry | RX | Blackbox |
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
| PARIS Sirius™ AIR HERO | F1 | AIRHERO3 | NMEA | HMC5883 | MS5611, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | SERIAL |
| OpenPilot CC3D | F1 | CC3D, CC3D_PPM1 | NMEA | HMC5883 | BMP085, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | no |
| AfroFlight NAZE32 | F1 | NAZE | NMEA | HMC5883 | MS5611, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | SERIAL, SPIFLASH |
| RMRC Seriously DODO | F3 | RMDO | All | All | All | All | All | SERIAL |
| ANYFC | F4 | ANYFC | All | All | All | All | All | SERIAL |
| YuPiF4 by RcNet | F4 | YUPIF4 | All | All | All | All | All | SERIAL, SD |
37 changes: 20 additions & 17 deletions docs/Cli.md
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ Re-apply any new defaults as desired.
| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude |
| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. |
| nav_mc_auto_disarm_delay | 2000 | |
| nav_fw_cruise_thr | 1400 | Cruise throttle in GPS assisted modes. Should be set high enough to avoid stalling |
| nav_fw_cruise_thr | 1400 | Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addiotional it will increase throttle if GPS speed gets below 7m/s ( hardcoded ) |
| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes |
| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes |
| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll |
Expand Down Expand Up @@ -225,7 +225,7 @@ Re-apply any new defaults as desired.
| align_board_roll | 0 | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc |
| align_board_pitch | 0 | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc |
| align_board_yaw | 0 | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc |
| gyro_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. |
| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. |
| moron_threshold | 32 | 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. |
| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements |
| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements |
Expand Down Expand Up @@ -293,21 +293,24 @@ Re-apply any new defaults as desired.
| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
| nav_alt_p | 50 | P gain of altitude PID controller |
| nav_alt_i | 0 | I gain of altitude PID controller |
| nav_alt_d | 0 | D gain of altitude PID controller |
| nav_vel_p | 100 | P gain of velocity PID controller |
| nav_vel_i | 50 | I gain of velocity PID controller |
| nav_vel_d | 10 | D gain of velocity PID controller |
| nav_pos_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity |
| nav_pos_i | 120 | Controls deceleration time. Measured in 1/100 sec. Expected hold position is placed at a distance calculated as decelerationTime * currentVelocity |
| nav_pos_d | 10 | |
| nav_posr_p | 180 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations |
| nav_posr_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot |
| nav_posr_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. |
| nav_navr_p | 10 | P gain of 2D trajectory PID controller. Play with this to get a straigh line between waypoints or a straight RTH |
| nav_navr_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tunning with zero |
| nav_navr_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tunning with zero |
| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) |
| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixdwing) |
| nav_mc_pos_z_i | 0 | I gain of altitude PID controller (Multirotor) |
| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixdwing) |
| nav_mc_pos_z_d | 0 | D gain of altitude PID controller (Multirotor) |
| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixdwing) |
| nav_mc_vel_z_p | 100 | P gain of velocity PID controller |
| nav_mc_vel_z_i | 50 | I gain of velocity PID controller |
| nav_mc_vel_z_d | 10 | D gain of velocity PID controller |
| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity |
| nav_mc_pos_xy_i | 120 | Controls deceleration time. Measured in 1/100 sec. Expected hold position is placed at a distance calculated as decelerationTime * currentVelocity |
| nav_mc_pos_xy_d | 10 | |
| nav_mc_vel_xy_p | 180 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations |
| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot |
| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. |
| nav_fw_pos_xy_p | 10 | P gain of 2D trajectory PID controller. Play with this to get a straigh line between waypoints or a straight RTH |
| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tunning with zero |
| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tunning with zero |
| deadband | 5 | 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. |
| yaw_deadband | 5 | 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. |
| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. |
Expand Down
10 changes: 5 additions & 5 deletions docs/Mixer.md
Original file line number Diff line number Diff line change
Expand Up @@ -230,10 +230,10 @@ mmix 0 1.0 0.0 0.0 0.3 # Left Engine
mmix 1 1.0 0.0 0.0 -0.3 # Right Engine
smix reset
# Rule Servo Source Rate Speed Min Max Box
smix 0 3 0 100 0 0 100 0 # Roll / Aileron
smix 1 4 0 100 0 0 100 0 # Roll / Aileron
smix 3 5 2 100 0 0 100 0 # Yaw / Rudder
smix 2 2 1 100 0 0 100 0 # Pitch / Elevator
# Rule Servo Source Rate Speed Min Max
smix 0 3 0 100 0 0 100 # Roll / Aileron
smix 1 4 0 100 0 0 100 # Roll / Aileron
smix 3 5 2 100 0 0 100 # Yaw / Rudder
smix 2 2 1 100 0 0 100 # Pitch / Elevator
```
2 changes: 1 addition & 1 deletion src/main/build/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#define FC_VERSION_MAJOR 1 // increment when a major release is made (big new feature, etc)
#define FC_VERSION_MINOR 6 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
#define FC_VERSION_PATCH_LEVEL 1 // increment when a bug is fixed

#define STR_HELPER(x) #x
#define STR(x) STR_HELPER(x)
Expand Down
1 change: 1 addition & 0 deletions src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -602,6 +602,7 @@ static const clivalue_t valueTable[] = {
{ "failsafe_recovery_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_recovery_delay) },
{ "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_off_delay) },
{ "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_kill_switch) },
{ "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1000, 2000 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_throttle) },
{ "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 300 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_throttle_low_delay) },
{ "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE_PROCEDURE }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_procedure) },
{ "failsafe_stick_threshold", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 500 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_stick_motion_threshold) },
Expand Down
Loading

0 comments on commit 6c878ae

Please sign in to comment.