mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 09:45:33 +03:00
commit
814dc4924c
109 changed files with 4296 additions and 522 deletions
1
AUTHORS
1
AUTHORS
|
@ -7,6 +7,7 @@ Alberto García Hierro
|
|||
Alex Gorbatchev
|
||||
Alex Zaitsev
|
||||
Alexander Fedorov
|
||||
Alexander van Saase
|
||||
Alexey Stankevich
|
||||
Andre Bernet
|
||||
Andreas Tacke
|
||||
|
|
|
@ -29,7 +29,7 @@ else()
|
|||
include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake")
|
||||
endif()
|
||||
|
||||
project(INAV VERSION 2.7.0)
|
||||
project(INAV VERSION 3.0.0)
|
||||
|
||||
enable_language(ASM)
|
||||
|
||||
|
|
|
@ -39,7 +39,7 @@ Tool for Blackbox logs analysis is available [here](https://github.com/iNavFligh
|
|||
|
||||
### Telemetry screen for OpenTX
|
||||
|
||||
Users of FrSky Taranis X9 and Q X7 can use INAV Lua Telemetry screen created by @teckel12 . Software and installation instruction are available here: [https://github.com/iNavFlight/LuaTelemetry](https://github.com/iNavFlight/LuaTelemetry)
|
||||
Users of OpenTX radios (Taranis, Horus, Jumper, Radiomaster, Nirvana) can use INAV OpenTX Telemetry Widget screen. Software and installation instruction are available here: [https://github.com/iNavFlight/OpenTX-Telemetry-Widget](https://github.com/iNavFlight/OpenTX-Telemetry-Widget)
|
||||
|
||||
## Installation
|
||||
|
||||
|
|
|
@ -97,8 +97,6 @@ function(target_stm32f7xx)
|
|||
VCP_SOURCES ${STM32F7_USB_SRC} ${STM32F7_VCP_SRC}
|
||||
VCP_INCLUDE_DIRECTORIES ${STM32F7_USB_INCLUDE_DIRS} ${STM32F7_VCP_DIR}
|
||||
|
||||
OPTIMIZATION -O2
|
||||
|
||||
OPENOCD_TARGET stm32f7x
|
||||
|
||||
BOOTLOADER
|
||||
|
@ -112,6 +110,11 @@ macro(define_target_stm32f7 subfamily size)
|
|||
set(func_ARGV ARGV)
|
||||
string(TOUPPER ${size} upper_size)
|
||||
get_stm32_flash_size(flash_size ${size})
|
||||
if(flash_size GREATER 512)
|
||||
set(opt -O2)
|
||||
else()
|
||||
set(opt -Os)
|
||||
endif()
|
||||
set(definitions
|
||||
STM32F7
|
||||
STM32F7${subfamily}xx
|
||||
|
@ -123,6 +126,8 @@ macro(define_target_stm32f7 subfamily size)
|
|||
STARTUP startup_stm32f7${subfamily}xx.s
|
||||
COMPILE_DEFINITIONS ${definitions}
|
||||
LINKER_SCRIPT stm32_flash_f7${subfamily}x${size}
|
||||
OPTIMIZATION ${opt}
|
||||
|
||||
${${func_ARGV}}
|
||||
)
|
||||
endfunction()
|
||||
|
|
|
@ -43,6 +43,8 @@ Sequences:
|
|||
14 DISARM_REPEAT 0, 100, 10 Stick held in disarm position (after pause)
|
||||
15 ARMED 0, 245, 10, 5 Board is armed (after pause ; repeats until board is disarmed or throttle is increased)
|
||||
|
||||
You can use [this tool](https://www.mrd-rc.com/tutorials-tools-and-testing/useful-tools/helpful-inav-buzzer-code-checker/) to hear current buzzer sequences or enter custom sequences.
|
||||
|
||||
## Controlling buzzer usage
|
||||
|
||||
The usage of the buzzer can be controlled by the CLI `beeper` command.
|
||||
|
|
|
@ -71,6 +71,9 @@ IPF can be edited using INAV Configurator user interface, of via CLI
|
|||
| 35 | TAN | Computes TAN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
|
||||
| 36 | MAP_INPUT | Scales `Operand A` from [`0` : `Operand B`] to [`0` : `1000`]. Note: input will be constrained and then scaled |
|
||||
| 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled |
|
||||
| 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B` |
|
||||
| 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. |
|
||||
| 40 | MOD | Divide `Operand A` by `Operand B` and returns the remainder |
|
||||
|
||||
|
||||
### Operands
|
||||
|
@ -93,8 +96,8 @@ IPF can be edited using INAV Configurator user interface, of via CLI
|
|||
| 1 | HOME_DISTANCE | in `meters` |
|
||||
| 2 | TRIP_DISTANCE | in `meters` |
|
||||
| 3 | RSSI | |
|
||||
| 4 | VBAT | in `Volts * 10`, eg. `12.1V` is `121` |
|
||||
| 5 | CELL_VOLTAGE | in `Volts * 10`, eg. `12.1V` is `121` |
|
||||
| 4 | VBAT | in `Volts * 100`, eg. `12.1V` is `1210` |
|
||||
| 5 | CELL_VOLTAGE | in `Volts * 100`, eg. `12.1V` is `1210` |
|
||||
| 6 | CURRENT | in `Amps * 100`, eg. `9A` is `900` |
|
||||
| 7 | MAH_DRAWN | in `mAh` |
|
||||
| 8 | GPS_SATS | |
|
||||
|
@ -123,6 +126,7 @@ IPF can be edited using INAV Configurator user interface, of via CLI
|
|||
| 31 | 3D HOME_DISTANCE | in `meters`, calculated from HOME_DISTANCE and ALTITUDE using Pythagorean theorem |
|
||||
| 32 | CROSSFIRE LQ | Crossfire Link quality as returned by the CRSF protocol |
|
||||
| 33 | CROSSFIRE SNR | Crossfire SNR as returned by the CRSF protocol |
|
||||
| 34 | GPS_VALID | boolean `0`/`1`. True when the GPS has a valid 3D Fix |
|
||||
|
||||
#### ACTIVE_WAYPOINT_ACTION
|
||||
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| airmode_throttle_threshold | 1300 | Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used |
|
||||
| airmode_type | STICK_CENTER | Defines the Airmode state handling type. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `airmode_throttle_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER_ONCE** or **STICK_CENTER** modes. |
|
||||
| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 |
|
||||
| align_acc | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
|
||||
| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
|
||||
|
@ -62,6 +64,7 @@
|
|||
| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. |
|
||||
| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON |
|
||||
| dji_esc_temp_source | ESC | Re-purpose the ESC temperature field for IMU/BARO temperature |
|
||||
| dji_speed_source | GROUND | Sets the speed type displayed by the DJI OSD: GROUND, 3D, AIR |
|
||||
| dji_use_name_for_messages | ON | Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance |
|
||||
| dji_workarounds | | Enables workarounds for different versions of MSP protocol used |
|
||||
| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter |
|
||||
|
@ -79,7 +82,7 @@
|
|||
| eleres_signature | | |
|
||||
| eleres_telemetry_en | | |
|
||||
| eleres_telemetry_power | | |
|
||||
| esc_sensor_listen_only | | |
|
||||
| esc_sensor_listen_only | OFF | Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case |
|
||||
| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). |
|
||||
| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb |
|
||||
| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll |
|
||||
|
@ -98,6 +101,7 @@
|
|||
| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout |
|
||||
| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. |
|
||||
| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. |
|
||||
| flip_over_after_crash_power_factor | 65 | flip over after crash power factor |
|
||||
| fpv_mix_degrees | | |
|
||||
| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
|
||||
| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
|
||||
|
@ -111,6 +115,9 @@
|
|||
| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection |
|
||||
| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot |
|
||||
| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point |
|
||||
| fw_d_pitch | 0 | Fixed wing rate stabilisation D-gain for PITCH |
|
||||
| fw_d_roll | 0 | Fixed wing rate stabilisation D-gain for ROLL |
|
||||
| fw_d_yaw | 0 | Fixed wing rate stabilisation D-gain for YAW |
|
||||
| fw_ff_pitch | 50 | Fixed-wing rate stabilisation FF-gain for PITCH |
|
||||
| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL |
|
||||
| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW |
|
||||
|
@ -120,6 +127,7 @@
|
|||
| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW |
|
||||
| fw_iterm_limit_stick_position | 0.5 | Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side |
|
||||
| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. |
|
||||
| fw_level_pitch_trim | 0 | Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level |
|
||||
| fw_loiter_direction | RIGHT | Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. |
|
||||
| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) |
|
||||
| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain |
|
||||
|
@ -130,6 +138,7 @@
|
|||
| fw_tpa_time_constant | 0 | TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups |
|
||||
| fw_turn_assist_pitch_gain | 1 | Gain required to keep constant pitch angle during coordinated turns (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter |
|
||||
| fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter |
|
||||
| fw_yaw_iterm_freeze_bank_angle | 0 | Yaw Iterm is frozen when bank angle is above this threshold [degrees]. This solves the problem of the rudder counteracting turns by partially disabling yaw stabilization when making banked turns. Setting to 0 (the default) disables this feature. Only applies when autopilot is not active and TURN ASSIST is disabled. |
|
||||
| gps_auto_baud | ON | Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports |
|
||||
| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. |
|
||||
| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. |
|
||||
|
@ -140,7 +149,7 @@
|
|||
| gyro_dyn_lpf_curve_expo | 5 | Expo value for the throttle-to-frequency mapping for Dynamic LPF |
|
||||
| gyro_dyn_lpf_max_hz | 500 | Maximum frequency of the gyro Dynamic LPF |
|
||||
| gyro_dyn_lpf_min_hz | 200 | Minimum frequency of the gyro Dynamic LPF |
|
||||
| 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. |
|
||||
| gyro_hardware_lpf | 256HZ | Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first. |
|
||||
| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
|
||||
| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
|
||||
| gyro_notch_cutoff | | |
|
||||
|
@ -216,8 +225,6 @@
|
|||
| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° |
|
||||
| max_check | 1900 | 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. |
|
||||
| max_throttle | 1850 | This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000. |
|
||||
| mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used |
|
||||
| mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode. |
|
||||
| mc_cd_lpf_hz | 30 | Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky |
|
||||
| mc_cd_pitch | 60 | Multicopter Control Derivative gain for PITCH |
|
||||
| mc_cd_roll | 60 | Multicopter Control Derivative gain for ROLL |
|
||||
|
@ -244,7 +251,7 @@
|
|||
| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] |
|
||||
| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] |
|
||||
| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. |
|
||||
| motor_poles | | |
|
||||
| motor_poles | 14 | The number of motor poles. Required to compute motor RPM |
|
||||
| motor_pwm_protocol | ONESHOT125 | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED |
|
||||
| motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. |
|
||||
| msp_override_channels | 0 | Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode. |
|
||||
|
@ -277,7 +284,7 @@
|
|||
| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) |
|
||||
| nav_fw_launch_timeout | 5000 | Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) |
|
||||
| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] |
|
||||
| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] |
|
||||
| nav_fw_loiter_radius | 7500 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] |
|
||||
| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes |
|
||||
| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes |
|
||||
| nav_fw_pitch2thr | 10 | Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) |
|
||||
|
@ -299,7 +306,7 @@
|
|||
| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] |
|
||||
| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] |
|
||||
| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] |
|
||||
| nav_max_terrain_follow_alt | | |
|
||||
| nav_max_terrain_follow_alt | 100 | Max allowed above the ground altitude for terrain following mode |
|
||||
| nav_mc_auto_disarm_delay | 2000 | Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s) |
|
||||
| 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_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode |
|
||||
|
@ -327,6 +334,7 @@
|
|||
| nav_mc_vel_z_d | 10 | D gain of velocity PID controller |
|
||||
| nav_mc_vel_z_i | 50 | I gain of velocity PID controller |
|
||||
| nav_mc_vel_z_p | 100 | P gain of velocity PID controller |
|
||||
| nav_mc_wp_slowdown | ON | When ON, NAV engine will slow down when switching to the next waypoint. This prioritizes turning over forward movement. When OFF, NAV engine will continue to the next waypoint and turn as it goes. |
|
||||
| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. |
|
||||
| nav_overrides_motor_stop | ALL_NAV | When set to OFF the navigation system will not take over the control of the motor if the throttle is low (motor will stop). When set to OFF_ALWAYS the navigation system will not take over the control of the motor if the throttle was low even when failsafe is triggered. When set to AUTO_ONLY the navigation system will only take over the control of the throttle in autonomous navigation modes (NAV WP and NAV RTH). When set to ALL_NAV (default) the navigation system will take over the control of the motor completely and never allow the motor to stop even when the throttle is low. This setting only has an effect on NAV modes which take control of the throttle when combined with MOTOR_STOP and is likely to cause a stall if fw_min_throttle_down_pitch isn't set correctly or the pitch estimation is wrong for fixed wing models when not set to ALL_NAV |
|
||||
| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) |
|
||||
|
@ -389,6 +397,8 @@
|
|||
| osd_link_quality_alarm | 70 | LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50% |
|
||||
| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. |
|
||||
| osd_neg_alt_alarm | 5 | Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_pan_servo_index | | Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos. |
|
||||
| osd_pan_servo_pwm2centideg | 0 | Centidegrees of pan servo rotation us PWM signal. A servo with 180 degrees of rotation from 1000 to 2000 us PWM typically needs `18` for this setting. Change sign to inverse direction. |
|
||||
| osd_plus_code_digits | 10 | Numer of plus code digits before shortening with `osd_plus_code_short`. Precision at the equator: 10=13.9x13.9m; 11=2.8x3.5m; 12=56x87cm; 13=11x22cm. |
|
||||
| osd_plus_code_short | 0 | Number of leading digits removed from plus code. Removing 2, 4 and 6 digits requires a reference location within, respectively, ~800km, ~40 km and ~2km to recover the original coordinates. |
|
||||
| osd_right_sidebar_scroll | | |
|
||||
|
@ -406,10 +416,10 @@
|
|||
| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` |
|
||||
| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
|
||||
| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
|
||||
| pinio_box1 | | |
|
||||
| pinio_box2 | | |
|
||||
| pinio_box3 | | |
|
||||
| pinio_box4 | | |
|
||||
| pinio_box1 | target specific | Mode assignment for PINIO#1 |
|
||||
| pinio_box2 | target specific | Mode assignment for PINIO#1 |
|
||||
| pinio_box3 | target specific | Mode assignment for PINIO#1 |
|
||||
| pinio_box4 | target specific | Mode assignment for PINIO#1 |
|
||||
| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
|
||||
| pitot_hardware | NONE | Selection of pitot hardware. |
|
||||
| pitot_lpf_milli_hz | | |
|
||||
|
@ -501,6 +511,7 @@
|
|||
| vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities |
|
||||
| vtx_pit_mode_chan | | |
|
||||
| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. |
|
||||
| vtx_smartaudio_early_akk_workaround | ON | Enable workaround for early AKK SAudio-enabled VTX bug. |
|
||||
| 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. |
|
||||
| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) |
|
||||
| yaw_rate | 20 | Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
|
||||
|
|
|
@ -123,7 +123,7 @@ The following sensors are transmitted
|
|||
* **0450** : 'Flight Path Vector' or 'Course over ground' in degrees*10
|
||||
### Compatible SmartPort/INAV telemetry flight status
|
||||
|
||||
To quickly and easily monitor these SmartPort sensors and flight modes, install [iNav LuaTelemetry](https://github.com/iNavFlight/LuaTelemetry) to your Taranis Q X7, X9D, X9D+ or X9E transmitter.
|
||||
To quickly and easily monitor these SmartPort sensors and flight modes, install [OpenTX Telemetry Widget](https://github.com/iNavFlight/OpenTX-Telemetry-Widget) to your Taranis Q X7, X9D, X9D+ or X9E transmitter.
|
||||
|
||||
## FrSky telemetry
|
||||
|
||||
|
|
|
@ -69,7 +69,7 @@ For 2.6 and later, inav uses `cmake` as its primary build tool. `cmake` simplies
|
|||
|
||||
## Using `cmake`
|
||||
|
||||
The canonanical method of using `cmake` is to create a `build` directory and run the `cmake` and `make` commands from within the `build` directory. So, assuming we've cloned the firmware repository into an `inav` directory, we can issue the following commands to set up the build environment.
|
||||
The canonical method of using `cmake` is to create a `build` directory and run the `cmake` and `make` commands from within the `build` directory. So, assuming we've cloned the firmware repository into an `inav` directory, we can issue the following commands to set up the build environment.
|
||||
|
||||
```
|
||||
cd inav
|
||||
|
|
|
@ -24,6 +24,8 @@ main_sources(COMMON_SRC
|
|||
common/encoding.h
|
||||
common/filter.c
|
||||
common/filter.h
|
||||
common/fp_pid.c
|
||||
common/fp_pid.h
|
||||
common/gps_conversion.c
|
||||
common/gps_conversion.h
|
||||
common/log.c
|
||||
|
@ -46,6 +48,8 @@ main_sources(COMMON_SRC
|
|||
common/typeconversion.h
|
||||
common/uvarint.c
|
||||
common/uvarint.h
|
||||
common/circular_queue.c
|
||||
common/circular_queue.h
|
||||
|
||||
config/config_eeprom.c
|
||||
config/config_eeprom.h
|
||||
|
@ -71,6 +75,8 @@ main_sources(COMMON_SRC
|
|||
drivers/accgyro/accgyro_adxl345.h
|
||||
drivers/accgyro/accgyro_bma280.c
|
||||
drivers/accgyro/accgyro_bma280.h
|
||||
drivers/accgyro/accgyro_bmi088.c
|
||||
drivers/accgyro/accgyro_bmi088.h
|
||||
drivers/accgyro/accgyro_bmi160.c
|
||||
drivers/accgyro/accgyro_bmi160.h
|
||||
drivers/accgyro/accgyro_fake.c
|
||||
|
@ -150,6 +156,8 @@ main_sources(COMMON_SRC
|
|||
drivers/compass/compass_mpu9250.h
|
||||
drivers/compass/compass_qmc5883l.c
|
||||
drivers/compass/compass_qmc5883l.h
|
||||
drivers/compass/compass_rm3100.c
|
||||
drivers/compass/compass_rm3100.h
|
||||
drivers/compass/compass_msp.c
|
||||
drivers/compass/compass_msp.h
|
||||
|
||||
|
@ -224,6 +232,8 @@ main_sources(COMMON_SRC
|
|||
drivers/rangefinder/rangefinder_srf10.h
|
||||
drivers/rangefinder/rangefinder_vl53l0x.c
|
||||
drivers/rangefinder/rangefinder_vl53l0x.h
|
||||
drivers/rangefinder/rangefinder_vl53l1x.c
|
||||
drivers/rangefinder/rangefinder_vl53l1x.h
|
||||
drivers/rangefinder/rangefinder_virtual.c
|
||||
drivers/rangefinder/rangefinder_virtual.h
|
||||
|
||||
|
|
|
@ -80,5 +80,6 @@ typedef enum {
|
|||
DEBUG_SPM_VARIO, // Smartport master variometer
|
||||
DEBUG_PCF8574,
|
||||
DEBUG_DYNAMIC_GYRO_LPF,
|
||||
DEBUG_FW_D,
|
||||
DEBUG_COUNT
|
||||
} debugType_e;
|
||||
|
|
|
@ -55,7 +55,7 @@
|
|||
#define RPY_PIDFF_MAX 200
|
||||
#define OTHER_PIDDF_MAX 255
|
||||
|
||||
#define PIDFF_ENTRY(label, ptr, max) OSD_UINT8_ENTRY(label, (&(const OSD_UINT16_t){ ptr, PIDFF_MIN, max, PIDFF_STEP }))
|
||||
#define PIDFF_ENTRY(label, ptr, max) OSD_UINT16_ENTRY(label, (&(const OSD_UINT16_t){ ptr, PIDFF_MIN, max, PIDFF_STEP }))
|
||||
#define RPY_PIDFF_ENTRY(label, ptr) PIDFF_ENTRY(label, ptr, RPY_PIDFF_MAX)
|
||||
#define OTHER_PIDFF_ENTRY(label, ptr) PIDFF_ENTRY(label, ptr, OTHER_PIDDF_MAX)
|
||||
|
||||
|
|
|
@ -47,6 +47,7 @@ static const OSD_Entry menuMiscEntries[]=
|
|||
OSD_SETTING_ENTRY("OSD VOLT DECIMALS", SETTING_OSD_MAIN_VOLTAGE_DECIMALS),
|
||||
OSD_SETTING_ENTRY("STATS ENERGY UNIT", SETTING_OSD_STATS_ENERGY_UNIT),
|
||||
#endif
|
||||
OSD_SETTING_ENTRY("FS PROCEDURE", SETTING_FAILSAFE_PROCEDURE),
|
||||
|
||||
OSD_BACK_AND_END_ENTRY,
|
||||
};
|
||||
|
|
66
src/main/common/circular_queue.c
Normal file
66
src/main/common/circular_queue.c
Normal file
|
@ -0,0 +1,66 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include "circular_queue.h"
|
||||
|
||||
void circularBufferInit(circularBuffer_t *circular_buffer, uint8_t *buffer, size_t buffer_size,
|
||||
size_t buffer_element_size) {
|
||||
circular_buffer->buffer = buffer;
|
||||
circular_buffer->bufferSize = buffer_size;
|
||||
circular_buffer->elementSize = buffer_element_size;
|
||||
circular_buffer->head = 0;
|
||||
circular_buffer->tail = 0;
|
||||
circular_buffer->size = 0;
|
||||
}
|
||||
|
||||
void circularBufferPushElement(circularBuffer_t *circularBuffer, uint8_t *element) {
|
||||
if (circularBufferIsFull(circularBuffer))
|
||||
return;
|
||||
|
||||
memcpy(circularBuffer->buffer + circularBuffer->tail, element, circularBuffer->elementSize);
|
||||
|
||||
circularBuffer->tail += circularBuffer->elementSize;
|
||||
circularBuffer->tail %= circularBuffer->bufferSize;
|
||||
circularBuffer->size += 1;
|
||||
}
|
||||
|
||||
void circularBufferPopHead(circularBuffer_t *circularBuffer, uint8_t *element) {
|
||||
memcpy(element, circularBuffer->buffer + circularBuffer->head, circularBuffer->elementSize);
|
||||
|
||||
circularBuffer->head += circularBuffer->elementSize;
|
||||
circularBuffer->head %= circularBuffer->bufferSize;
|
||||
circularBuffer->size -= 1;
|
||||
}
|
||||
|
||||
int circularBufferIsFull(circularBuffer_t *circularBuffer) {
|
||||
return circularBufferCountElements(circularBuffer) * circularBuffer->elementSize == circularBuffer->bufferSize;
|
||||
}
|
||||
|
||||
int circularBufferIsEmpty(circularBuffer_t *circularBuffer) {
|
||||
return circularBuffer==NULL || circularBufferCountElements(circularBuffer) == 0;
|
||||
}
|
||||
|
||||
size_t circularBufferCountElements(circularBuffer_t *circularBuffer) {
|
||||
return circularBuffer->size;
|
||||
}
|
47
src/main/common/circular_queue.h
Normal file
47
src/main/common/circular_queue.h
Normal file
|
@ -0,0 +1,47 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#ifndef INAV_CIRCULAR_QUEUE_H
|
||||
#define INAV_CIRCULAR_QUEUE_H
|
||||
|
||||
#include "stdint.h"
|
||||
#include "string.h"
|
||||
|
||||
typedef struct circularBuffer_s{
|
||||
size_t head;
|
||||
size_t tail;
|
||||
size_t bufferSize;
|
||||
uint8_t * buffer;
|
||||
size_t elementSize;
|
||||
size_t size;
|
||||
}circularBuffer_t;
|
||||
|
||||
void circularBufferInit(circularBuffer_t * circularBuffer, uint8_t * buffer, size_t bufferSize, size_t bufferElementSize);
|
||||
void circularBufferPushElement(circularBuffer_t * circularBuffer, uint8_t * element);
|
||||
void circularBufferPopHead(circularBuffer_t * circularBuffer, uint8_t * element);
|
||||
int circularBufferIsFull(circularBuffer_t * circularBuffer);
|
||||
int circularBufferIsEmpty(circularBuffer_t *circularBuffer);
|
||||
size_t circularBufferCountElements(circularBuffer_t * circularBuffer);
|
||||
|
||||
#endif //INAV_CIRCULAR_QUEUE_H
|
156
src/main/common/fp_pid.c
Normal file
156
src/main/common/fp_pid.c
Normal file
|
@ -0,0 +1,156 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
FILE_COMPILE_FOR_SPEED
|
||||
|
||||
#include <math.h>
|
||||
#include "common/fp_pid.h"
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Float point PID-controller implementation
|
||||
*-----------------------------------------------------------*/
|
||||
// Implementation of PID with back-calculation I-term anti-windup
|
||||
// Control System Design, Lecture Notes for ME 155A by Karl Johan Åström (p.228)
|
||||
// http://www.cds.caltech.edu/~murray/courses/cds101/fa02/caltech/astrom-ch6.pdf
|
||||
float navPidApply3(
|
||||
pidController_t *pid,
|
||||
const float setpoint,
|
||||
const float measurement,
|
||||
const float dt,
|
||||
const float outMin,
|
||||
const float outMax,
|
||||
const pidControllerFlags_e pidFlags,
|
||||
const float gainScaler,
|
||||
const float dTermScaler
|
||||
) {
|
||||
float newProportional, newDerivative, newFeedForward;
|
||||
float error = setpoint - measurement;
|
||||
|
||||
/* P-term */
|
||||
newProportional = error * pid->param.kP * gainScaler;
|
||||
|
||||
/* D-term */
|
||||
if (pid->reset) {
|
||||
pid->last_input = (pidFlags & PID_DTERM_FROM_ERROR) ? error : measurement;
|
||||
pid->reset = false;
|
||||
}
|
||||
|
||||
if (pidFlags & PID_DTERM_FROM_ERROR) {
|
||||
/* Error-tracking D-term */
|
||||
newDerivative = (error - pid->last_input) / dt;
|
||||
pid->last_input = error;
|
||||
} else {
|
||||
/* Measurement tracking D-term */
|
||||
newDerivative = -(measurement - pid->last_input) / dt;
|
||||
pid->last_input = measurement;
|
||||
}
|
||||
|
||||
if (pid->dTermLpfHz > 0) {
|
||||
newDerivative = pid->param.kD * pt1FilterApply4(&pid->dterm_filter_state, newDerivative, pid->dTermLpfHz, dt);
|
||||
} else {
|
||||
newDerivative = pid->param.kD * newDerivative;
|
||||
}
|
||||
|
||||
newDerivative = newDerivative * gainScaler * dTermScaler;
|
||||
|
||||
if (pidFlags & PID_ZERO_INTEGRATOR) {
|
||||
pid->integrator = 0.0f;
|
||||
}
|
||||
|
||||
/*
|
||||
* Compute FeedForward parameter
|
||||
*/
|
||||
newFeedForward = setpoint * pid->param.kFF * gainScaler;
|
||||
|
||||
/* Pre-calculate output and limit it if actuator is saturating */
|
||||
const float outVal = newProportional + (pid->integrator * gainScaler) + newDerivative + newFeedForward;
|
||||
const float outValConstrained = constrainf(outVal, outMin, outMax);
|
||||
|
||||
pid->proportional = newProportional;
|
||||
pid->integral = pid->integrator;
|
||||
pid->derivative = newDerivative;
|
||||
pid->feedForward = newFeedForward;
|
||||
pid->output_constrained = outValConstrained;
|
||||
|
||||
/* Update I-term */
|
||||
if (!(pidFlags & PID_ZERO_INTEGRATOR)) {
|
||||
const float newIntegrator = pid->integrator + (error * pid->param.kI * gainScaler * dt) + ((outValConstrained - outVal) * pid->param.kT * dt);
|
||||
|
||||
if (pidFlags & PID_SHRINK_INTEGRATOR) {
|
||||
// Only allow integrator to shrink
|
||||
if (fabsf(newIntegrator) < fabsf(pid->integrator)) {
|
||||
pid->integrator = newIntegrator;
|
||||
}
|
||||
}
|
||||
else {
|
||||
pid->integrator = newIntegrator;
|
||||
}
|
||||
}
|
||||
|
||||
if (pidFlags & PID_LIMIT_INTEGRATOR) {
|
||||
pid->integrator = constrainf(pid->integrator, outMin, outMax);
|
||||
}
|
||||
|
||||
return outValConstrained;
|
||||
}
|
||||
|
||||
float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags)
|
||||
{
|
||||
return navPidApply3(pid, setpoint, measurement, dt, outMin, outMax, pidFlags, 1.0f, 1.0f);
|
||||
}
|
||||
|
||||
void navPidReset(pidController_t *pid)
|
||||
{
|
||||
pid->reset = true;
|
||||
pid->proportional = 0.0f;
|
||||
pid->integral = 0.0f;
|
||||
pid->derivative = 0.0f;
|
||||
pid->integrator = 0.0f;
|
||||
pid->last_input = 0.0f;
|
||||
pid->feedForward = 0.0f;
|
||||
pt1FilterReset(&pid->dterm_filter_state, 0.0f);
|
||||
pid->output_constrained = 0.0f;
|
||||
}
|
||||
|
||||
void navPidInit(pidController_t *pid, float _kP, float _kI, float _kD, float _kFF, float _dTermLpfHz)
|
||||
{
|
||||
pid->param.kP = _kP;
|
||||
pid->param.kI = _kI;
|
||||
pid->param.kD = _kD;
|
||||
pid->param.kFF = _kFF;
|
||||
|
||||
if (_kI > 1e-6f && _kP > 1e-6f) {
|
||||
float Ti = _kP / _kI;
|
||||
float Td = _kD / _kP;
|
||||
pid->param.kT = 2.0f / (Ti + Td);
|
||||
}
|
||||
else {
|
||||
pid->param.kI = 0.0;
|
||||
pid->param.kT = 0.0;
|
||||
}
|
||||
pid->dTermLpfHz = _dTermLpfHz;
|
||||
navPidReset(pid);
|
||||
}
|
75
src/main/common/fp_pid.h
Normal file
75
src/main/common/fp_pid.h
Normal file
|
@ -0,0 +1,75 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
typedef struct {
|
||||
float kP;
|
||||
float kI;
|
||||
float kD;
|
||||
float kT; // Tracking gain (anti-windup)
|
||||
float kFF; // FeedForward Component
|
||||
} pidControllerParam_t;
|
||||
|
||||
typedef enum {
|
||||
PID_DTERM_FROM_ERROR = 1 << 0,
|
||||
PID_ZERO_INTEGRATOR = 1 << 1,
|
||||
PID_SHRINK_INTEGRATOR = 1 << 2,
|
||||
PID_LIMIT_INTEGRATOR = 1 << 3,
|
||||
} pidControllerFlags_e;
|
||||
|
||||
typedef struct {
|
||||
bool reset;
|
||||
pidControllerParam_t param;
|
||||
pt1Filter_t dterm_filter_state; // last derivative for low-pass filter
|
||||
float dTermLpfHz; // dTerm low pass filter cutoff frequency
|
||||
float integrator; // integrator value
|
||||
float last_input; // last input for derivative
|
||||
|
||||
float integral; // used integral value in output
|
||||
float proportional; // used proportional value in output
|
||||
float derivative; // used derivative value in output
|
||||
float feedForward; // used FeedForward value in output
|
||||
float output_constrained; // controller output constrained
|
||||
} pidController_t;
|
||||
|
||||
float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags);
|
||||
float navPidApply3(
|
||||
pidController_t *pid,
|
||||
const float setpoint,
|
||||
const float measurement,
|
||||
const float dt,
|
||||
const float outMin,
|
||||
const float outMax,
|
||||
const pidControllerFlags_e pidFlags,
|
||||
const float gainScaler,
|
||||
const float dTermScaler
|
||||
);
|
||||
void navPidReset(pidController_t *pid);
|
||||
void navPidInit(pidController_t *pid, float _kP, float _kI, float _kD, float _kFF, float _dTermLpfHz);
|
|
@ -142,7 +142,7 @@ int32_t applyDeadband(int32_t value, int32_t deadband)
|
|||
return value;
|
||||
}
|
||||
|
||||
int constrain(int amt, int low, int high)
|
||||
int32_t constrain(int32_t amt, int32_t low, int32_t high)
|
||||
{
|
||||
if (amt < low)
|
||||
return low;
|
||||
|
|
|
@ -88,6 +88,8 @@
|
|||
#define _ABS_I(x, var) _ABS_II(x, var)
|
||||
#define ABS(x) _ABS_I(x, _CHOOSE_VAR(_abs, __COUNTER__))
|
||||
|
||||
#define power3(x) ((x)*(x)*(x))
|
||||
|
||||
// Floating point Euler angles.
|
||||
typedef struct fp_angles {
|
||||
float roll;
|
||||
|
@ -131,7 +133,7 @@ bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu
|
|||
int gcd(int num, int denom);
|
||||
int32_t applyDeadband(int32_t value, int32_t deadband);
|
||||
|
||||
int constrain(int amt, int low, int high);
|
||||
int32_t constrain(int32_t amt, int32_t low, int32_t high);
|
||||
float constrainf(float amt, float low, float high);
|
||||
|
||||
void devClear(stdev_t *dev);
|
||||
|
|
245
src/main/drivers/accgyro/accgyro_bmi088.c
Normal file
245
src/main/drivers/accgyro/accgyro_bmi088.c
Normal file
|
@ -0,0 +1,245 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_bmi088.h"
|
||||
|
||||
|
||||
#if defined(USE_IMU_BMI088)
|
||||
|
||||
/*
|
||||
device registers, names follow datasheet conventions, with REGA_
|
||||
prefix for accel, and REGG_ prefix for gyro
|
||||
*/
|
||||
#define REGA_CHIPID 0x00
|
||||
#define REGA_ERR_REG 0x02
|
||||
#define REGA_STATUS 0x03
|
||||
#define REGA_X_LSB 0x12
|
||||
#define REGA_INT_STATUS_1 0x1D
|
||||
#define REGA_TEMP_LSB 0x22
|
||||
#define REGA_TEMP_MSB 0x23
|
||||
#define REGA_CONF 0x40
|
||||
#define REGA_RANGE 0x41
|
||||
#define REGA_PWR_CONF 0x7C
|
||||
#define REGA_PWR_CTRL 0x7D
|
||||
#define REGA_SOFTRESET 0x7E
|
||||
#define REGA_FIFO_CONFIG0 0x48
|
||||
#define REGA_FIFO_CONFIG1 0x49
|
||||
#define REGA_FIFO_DOWNS 0x45
|
||||
#define REGA_FIFO_DATA 0x26
|
||||
#define REGA_FIFO_LEN0 0x24
|
||||
#define REGA_FIFO_LEN1 0x25
|
||||
|
||||
#define REGG_CHIPID 0x00
|
||||
#define REGG_RATE_X_LSB 0x02
|
||||
#define REGG_INT_CTRL 0x15
|
||||
#define REGG_INT_STATUS_1 0x0A
|
||||
#define REGG_INT_STATUS_2 0x0B
|
||||
#define REGG_INT_STATUS_3 0x0C
|
||||
#define REGG_FIFO_STATUS 0x0E
|
||||
#define REGG_RANGE 0x0F
|
||||
#define REGG_BW 0x10
|
||||
#define REGG_LPM1 0x11
|
||||
#define REGG_RATE_HBW 0x13
|
||||
#define REGG_BGW_SOFTRESET 0x14
|
||||
#define REGG_FIFO_CONFIG_1 0x3E
|
||||
#define REGG_FIFO_DATA 0x3F
|
||||
|
||||
|
||||
static void bmi088GyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
gyroIntExtiInit(gyro);
|
||||
|
||||
busSetSpeed(gyro->busDev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
// Soft reset
|
||||
busWrite(gyro->busDev, REGG_BGW_SOFTRESET, 0xB6);
|
||||
delay(100);
|
||||
|
||||
// ODR 2kHz, BW 532Hz
|
||||
busWrite(gyro->busDev, REGG_BW, 0x81);
|
||||
delay(1);
|
||||
|
||||
// Enable sampling
|
||||
busWrite(gyro->busDev, REGG_INT_CTRL, 0x80);
|
||||
delay(1);
|
||||
|
||||
busSetSpeed(gyro->busDev, BUS_SPEED_FAST);
|
||||
}
|
||||
|
||||
static void bmi088AccInit(accDev_t *acc)
|
||||
{
|
||||
busSetSpeed(acc->busDev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
// Soft reset
|
||||
busWrite(acc->busDev, REGA_SOFTRESET, 0xB6);
|
||||
delay(100);
|
||||
|
||||
// Active mode
|
||||
busWrite(acc->busDev, REGA_PWR_CONF, 0);
|
||||
delay(100);
|
||||
|
||||
// ACC ON
|
||||
busWrite(acc->busDev, REGA_PWR_CTRL, 0x04);
|
||||
delay(100);
|
||||
|
||||
// OSR4, ODR 1600Hz
|
||||
busWrite(acc->busDev, REGA_CONF, 0x8C);
|
||||
delay(1);
|
||||
|
||||
// Range 12g
|
||||
busWrite(acc->busDev, REGA_RANGE, 0x02);
|
||||
delay(1);
|
||||
|
||||
busSetSpeed(acc->busDev, BUS_SPEED_STANDARD);
|
||||
|
||||
acc->acc_1G = 2048;
|
||||
}
|
||||
|
||||
static bool bmi088GyroRead(gyroDev_t *gyro)
|
||||
{
|
||||
uint8_t gyroRaw[6];
|
||||
|
||||
if (busReadBuf(gyro->busDev, REGG_RATE_X_LSB, gyroRaw, 6)) {
|
||||
gyro->gyroADCRaw[X] = (int16_t)((gyroRaw[1] << 8) | gyroRaw[0]);
|
||||
gyro->gyroADCRaw[Y] = (int16_t)((gyroRaw[3] << 8) | gyroRaw[2]);
|
||||
gyro->gyroADCRaw[Z] = (int16_t)((gyroRaw[5] << 8) | gyroRaw[4]);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool bmi088AccRead(accDev_t *acc)
|
||||
{
|
||||
uint8_t buffer[7];
|
||||
|
||||
if (busReadBuf(acc->busDev, REGA_STATUS, buffer, 2) && (buffer[1] & 0x80) && busReadBuf(acc->busDev, REGA_X_LSB, buffer, 7)) {
|
||||
// first byte is discarded, see datasheet
|
||||
acc->ADCRaw[X] = (int32_t)(((int16_t)(buffer[2] << 8) | buffer[1]) * 3 / 4);
|
||||
acc->ADCRaw[Y] = (int32_t)(((int16_t)(buffer[4] << 8) | buffer[3]) * 3 / 4);
|
||||
acc->ADCRaw[Z] = (int32_t)(((int16_t)(buffer[6] << 8) | buffer[5]) * 3 / 4);
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool gyroDeviceDetect(busDevice_t * busDev)
|
||||
{
|
||||
uint8_t attempts;
|
||||
|
||||
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
for (attempts = 0; attempts < 5; attempts++) {
|
||||
uint8_t chipId;
|
||||
|
||||
delay(100);
|
||||
busRead(busDev, REGG_CHIPID, &chipId);
|
||||
|
||||
if (chipId == 0x0F) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool accDeviceDetect(busDevice_t * busDev)
|
||||
{
|
||||
uint8_t attempts;
|
||||
|
||||
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
for (attempts = 0; attempts < 5; attempts++) {
|
||||
uint8_t chipId;
|
||||
|
||||
delay(100);
|
||||
busRead(busDev, REGA_CHIPID, &chipId);
|
||||
|
||||
if (chipId == 0x1E) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool bmi088AccDetect(accDev_t *acc)
|
||||
{
|
||||
acc->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_BMI088_ACC, acc->imuSensorToUse, OWNER_MPU);
|
||||
if (acc->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!accDeviceDetect(acc->busDev)) {
|
||||
busDeviceDeInit(acc->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
acc->initFn = bmi088AccInit;
|
||||
acc->readFn = bmi088AccRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool bmi088GyroDetect(gyroDev_t *gyro)
|
||||
{
|
||||
gyro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_BMI088_GYRO, gyro->imuSensorToUse, OWNER_MPU);
|
||||
if (gyro->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!gyroDeviceDetect(gyro->busDev)) {
|
||||
busDeviceDeInit(gyro->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
gyro->initFn = bmi088GyroInit;
|
||||
gyro->readFn = bmi088GyroRead;
|
||||
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->gyroAlign = gyro->busDev->param;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif /* USE_IMU_BMI088 */
|
30
src/main/drivers/accgyro/accgyro_bmi088.h
Normal file
30
src/main/drivers/accgyro/accgyro_bmi088.h
Normal file
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
bool bmi088AccDetect(accDev_t *acc);
|
||||
bool bmi088GyroDetect(gyroDev_t *gyro);
|
|
@ -91,6 +91,8 @@ typedef enum {
|
|||
DEVHW_MPU6050,
|
||||
DEVHW_MPU6500,
|
||||
DEVHW_BMI160,
|
||||
DEVHW_BMI088_GYRO,
|
||||
DEVHW_BMI088_ACC,
|
||||
DEVHW_ICM20689,
|
||||
|
||||
/* Combined ACC/GYRO/MAG chips */
|
||||
|
@ -116,6 +118,7 @@ typedef enum {
|
|||
DEVHW_QMC5883,
|
||||
DEVHW_MAG3110,
|
||||
DEVHW_LIS3MDL,
|
||||
DEVHW_RM3100,
|
||||
|
||||
/* Temp sensor chips */
|
||||
DEVHW_LM75_0,
|
||||
|
@ -137,6 +140,7 @@ typedef enum {
|
|||
DEVHW_SRF10,
|
||||
DEVHW_HCSR04_I2C, // DIY-style adapter
|
||||
DEVHW_VL53L0X,
|
||||
DEVHW_VL53L1X,
|
||||
|
||||
/* Other hardware */
|
||||
DEVHW_MS4525, // Pitot meter
|
||||
|
|
179
src/main/drivers/compass/compass_rm3100.c
Normal file
179
src/main/drivers/compass/compass_rm3100.c
Normal file
|
@ -0,0 +1,179 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_MAG_RM3100
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
|
||||
#include "drivers/compass/compass_rm3100.h"
|
||||
|
||||
#define RM3100_REG_POLL 0x00
|
||||
#define RM3100_REG_CMM 0x01
|
||||
#define RM3100_REG_CCX1 0x04
|
||||
#define RM3100_REG_CCX0 0x05
|
||||
#define RM3100_REG_CCY1 0x06
|
||||
#define RM3100_REG_CCY0 0x07
|
||||
#define RM3100_REG_CCZ1 0x08
|
||||
#define RM3100_REG_CCZ0 0x09
|
||||
#define RM3100_REG_TMRC 0x0B
|
||||
#define RM3100_REG_MX 0x24
|
||||
#define RM3100_REG_MY 0x27
|
||||
#define RM3100_REG_MZ 0x2A
|
||||
#define RM3100_REG_BIST 0x33
|
||||
#define RM3100_REG_STATUS 0x34
|
||||
#define RM3100_REG_HSHAKE 0x35
|
||||
#define RM3100_REG_REVID 0x36
|
||||
|
||||
#define RM3100_REVID 0x22
|
||||
|
||||
#define CCX_DEFAULT_MSB 0x00
|
||||
#define CCX_DEFAULT_LSB 0xC8
|
||||
#define CCY_DEFAULT_MSB CCX_DEFAULT_MSB
|
||||
#define CCY_DEFAULT_LSB CCX_DEFAULT_LSB
|
||||
#define CCZ_DEFAULT_MSB CCX_DEFAULT_MSB
|
||||
#define CCZ_DEFAULT_LSB CCX_DEFAULT_LSB
|
||||
#define CMM_DEFAULT 0x71 // Continuous mode
|
||||
#define TMRC_DEFAULT 0x94
|
||||
|
||||
|
||||
static bool deviceInit(magDev_t * mag)
|
||||
{
|
||||
busWrite(mag->busDev, RM3100_REG_TMRC, TMRC_DEFAULT);
|
||||
|
||||
busWrite(mag->busDev, RM3100_REG_CMM, CMM_DEFAULT);
|
||||
|
||||
busWrite(mag->busDev, RM3100_REG_CCX1, CCX_DEFAULT_MSB);
|
||||
busWrite(mag->busDev, RM3100_REG_CCX0, CCX_DEFAULT_LSB);
|
||||
|
||||
busWrite(mag->busDev, RM3100_REG_CCY1, CCY_DEFAULT_MSB);
|
||||
busWrite(mag->busDev, RM3100_REG_CCY0, CCY_DEFAULT_LSB);
|
||||
|
||||
busWrite(mag->busDev, RM3100_REG_CCZ1, CCZ_DEFAULT_MSB);
|
||||
busWrite(mag->busDev, RM3100_REG_CCZ0, CCZ_DEFAULT_LSB);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool deviceRead(magDev_t * mag)
|
||||
{
|
||||
uint8_t status;
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct {
|
||||
uint8_t x[3];
|
||||
uint8_t y[3];
|
||||
uint8_t z[3];
|
||||
} rm_report;
|
||||
#pragma pack(pop)
|
||||
|
||||
mag->magADCRaw[X] = 0;
|
||||
mag->magADCRaw[Y] = 0;
|
||||
mag->magADCRaw[Z] = 0;
|
||||
|
||||
/* Check if new measurement is ready */
|
||||
bool ack = busRead(mag->busDev, RM3100_REG_STATUS, &status);
|
||||
|
||||
if (!ack || (status & 0x80) == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
ack = busReadBuf(mag->busDev, RM3100_REG_MX, (uint8_t *)&rm_report, sizeof(rm_report));
|
||||
if (!ack) {
|
||||
return false;
|
||||
}
|
||||
|
||||
int32_t xraw;
|
||||
int32_t yraw;
|
||||
int32_t zraw;
|
||||
|
||||
/* Rearrange mag data */
|
||||
xraw = ((rm_report.x[0] << 24) | (rm_report.x[1] << 16) | (rm_report.x[2]) << 8);
|
||||
yraw = ((rm_report.y[0] << 24) | (rm_report.y[1] << 16) | (rm_report.y[2]) << 8);
|
||||
zraw = ((rm_report.z[0] << 24) | (rm_report.z[1] << 16) | (rm_report.z[2]) << 8);
|
||||
|
||||
/* Truncate to 16-bit integers and pass along */
|
||||
mag->magADCRaw[X] = (int16_t)(xraw >> 16);
|
||||
mag->magADCRaw[Y] = (int16_t)(yraw >> 16);
|
||||
mag->magADCRaw[Z] = (int16_t)(zraw >> 16);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#define DETECTION_MAX_RETRY_COUNT 5
|
||||
static bool deviceDetect(magDev_t * mag)
|
||||
{
|
||||
for (int retryCount = 0; retryCount < DETECTION_MAX_RETRY_COUNT; retryCount++) {
|
||||
uint8_t revid = 0;
|
||||
bool ack = busRead(mag->busDev, RM3100_REG_REVID, &revid);
|
||||
|
||||
if (ack && revid == RM3100_REVID) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool rm3100MagDetect(magDev_t * mag)
|
||||
{
|
||||
busSetSpeed(mag->busDev, BUS_SPEED_STANDARD);
|
||||
|
||||
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_RM3100, mag->magSensorToUse, OWNER_COMPASS);
|
||||
if (mag->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!deviceDetect(mag)) {
|
||||
busDeviceDeInit(mag->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
mag->init = deviceInit;
|
||||
mag->read = deviceRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
27
src/main/drivers/compass/compass_rm3100.h
Normal file
27
src/main/drivers/compass/compass_rm3100.h
Normal file
|
@ -0,0 +1,27 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
bool rm3100MagDetect(magDev_t *mag);
|
|
@ -10,7 +10,7 @@
|
|||
|
||||
static IO_t lightsIO = DEFIO_IO(NONE);
|
||||
|
||||
bool lightsHardwareInit()
|
||||
bool lightsHardwareInit(void)
|
||||
{
|
||||
lightsIO = IOGetByTag(IO_TAG(LIGHTS_PIN));
|
||||
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
#ifdef USE_LIGHTS
|
||||
|
||||
|
||||
bool lightsHardwareInit();
|
||||
bool lightsHardwareInit(void);
|
||||
void lightsHardwareSetStatus(bool status);
|
||||
|
||||
#endif /* USE_LIGHTS */
|
||||
|
|
|
@ -268,7 +268,8 @@ static bool motorsUseHardwareTimers(void)
|
|||
|
||||
static bool servosUseHardwareTimers(void)
|
||||
{
|
||||
return servoConfig()->servo_protocol == SERVO_TYPE_PWM;
|
||||
return servoConfig()->servo_protocol == SERVO_TYPE_PWM ||
|
||||
servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM;
|
||||
}
|
||||
|
||||
static void pwmInitMotors(timMotorServoHardware_t * timOutputs)
|
||||
|
|
|
@ -52,7 +52,8 @@ typedef enum {
|
|||
typedef enum {
|
||||
SERVO_TYPE_PWM = 0,
|
||||
SERVO_TYPE_SERVO_DRIVER,
|
||||
SERVO_TYPE_SBUS
|
||||
SERVO_TYPE_SBUS,
|
||||
SERVO_TYPE_SBUS_PWM
|
||||
} servoProtocolType_e;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -28,6 +28,7 @@ FILE_COMPILE_FOR_SPEED
|
|||
|
||||
#include "common/log.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/circular_queue.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/timer.h"
|
||||
|
@ -60,6 +61,10 @@ FILE_COMPILE_FOR_SPEED
|
|||
#define DSHOT_MOTOR_BITLENGTH 20
|
||||
|
||||
#define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */
|
||||
|
||||
#define DSHOT_COMMAND_INTERVAL_US 1000
|
||||
#define DSHOT_COMMAND_QUEUE_LENGTH 8
|
||||
#define DHSOT_COMMAND_QUEUE_SIZE DSHOT_COMMAND_QUEUE_LENGTH * sizeof(dshotCommands_e)
|
||||
#endif
|
||||
|
||||
typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
|
||||
|
@ -110,6 +115,12 @@ static uint8_t allocatedOutputPortCount = 0;
|
|||
|
||||
static bool pwmMotorsEnabled = true;
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
static circularBuffer_t commandsCircularBuffer;
|
||||
static uint8_t commandsBuff[DHSOT_COMMAND_QUEUE_SIZE];
|
||||
static currentExecutingCommand_t currentExecutingCommand;
|
||||
#endif
|
||||
|
||||
static void pwmOutConfigTimer(pwmOutputPort_t * p, TCH_t * tch, uint32_t hz, uint16_t period, uint16_t value)
|
||||
{
|
||||
p->tch = tch;
|
||||
|
@ -340,8 +351,60 @@ void pwmRequestMotorTelemetry(int motorIndex)
|
|||
}
|
||||
}
|
||||
|
||||
void pwmCompleteMotorUpdate(void)
|
||||
{
|
||||
#ifdef USE_DSHOT
|
||||
void sendDShotCommand(dshotCommands_e cmd) {
|
||||
circularBufferPushElement(&commandsCircularBuffer, (uint8_t *) &cmd);
|
||||
}
|
||||
|
||||
void initDShotCommands(void) {
|
||||
circularBufferInit(&commandsCircularBuffer, commandsBuff,DHSOT_COMMAND_QUEUE_SIZE, sizeof(dshotCommands_e));
|
||||
|
||||
currentExecutingCommand.remainingRepeats = 0;
|
||||
}
|
||||
|
||||
static int getDShotCommandRepeats(dshotCommands_e cmd) {
|
||||
int repeats = 1;
|
||||
|
||||
switch (cmd) {
|
||||
case DSHOT_CMD_SPIN_DIRECTION_NORMAL:
|
||||
case DSHOT_CMD_SPIN_DIRECTION_REVERSED:
|
||||
repeats = 6;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return repeats;
|
||||
}
|
||||
|
||||
static void executeDShotCommands(void){
|
||||
|
||||
if(currentExecutingCommand.remainingRepeats == 0) {
|
||||
|
||||
const int isTherePendingCommands = !circularBufferIsEmpty(&commandsCircularBuffer);
|
||||
|
||||
if (isTherePendingCommands) {
|
||||
//Load the command
|
||||
dshotCommands_e cmd;
|
||||
circularBufferPopHead(&commandsCircularBuffer, (uint8_t *) &cmd);
|
||||
|
||||
currentExecutingCommand.cmd = cmd;
|
||||
currentExecutingCommand.remainingRepeats = getDShotCommandRepeats(cmd);
|
||||
}
|
||||
else {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < getMotorCount(); i++) {
|
||||
motors[i].requestTelemetry = true;
|
||||
motors[i].value = currentExecutingCommand.cmd;
|
||||
}
|
||||
currentExecutingCommand.remainingRepeats--;
|
||||
}
|
||||
#endif
|
||||
|
||||
void pwmCompleteMotorUpdate(void) {
|
||||
// This only makes sense for digital motor protocols
|
||||
if (!isMotorProtocolDigital()) {
|
||||
return;
|
||||
|
@ -359,6 +422,9 @@ void pwmCompleteMotorUpdate(void)
|
|||
|
||||
#ifdef USE_DSHOT
|
||||
if (isMotorProtocolDshot()) {
|
||||
|
||||
executeDShotCommands();
|
||||
|
||||
// Generate DMA buffers
|
||||
for (int index = 0; index < motorCount; index++) {
|
||||
if (motors[index].pwmPort && motors[index].pwmPort->configured) {
|
||||
|
@ -501,6 +567,14 @@ static void pwmServoWriteStandard(uint8_t index, uint16_t value)
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_SERVO_SBUS
|
||||
static void sbusPwmWriteStandard(uint8_t index, uint16_t value)
|
||||
{
|
||||
pwmServoWriteStandard(index, value);
|
||||
sbusServoUpdate(index, value);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
static void pwmServoWriteExternalDriver(uint8_t index, uint16_t value)
|
||||
{
|
||||
|
@ -532,6 +606,11 @@ void pwmServoPreconfigure(void)
|
|||
sbusServoInitialize();
|
||||
servoWritePtr = sbusServoUpdate;
|
||||
break;
|
||||
|
||||
case SERVO_TYPE_SBUS_PWM:
|
||||
sbusServoInitialize();
|
||||
servoWritePtr = sbusPwmWriteStandard;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -20,6 +20,16 @@
|
|||
#include "drivers/io_types.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
typedef enum {
|
||||
DSHOT_CMD_SPIN_DIRECTION_NORMAL = 20,
|
||||
DSHOT_CMD_SPIN_DIRECTION_REVERSED = 21,
|
||||
} dshotCommands_e;
|
||||
|
||||
typedef struct {
|
||||
dshotCommands_e cmd;
|
||||
int remainingRepeats;
|
||||
} currentExecutingCommand_t;
|
||||
|
||||
void pwmRequestMotorTelemetry(int motorIndex);
|
||||
|
||||
ioTag_t pwmGetMotorPinTag(int motorIndex);
|
||||
|
@ -28,6 +38,7 @@ void pwmWriteMotor(uint8_t index, uint16_t value);
|
|||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
|
||||
void pwmCompleteMotorUpdate(void);
|
||||
bool isMotorProtocolDigital(void);
|
||||
bool isMotorProtocolDshot(void);
|
||||
|
||||
void pwmWriteServo(uint8_t index, uint16_t value);
|
||||
|
||||
|
@ -42,3 +53,6 @@ void pwmServoPreconfigure(void);
|
|||
bool pwmServoConfig(const struct timerHardware_s *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse, bool enableOutput);
|
||||
void pwmWriteBeeper(bool onoffBeep);
|
||||
void beeperPwmInit(ioTag_t tag, uint16_t frequency);
|
||||
|
||||
void sendDShotCommand(dshotCommands_e directionSpin);
|
||||
void initDShotCommands(void);
|
1696
src/main/drivers/rangefinder/rangefinder_vl53l1x.c
Normal file
1696
src/main/drivers/rangefinder/rangefinder_vl53l1x.c
Normal file
File diff suppressed because it is too large
Load diff
29
src/main/drivers/rangefinder/rangefinder_vl53l1x.h
Normal file
29
src/main/drivers/rangefinder/rangefinder_vl53l1x.h
Normal file
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define RANGEFINDER_VL53L1X_TASK_PERIOD_MS (40)
|
||||
|
||||
bool vl53l1xDetect(rangefinderDev_t *dev);
|
|
@ -1081,7 +1081,7 @@ SD_Error_t SD_GetStatus(void)
|
|||
}
|
||||
}
|
||||
else {
|
||||
ErrorState = SD_CARD_ERROR;
|
||||
ErrorState = SD_ERROR;
|
||||
}
|
||||
|
||||
return ErrorState;
|
||||
|
|
|
@ -41,6 +41,7 @@ uint8_t cliMode = 0;
|
|||
#include "common/memory.h"
|
||||
#include "common/time.h"
|
||||
#include "common/typeconversion.h"
|
||||
#include "common/fp_pid.h"
|
||||
#include "programming/global_variables.h"
|
||||
#include "programming/pid.h"
|
||||
|
||||
|
|
|
@ -217,7 +217,7 @@ void validateAndFixConfig(void)
|
|||
#endif
|
||||
|
||||
#ifndef USE_SERVO_SBUS
|
||||
if (servoConfig()->servo_protocol == SERVO_TYPE_SBUS) {
|
||||
if (servoConfig()->servo_protocol == SERVO_TYPE_SBUS || servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM) {
|
||||
servoConfigMutable()->servo_protocol = SERVO_TYPE_PWM;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -64,7 +64,7 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance)
|
|||
},
|
||||
|
||||
.misc = {
|
||||
.fpvCamAngleDegrees = 0
|
||||
.fpvCamAngleDegrees = 0,
|
||||
}
|
||||
);
|
||||
}
|
||||
|
|
|
@ -295,6 +295,16 @@ static void updateArmingStatus(void)
|
|||
DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
|
||||
}
|
||||
|
||||
if (isModeActivationConditionPresent(BOXPREARM)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXPREARM)) {
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_NO_PREARM);
|
||||
} else {
|
||||
ENABLE_ARMING_FLAG(ARMING_DISABLED_NO_PREARM);
|
||||
}
|
||||
} else {
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_NO_PREARM);
|
||||
}
|
||||
|
||||
/* CHECK: Arming switch */
|
||||
// If arming is disabled and the ARM switch is on
|
||||
// Note that this should be last check so all other blockers could be cleared correctly
|
||||
|
@ -388,10 +398,17 @@ void disarm(disarmReason_t disarmReason)
|
|||
blackboxFinish();
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
if (FLIGHT_MODE(FLIP_OVER_AFTER_CRASH)) {
|
||||
sendDShotCommand(DSHOT_CMD_SPIN_DIRECTION_NORMAL);
|
||||
DISABLE_FLIGHT_MODE(FLIP_OVER_AFTER_CRASH);
|
||||
}
|
||||
#endif
|
||||
statsOnDisarm();
|
||||
logicConditionReset();
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
programmingPidReset();
|
||||
#endif
|
||||
beeper(BEEPER_DISARMING); // emit disarm tone
|
||||
}
|
||||
}
|
||||
|
@ -447,6 +464,21 @@ void releaseSharedTelemetryPorts(void) {
|
|||
void tryArm(void)
|
||||
{
|
||||
updateArmingStatus();
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
if (
|
||||
STATE(MULTIROTOR) &&
|
||||
IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH) &&
|
||||
emergencyArmingCanOverrideArmingDisabled() &&
|
||||
isMotorProtocolDshot() &&
|
||||
!FLIGHT_MODE(FLIP_OVER_AFTER_CRASH)
|
||||
) {
|
||||
sendDShotCommand(DSHOT_CMD_SPIN_DIRECTION_REVERSED);
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
enableFlightMode(FLIP_OVER_AFTER_CRASH);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
if (
|
||||
!isArmingDisabled() ||
|
||||
|
@ -482,7 +514,10 @@ void tryArm(void)
|
|||
//It is required to inform the mixer that arming was executed and it has to switch to the FORWARD direction
|
||||
ENABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD);
|
||||
logicConditionReset();
|
||||
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
programmingPidReset();
|
||||
#endif
|
||||
headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
|
||||
|
||||
resetHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude.values.yaw));
|
||||
|
@ -506,6 +541,7 @@ void tryArm(void)
|
|||
#else
|
||||
beeper(BEEPER_ARMING);
|
||||
#endif
|
||||
|
||||
statsOnArm();
|
||||
|
||||
return;
|
||||
|
|
|
@ -673,6 +673,10 @@ void init(void)
|
|||
rcdeviceInit();
|
||||
#endif // USE_RCDEVICE
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
initDShotCommands();
|
||||
#endif
|
||||
|
||||
// Latch active features AGAIN since some may be modified by init().
|
||||
latchActiveFeatures();
|
||||
motorControlEnable = true;
|
||||
|
|
|
@ -567,6 +567,11 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU16(dst, programmingPids(i)->gains.FF);
|
||||
}
|
||||
break;
|
||||
case MSP2_INAV_PROGRAMMING_PID_STATUS:
|
||||
for (int i = 0; i < MAX_PROGRAMMING_PID_COUNT; i++) {
|
||||
sbufWriteU32(dst, programmingPidGetOutput(i));
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case MSP2_COMMON_MOTOR_MIXER:
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
|
@ -824,6 +829,17 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, currentBatteryProfile->capacity.unit);
|
||||
break;
|
||||
|
||||
case MSP2_INAV_MISC2:
|
||||
// Timers
|
||||
sbufWriteU32(dst, micros() / 1000000); // On time (seconds)
|
||||
sbufWriteU32(dst, getFlightTime()); // Flight time (seconds)
|
||||
|
||||
// Throttle
|
||||
sbufWriteU8(dst, getThrottlePercent()); // Throttle Percent
|
||||
sbufWriteU8(dst, navigationIsControllingThrottle() ? 1 : 0); // Auto Throttle Flag (0 or 1)
|
||||
|
||||
break;
|
||||
|
||||
case MSP2_INAV_BATTERY_CONFIG:
|
||||
sbufWriteU16(dst, batteryMetersConfig()->voltage.scale);
|
||||
sbufWriteU8(dst, batteryMetersConfig()->voltageSource);
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
|
||||
#include "io/osd.h"
|
||||
|
||||
#include "drivers/pwm_output.h"
|
||||
|
||||
#include "sensors/diagnostics.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
|
@ -86,6 +88,8 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
|
|||
{ BOXUSER2, "USER2", BOX_PERMANENT_ID_USER2 },
|
||||
{ BOXLOITERDIRCHN, "LOITER CHANGE", 49 },
|
||||
{ BOXMSPRCOVERRIDE, "MSP RC OVERRIDE", 50 },
|
||||
{ BOXPREARM, "PREARM", 51 },
|
||||
{ BOXFLIPOVERAFTERCRASH, "TURTLE", 52 },
|
||||
{ CHECKBOX_ITEM_COUNT, NULL, 0xFF }
|
||||
};
|
||||
|
||||
|
@ -163,6 +167,7 @@ void initActiveBoxIds(void)
|
|||
|
||||
activeBoxIdCount = 0;
|
||||
activeBoxIds[activeBoxIdCount++] = BOXARM;
|
||||
activeBoxIds[activeBoxIdCount++] = BOXPREARM;
|
||||
|
||||
if (sensors(SENSOR_ACC) && STATE(ALTITUDE_CONTROL)) {
|
||||
activeBoxIds[activeBoxIdCount++] = BOXANGLE;
|
||||
|
@ -304,6 +309,11 @@ void initActiveBoxIds(void)
|
|||
#if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE)
|
||||
activeBoxIds[activeBoxIdCount++] = BOXMSPRCOVERRIDE;
|
||||
#endif
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
if(STATE(MULTIROTOR) && isMotorProtocolDshot())
|
||||
activeBoxIds[activeBoxIdCount++] = BOXFLIPOVERAFTERCRASH;
|
||||
#endif
|
||||
}
|
||||
|
||||
#define IS_ENABLED(mask) (mask == 0 ? 0 : 1)
|
||||
|
|
|
@ -346,7 +346,7 @@ void fcTasksInit(void)
|
|||
setTaskEnabled(TASK_STACK_CHECK, true);
|
||||
#endif
|
||||
#if defined(USE_PWM_SERVO_DRIVER) || defined(USE_SERVO_SBUS)
|
||||
setTaskEnabled(TASK_PWMDRIVER, (servoConfig()->servo_protocol == SERVO_TYPE_SERVO_DRIVER) || (servoConfig()->servo_protocol == SERVO_TYPE_SBUS));
|
||||
setTaskEnabled(TASK_PWMDRIVER, (servoConfig()->servo_protocol == SERVO_TYPE_SERVO_DRIVER) || (servoConfig()->servo_protocol == SERVO_TYPE_SBUS) || (servoConfig()->servo_protocol == SERVO_TYPE_SBUS_PWM));
|
||||
#endif
|
||||
#ifdef USE_CMS
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
|
|
|
@ -101,7 +101,43 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU
|
|||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_ROLL_D_FF,
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_ROLL_D,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_ROLL_FF,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_P,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_I,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_D,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_FF,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_ROLL_P,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_ROLL_I,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_ROLL_D,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_ROLL_FF,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
|
@ -113,7 +149,11 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU
|
|||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_YAW_D_FF,
|
||||
.adjustmentFunction = ADJUSTMENT_YAW_D,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_YAW_FF,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
|
@ -128,30 +168,6 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU
|
|||
.adjustmentFunction = ADJUSTMENT_ROLL_RATE,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_P,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_I,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_D_FF,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_ROLL_P,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_ROLL_I,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_ROLL_D_FF,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { .stepConfig = { .step = 1 }}
|
||||
}, {
|
||||
.adjustmentFunction = ADJUSTMENT_RC_YAW_EXPO,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
|
@ -447,18 +463,32 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t
|
|||
applyAdjustmentPID(ADJUSTMENT_ROLL_I, &pidBankMutable()->pid[PID_ROLL].I, delta);
|
||||
schedulePidGainsUpdate();
|
||||
break;
|
||||
case ADJUSTMENT_PITCH_ROLL_D_FF:
|
||||
case ADJUSTMENT_PITCH_D_FF:
|
||||
applyAdjustmentPID(ADJUSTMENT_PITCH_D_FF, getD_FFRefByBank(pidBankMutable(), PID_PITCH), delta);
|
||||
if (adjustmentFunction == ADJUSTMENT_PITCH_D_FF) {
|
||||
case ADJUSTMENT_PITCH_ROLL_D:
|
||||
case ADJUSTMENT_PITCH_D:
|
||||
applyAdjustmentPID(ADJUSTMENT_PITCH_D, &pidBankMutable()->pid[PID_PITCH].D, delta);
|
||||
if (adjustmentFunction == ADJUSTMENT_PITCH_D) {
|
||||
schedulePidGainsUpdate();
|
||||
break;
|
||||
}
|
||||
// follow though for combined ADJUSTMENT_PITCH_ROLL_D
|
||||
FALLTHROUGH;
|
||||
|
||||
case ADJUSTMENT_ROLL_D_FF:
|
||||
applyAdjustmentPID(ADJUSTMENT_ROLL_D_FF, getD_FFRefByBank(pidBankMutable(), PID_ROLL), delta);
|
||||
case ADJUSTMENT_ROLL_D:
|
||||
applyAdjustmentPID(ADJUSTMENT_ROLL_D, &pidBankMutable()->pid[PID_ROLL].D, delta);
|
||||
schedulePidGainsUpdate();
|
||||
break;
|
||||
case ADJUSTMENT_PITCH_ROLL_FF:
|
||||
case ADJUSTMENT_PITCH_FF:
|
||||
applyAdjustmentPID(ADJUSTMENT_PITCH_FF, &pidBankMutable()->pid[PID_PITCH].FF, delta);
|
||||
if (adjustmentFunction == ADJUSTMENT_PITCH_FF) {
|
||||
schedulePidGainsUpdate();
|
||||
break;
|
||||
}
|
||||
// follow though for combined ADJUSTMENT_PITCH_ROLL_FF
|
||||
FALLTHROUGH;
|
||||
|
||||
case ADJUSTMENT_ROLL_FF:
|
||||
applyAdjustmentPID(ADJUSTMENT_ROLL_FF, &pidBankMutable()->pid[PID_ROLL].FF, delta);
|
||||
schedulePidGainsUpdate();
|
||||
break;
|
||||
case ADJUSTMENT_YAW_P:
|
||||
|
@ -469,8 +499,12 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t
|
|||
applyAdjustmentPID(ADJUSTMENT_YAW_I, &pidBankMutable()->pid[PID_YAW].I, delta);
|
||||
schedulePidGainsUpdate();
|
||||
break;
|
||||
case ADJUSTMENT_YAW_D_FF:
|
||||
applyAdjustmentPID(ADJUSTMENT_YAW_D_FF, getD_FFRefByBank(pidBankMutable(), PID_YAW), delta);
|
||||
case ADJUSTMENT_YAW_D:
|
||||
applyAdjustmentPID(ADJUSTMENT_YAW_D, &pidBankMutable()->pid[PID_YAW].D, delta);
|
||||
schedulePidGainsUpdate();
|
||||
break;
|
||||
case ADJUSTMENT_YAW_FF:
|
||||
applyAdjustmentPID(ADJUSTMENT_YAW_FF, &pidBankMutable()->pid[PID_YAW].FF, delta);
|
||||
schedulePidGainsUpdate();
|
||||
break;
|
||||
case ADJUSTMENT_NAV_FW_CRUISE_THR:
|
||||
|
|
|
@ -33,51 +33,55 @@ typedef enum {
|
|||
ADJUSTMENT_YAW_RATE = 5,
|
||||
ADJUSTMENT_PITCH_ROLL_P = 6,
|
||||
ADJUSTMENT_PITCH_ROLL_I = 7,
|
||||
ADJUSTMENT_PITCH_ROLL_D_FF = 8,
|
||||
ADJUSTMENT_YAW_P = 9,
|
||||
ADJUSTMENT_YAW_I = 10,
|
||||
ADJUSTMENT_YAW_D_FF = 11,
|
||||
ADJUSTMENT_RATE_PROFILE = 12, // Unused, placeholder for compatibility
|
||||
ADJUSTMENT_PITCH_RATE = 13,
|
||||
ADJUSTMENT_ROLL_RATE = 14,
|
||||
ADJUSTMENT_PITCH_P = 15,
|
||||
ADJUSTMENT_PITCH_I = 16,
|
||||
ADJUSTMENT_PITCH_D_FF = 17,
|
||||
ADJUSTMENT_ROLL_P = 18,
|
||||
ADJUSTMENT_ROLL_I = 19,
|
||||
ADJUSTMENT_ROLL_D_FF = 20,
|
||||
ADJUSTMENT_RC_YAW_EXPO = 21,
|
||||
ADJUSTMENT_MANUAL_RC_EXPO = 22,
|
||||
ADJUSTMENT_MANUAL_RC_YAW_EXPO = 23,
|
||||
ADJUSTMENT_MANUAL_PITCH_ROLL_RATE = 24,
|
||||
ADJUSTMENT_MANUAL_ROLL_RATE = 25,
|
||||
ADJUSTMENT_MANUAL_PITCH_RATE = 26,
|
||||
ADJUSTMENT_MANUAL_YAW_RATE = 27,
|
||||
ADJUSTMENT_NAV_FW_CRUISE_THR = 28,
|
||||
ADJUSTMENT_NAV_FW_PITCH2THR = 29,
|
||||
ADJUSTMENT_ROLL_BOARD_ALIGNMENT = 30,
|
||||
ADJUSTMENT_PITCH_BOARD_ALIGNMENT = 31,
|
||||
ADJUSTMENT_LEVEL_P = 32,
|
||||
ADJUSTMENT_LEVEL_I = 33,
|
||||
ADJUSTMENT_LEVEL_D = 34,
|
||||
ADJUSTMENT_POS_XY_P = 35,
|
||||
ADJUSTMENT_POS_XY_I = 36,
|
||||
ADJUSTMENT_POS_XY_D = 37,
|
||||
ADJUSTMENT_POS_Z_P = 38,
|
||||
ADJUSTMENT_POS_Z_I = 39,
|
||||
ADJUSTMENT_POS_Z_D = 40,
|
||||
ADJUSTMENT_HEADING_P = 41,
|
||||
ADJUSTMENT_VEL_XY_P = 42,
|
||||
ADJUSTMENT_VEL_XY_I = 43,
|
||||
ADJUSTMENT_VEL_XY_D = 44,
|
||||
ADJUSTMENT_VEL_Z_P = 45,
|
||||
ADJUSTMENT_VEL_Z_I = 46,
|
||||
ADJUSTMENT_VEL_Z_D = 47,
|
||||
ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE = 48,
|
||||
ADJUSTMENT_VTX_POWER_LEVEL = 49,
|
||||
ADJUSTMENT_TPA = 50,
|
||||
ADJUSTMENT_TPA_BREAKPOINT = 51,
|
||||
ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS = 52,
|
||||
ADJUSTMENT_PITCH_ROLL_D = 8,
|
||||
ADJUSTMENT_PITCH_ROLL_FF = 9,
|
||||
ADJUSTMENT_PITCH_P = 10,
|
||||
ADJUSTMENT_PITCH_I = 11,
|
||||
ADJUSTMENT_PITCH_D = 12,
|
||||
ADJUSTMENT_PITCH_FF = 13,
|
||||
ADJUSTMENT_ROLL_P = 14,
|
||||
ADJUSTMENT_ROLL_I = 15,
|
||||
ADJUSTMENT_ROLL_D = 16,
|
||||
ADJUSTMENT_ROLL_FF = 17,
|
||||
ADJUSTMENT_YAW_P = 18,
|
||||
ADJUSTMENT_YAW_I = 19,
|
||||
ADJUSTMENT_YAW_D = 20,
|
||||
ADJUSTMENT_YAW_FF = 21,
|
||||
ADJUSTMENT_RATE_PROFILE = 22, // Unused, placeholder for compatibility
|
||||
ADJUSTMENT_PITCH_RATE = 23,
|
||||
ADJUSTMENT_ROLL_RATE = 24,
|
||||
ADJUSTMENT_RC_YAW_EXPO = 25,
|
||||
ADJUSTMENT_MANUAL_RC_EXPO = 26,
|
||||
ADJUSTMENT_MANUAL_RC_YAW_EXPO = 27,
|
||||
ADJUSTMENT_MANUAL_PITCH_ROLL_RATE = 28,
|
||||
ADJUSTMENT_MANUAL_ROLL_RATE = 29,
|
||||
ADJUSTMENT_MANUAL_PITCH_RATE = 30,
|
||||
ADJUSTMENT_MANUAL_YAW_RATE = 31,
|
||||
ADJUSTMENT_NAV_FW_CRUISE_THR = 32,
|
||||
ADJUSTMENT_NAV_FW_PITCH2THR = 33,
|
||||
ADJUSTMENT_ROLL_BOARD_ALIGNMENT = 34,
|
||||
ADJUSTMENT_PITCH_BOARD_ALIGNMENT = 35,
|
||||
ADJUSTMENT_LEVEL_P = 36,
|
||||
ADJUSTMENT_LEVEL_I = 37,
|
||||
ADJUSTMENT_LEVEL_D = 38,
|
||||
ADJUSTMENT_POS_XY_P = 39,
|
||||
ADJUSTMENT_POS_XY_I = 40,
|
||||
ADJUSTMENT_POS_XY_D = 41,
|
||||
ADJUSTMENT_POS_Z_P = 42,
|
||||
ADJUSTMENT_POS_Z_I = 43,
|
||||
ADJUSTMENT_POS_Z_D = 44,
|
||||
ADJUSTMENT_HEADING_P = 45,
|
||||
ADJUSTMENT_VEL_XY_P = 46,
|
||||
ADJUSTMENT_VEL_XY_I = 47,
|
||||
ADJUSTMENT_VEL_XY_D = 48,
|
||||
ADJUSTMENT_VEL_Z_P = 49,
|
||||
ADJUSTMENT_VEL_Z_I = 50,
|
||||
ADJUSTMENT_VEL_Z_D = 51,
|
||||
ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE = 52,
|
||||
ADJUSTMENT_VTX_POWER_LEVEL = 53,
|
||||
ADJUSTMENT_TPA = 54,
|
||||
ADJUSTMENT_TPA_BREAKPOINT = 55,
|
||||
ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS = 56,
|
||||
ADJUSTMENT_FUNCTION_COUNT // must be last
|
||||
} adjustmentFunction_e;
|
||||
|
||||
|
|
|
@ -134,13 +134,7 @@ void rcModeUpdate(boxBitmask_t *newState)
|
|||
|
||||
bool isModeActivationConditionPresent(boxId_e modeId)
|
||||
{
|
||||
for (int index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
|
||||
if (modeActivationConditions(index)->modeId == modeId && IS_RANGE_USABLE(&modeActivationConditions(index)->range)) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
return specifiedConditionCountPerMode[modeId] > 0;
|
||||
}
|
||||
|
||||
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range)
|
||||
|
|
|
@ -68,6 +68,8 @@ typedef enum {
|
|||
BOXFPVANGLEMIX = 39,
|
||||
BOXLOITERDIRCHN = 40,
|
||||
BOXMSPRCOVERRIDE = 41,
|
||||
BOXPREARM = 42,
|
||||
BOXFLIPOVERAFTERCRASH = 43,
|
||||
CHECKBOX_ITEM_COUNT
|
||||
} boxId_e;
|
||||
|
||||
|
|
|
@ -36,7 +36,7 @@ const char *armingDisableFlagNames[]= {
|
|||
"FS", "ANGLE", "CAL", "OVRLD", "NAV", "COMPASS",
|
||||
"ACC", "ARMSW", "HWFAIL", "BOXFS", "KILLSW", "RX",
|
||||
"THR", "CLI", "CMS", "OSD", "ROLL/PITCH", "AUTOTRIM", "OOM",
|
||||
"SETTINGFAIL", "PWMOUT"
|
||||
"SETTINGFAIL", "PWMOUT", "NOPREARM"
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -57,7 +57,8 @@ const armingFlag_e armDisableReasonsChecklist[] = {
|
|||
ARMING_DISABLED_OSD_MENU,
|
||||
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED,
|
||||
ARMING_DISABLED_SERVO_AUTOTRIM,
|
||||
ARMING_DISABLED_OOM
|
||||
ARMING_DISABLED_OOM,
|
||||
ARMING_DISABLED_NO_PREARM
|
||||
};
|
||||
|
||||
armingFlag_e isArmingDisabledReason(void)
|
||||
|
|
|
@ -23,7 +23,6 @@ typedef enum {
|
|||
WAS_EVER_ARMED = (1 << 3),
|
||||
|
||||
ARMING_DISABLED_FAILSAFE_SYSTEM = (1 << 7),
|
||||
|
||||
ARMING_DISABLED_NOT_LEVEL = (1 << 8),
|
||||
ARMING_DISABLED_SENSORS_CALIBRATING = (1 << 9),
|
||||
ARMING_DISABLED_SYSTEM_OVERLOADED = (1 << 10),
|
||||
|
@ -44,6 +43,7 @@ typedef enum {
|
|||
ARMING_DISABLED_OOM = (1 << 25),
|
||||
ARMING_DISABLED_INVALID_SETTING = (1 << 26),
|
||||
ARMING_DISABLED_PWM_OUTPUT_ERROR = (1 << 27),
|
||||
ARMING_DISABLED_NO_PREARM = (1 << 28),
|
||||
|
||||
ARMING_DISABLED_ALL_FLAGS = (ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING |
|
||||
ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE |
|
||||
|
@ -52,7 +52,7 @@ typedef enum {
|
|||
ARMING_DISABLED_BOXKILLSWITCH | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI |
|
||||
ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED |
|
||||
ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING |
|
||||
ARMING_DISABLED_PWM_OUTPUT_ERROR),
|
||||
ARMING_DISABLED_PWM_OUTPUT_ERROR | ARMING_DISABLED_NO_PREARM),
|
||||
} armingFlag_e;
|
||||
|
||||
// Arming blockers that can be overriden by emergency arming.
|
||||
|
@ -78,7 +78,7 @@ extern const char *armingDisableFlagNames[];
|
|||
#define ARMING_FLAG(mask) (armingFlags & (mask))
|
||||
|
||||
// Returns the 1st flag from ARMING_DISABLED_ALL_FLAGS which is
|
||||
// preventing arming, or zero is arming is not disabled.
|
||||
// preventing arming, or zero if arming is not disabled.
|
||||
armingFlag_e isArmingDisabledReason(void);
|
||||
|
||||
typedef enum {
|
||||
|
@ -97,6 +97,7 @@ typedef enum {
|
|||
NAV_CRUISE_MODE = (1 << 12),
|
||||
FLAPERON = (1 << 13),
|
||||
TURN_ASSISTANT = (1 << 14),
|
||||
FLIP_OVER_AFTER_CRASH = (1 << 15),
|
||||
} flightModeFlags_e;
|
||||
|
||||
extern uint32_t flightModeFlags;
|
||||
|
|
|
@ -4,16 +4,16 @@ tables:
|
|||
- name: gyro_lpf
|
||||
values: ["256HZ", "188HZ", "98HZ", "42HZ", "20HZ", "10HZ"]
|
||||
- name: acc_hardware
|
||||
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"]
|
||||
values: ["NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "FAKE"]
|
||||
enum: accelerationSensor_e
|
||||
- name: rangefinder_hardware
|
||||
values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UNUSED", "BENEWAKE"]
|
||||
values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UNUSED", "BENEWAKE", "VL53L1X"]
|
||||
enum: rangefinderType_e
|
||||
- name: mag_hardware
|
||||
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "FAKE"]
|
||||
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", FAKE"]
|
||||
enum: magSensor_e
|
||||
- name: opflow_hardware
|
||||
values: ["NONE", "PMW3901", "CXOF", "MSP", "FAKE"]
|
||||
values: ["NONE", "CXOF", "MSP", "FAKE"]
|
||||
enum: opticalFlowSensor_e
|
||||
- name: baro_hardware
|
||||
values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "MSP", "FAKE"]
|
||||
|
@ -34,7 +34,7 @@ tables:
|
|||
- name: motor_pwm_protocol
|
||||
values: ["STANDARD", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200", "SERIALSHOT"]
|
||||
- name: servo_protocol
|
||||
values: ["PWM", "SERVO_DRIVER", "SBUS"]
|
||||
values: ["PWM", "SERVO_DRIVER", "SBUS", "SBUS_PWM"]
|
||||
- name: failsafe_procedure
|
||||
values: ["SET-THR", "DROP", "RTH", "NONE"]
|
||||
- name: current_sensor
|
||||
|
@ -84,7 +84,7 @@ tables:
|
|||
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
|
||||
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
|
||||
"ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
|
||||
"IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF"]
|
||||
"IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "FW_D"]
|
||||
- name: async_mode
|
||||
values: ["NONE", "GYRO", "ALL"]
|
||||
- name: aux_operator
|
||||
|
@ -152,6 +152,9 @@ tables:
|
|||
- name: djiOsdTempSource
|
||||
values: ["ESC", "IMU", "BARO"]
|
||||
enum: djiOsdTempSource_e
|
||||
- name: djiOsdSpeedSource
|
||||
values: ["GROUND", "3D", "AIR"]
|
||||
enum: djiOsdSpeedSource_e
|
||||
- name: nav_overrides_motor_stop
|
||||
enum: navOverridesMotorStop_e
|
||||
values: ["OFF_ALWAYS", "OFF", "AUTO_ONLY", "ALL_NAV"]
|
||||
|
@ -182,8 +185,8 @@ groups:
|
|||
type: uint8_t
|
||||
table: alignment
|
||||
- name: gyro_hardware_lpf
|
||||
description: "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."
|
||||
default_value: "42HZ"
|
||||
description: "Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first."
|
||||
default_value: "256HZ"
|
||||
field: gyro_lpf
|
||||
table: gyro_lpf
|
||||
- name: gyro_lpf_hz
|
||||
|
@ -464,7 +467,7 @@ groups:
|
|||
description: "Adjust how long time the Calibration of mag will last."
|
||||
default_value: "30"
|
||||
field: magCalibrationTimeLimit
|
||||
min: 30
|
||||
min: 20
|
||||
max: 120
|
||||
- name: mag_to_use
|
||||
description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target"
|
||||
|
@ -718,8 +721,17 @@ groups:
|
|||
max: 30
|
||||
- name: motor_poles
|
||||
field: motorPoleCount
|
||||
description: "The number of motor poles. Required to compute motor RPM"
|
||||
default_value: "14"
|
||||
min: 4
|
||||
max: 255
|
||||
- name: flip_over_after_crash_power_factor
|
||||
field: flipOverAfterPowerFactor
|
||||
default_value: "65"
|
||||
description: "flip over after crash power factor"
|
||||
condition: "USE_DSHOT"
|
||||
min: 0
|
||||
max: 100
|
||||
|
||||
- name: PG_FAILSAFE_CONFIG
|
||||
type: failsafeConfig_t
|
||||
|
@ -1345,13 +1357,13 @@ groups:
|
|||
field: mid_throttle_deadband
|
||||
min: 0
|
||||
max: 200
|
||||
- name: mc_airmode_type
|
||||
description: "Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode."
|
||||
- name: airmode_type
|
||||
description: "Defines the Airmode state handling type. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `airmode_throttle_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER_ONCE** or **STICK_CENTER** modes."
|
||||
default_value: "STICK_CENTER"
|
||||
field: airmodeHandlingType
|
||||
table: airmodeHandlingType
|
||||
- name: mc_airmode_threshold
|
||||
description: "Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used"
|
||||
- name: airmode_throttle_threshold
|
||||
description: "Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used"
|
||||
default_value: "1300"
|
||||
field: airmodeThrottleThreshold
|
||||
min: 1000
|
||||
|
@ -1464,6 +1476,12 @@ groups:
|
|||
field: bank_fw.pid[PID_PITCH].I
|
||||
min: 0
|
||||
max: 200
|
||||
- name: fw_d_pitch
|
||||
description: "Fixed wing rate stabilisation D-gain for PITCH"
|
||||
default_value: "0"
|
||||
field: bank_fw.pid[PID_PITCH].D
|
||||
min: 0
|
||||
max: 200
|
||||
- name: fw_ff_pitch
|
||||
description: "Fixed-wing rate stabilisation FF-gain for PITCH"
|
||||
default_value: "50"
|
||||
|
@ -1482,6 +1500,12 @@ groups:
|
|||
field: bank_fw.pid[PID_ROLL].I
|
||||
min: 0
|
||||
max: 200
|
||||
- name: fw_d_roll
|
||||
description: "Fixed wing rate stabilisation D-gain for ROLL"
|
||||
default_value: "0"
|
||||
field: bank_fw.pid[PID_ROLL].D
|
||||
min: 0
|
||||
max: 200
|
||||
- name: fw_ff_roll
|
||||
description: "Fixed-wing rate stabilisation FF-gain for ROLL"
|
||||
default_value: "50"
|
||||
|
@ -1500,6 +1524,12 @@ groups:
|
|||
field: bank_fw.pid[PID_YAW].I
|
||||
min: 0
|
||||
max: 200
|
||||
- name: fw_d_yaw
|
||||
description: "Fixed wing rate stabilisation D-gain for YAW"
|
||||
default_value: "0"
|
||||
field: bank_fw.pid[PID_YAW].D
|
||||
min: 0
|
||||
max: 200
|
||||
- name: fw_ff_yaw
|
||||
description: "Fixed-wing rate stabilisation FF-gain for YAW"
|
||||
default_value: "60"
|
||||
|
@ -1597,6 +1627,12 @@ groups:
|
|||
field: fixedWingItermLimitOnStickPosition
|
||||
min: 0
|
||||
max: 1
|
||||
- name: fw_yaw_iterm_freeze_bank_angle
|
||||
description: "Yaw Iterm is frozen when bank angle is above this threshold [degrees]. This solves the problem of the rudder counteracting turns by partially disabling yaw stabilization when making banked turns. Setting to 0 (the default) disables this feature. Only applies when autopilot is not active and TURN ASSIST is disabled."
|
||||
default_value: "0"
|
||||
field: fixedWingYawItermBankFreeze
|
||||
min: 0
|
||||
max: 90
|
||||
- name: pidsum_limit
|
||||
description: "A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help"
|
||||
default_value: "500"
|
||||
|
@ -1877,6 +1913,12 @@ groups:
|
|||
condition: USE_GYRO_KALMAN
|
||||
min: 1
|
||||
max: 16000
|
||||
- name: fw_level_pitch_trim
|
||||
description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
|
||||
default_value: "0"
|
||||
field: fixedWingLevelTrim
|
||||
min: -10
|
||||
max: 10
|
||||
|
||||
- name: PG_PID_AUTOTUNE_CONFIG
|
||||
type: pidAutotuneConfig_t
|
||||
|
@ -2171,6 +2213,8 @@ groups:
|
|||
max: 65000
|
||||
- name: nav_max_terrain_follow_alt
|
||||
field: general.max_terrain_follow_altitude
|
||||
default_value: "100"
|
||||
description: "Max allowed above the ground altitude for terrain following mode"
|
||||
max: 1000
|
||||
- name: nav_rth_altitude
|
||||
description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)"
|
||||
|
@ -2276,6 +2320,11 @@ groups:
|
|||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_mc_wp_slowdown
|
||||
description: "When ON, NAV engine will slow down when switching to the next waypoint. This prioritizes turning over forward movement. When OFF, NAV engine will continue to the next waypoint and turn as it goes."
|
||||
default_value: "ON"
|
||||
field: mc.slowDownForTurning
|
||||
type: bool
|
||||
- name: nav_fw_cruise_thr
|
||||
description: "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 addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )"
|
||||
default_value: "1400"
|
||||
|
@ -2332,7 +2381,7 @@ groups:
|
|||
max: 900
|
||||
- name: nav_fw_loiter_radius
|
||||
description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]"
|
||||
default_value: "5000"
|
||||
default_value: "7500"
|
||||
field: fw.loiter_radius
|
||||
min: 0
|
||||
max: 10000
|
||||
|
@ -2796,8 +2845,8 @@ groups:
|
|||
description: "Value below which Crossfire SNR Alarm pops-up. (dB)"
|
||||
default_value: "4"
|
||||
field: snr_alarm
|
||||
min: -12
|
||||
max: 8
|
||||
min: -20
|
||||
max: 10
|
||||
- name: osd_link_quality_alarm
|
||||
condition: USE_SERIALRX_CRSF
|
||||
description: "LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%"
|
||||
|
@ -3018,6 +3067,20 @@ groups:
|
|||
default_value: "ON"
|
||||
description: Should home position coordinates be displayed on the arming screen.
|
||||
|
||||
- name: osd_pan_servo_index
|
||||
description: Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos.
|
||||
field: pan_servo_index
|
||||
min: 0
|
||||
max: 10
|
||||
|
||||
- name: osd_pan_servo_pwm2centideg
|
||||
description: Centidegrees of pan servo rotation us PWM signal. A servo with 180 degrees of rotation from 1000 to 2000 us PWM typically needs `18` for this setting. Change sign to inverse direction.
|
||||
field: pan_servo_pwm2centideg
|
||||
default_value: 0
|
||||
min: -36
|
||||
max: 36
|
||||
|
||||
|
||||
- name: PG_SYSTEM_CONFIG
|
||||
type: systemConfig_t
|
||||
headers: ["fc/config.h"]
|
||||
|
@ -3115,6 +3178,11 @@ groups:
|
|||
default_value: "ON"
|
||||
field: halfDuplex
|
||||
type: bool
|
||||
- name: vtx_smartaudio_early_akk_workaround
|
||||
description: "Enable workaround for early AKK SAudio-enabled VTX bug."
|
||||
default_value: "ON"
|
||||
field: smartAudioEarlyAkkWorkaroundEnable
|
||||
type: bool
|
||||
|
||||
- name: PG_VTX_SETTINGS_CONFIG
|
||||
type: vtxSettingsConfig_t
|
||||
|
@ -3163,21 +3231,29 @@ groups:
|
|||
members:
|
||||
- name: pinio_box1
|
||||
field: permanentId[0]
|
||||
description: "Mode assignment for PINIO#1"
|
||||
default_value: "target specific"
|
||||
min: 0
|
||||
max: 255
|
||||
type: uint8_t
|
||||
- name: pinio_box2
|
||||
field: permanentId[1]
|
||||
default_value: "target specific"
|
||||
description: "Mode assignment for PINIO#1"
|
||||
min: 0
|
||||
max: 255
|
||||
type: uint8_t
|
||||
- name: pinio_box3
|
||||
field: permanentId[2]
|
||||
default_value: "target specific"
|
||||
description: "Mode assignment for PINIO#1"
|
||||
min: 0
|
||||
max: 255
|
||||
type: uint8_t
|
||||
- name: pinio_box4
|
||||
field: permanentId[3]
|
||||
default_value: "target specific"
|
||||
description: "Mode assignment for PINIO#1"
|
||||
min: 0
|
||||
max: 255
|
||||
type: uint8_t
|
||||
|
@ -3205,6 +3281,8 @@ groups:
|
|||
condition: USE_ESC_SENSOR
|
||||
members:
|
||||
- name: esc_sensor_listen_only
|
||||
default_value: "OFF"
|
||||
description: "Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case"
|
||||
field: listenOnly
|
||||
type: bool
|
||||
|
||||
|
@ -3241,3 +3319,9 @@ groups:
|
|||
field: esc_temperature_source
|
||||
table: djiOsdTempSource
|
||||
type: uint8_t
|
||||
- name: dji_speed_source
|
||||
description: "Sets the speed type displayed by the DJI OSD: GROUND, 3D, AIR"
|
||||
default_value: "GROUND"
|
||||
field: speedSource
|
||||
table: djiOsdSpeedSource
|
||||
type: uint8_t
|
||||
|
|
|
@ -42,6 +42,7 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_modes.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
|
@ -99,7 +100,7 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
|
|||
|
||||
#define DEFAULT_MAX_THROTTLE 1850
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 6);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 7);
|
||||
|
||||
PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
|
||||
.motorPwmProtocol = DEFAULT_PWM_PROTOCOL,
|
||||
|
@ -110,11 +111,15 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
|
|||
.motorDecelTimeMs = 0,
|
||||
.throttleIdle = 15.0f,
|
||||
.throttleScale = 1.0f,
|
||||
.motorPoleCount = 14 // Most brushless motors that we use are 14 poles
|
||||
.motorPoleCount = 14, // Most brushless motors that we use are 14 poles
|
||||
.flipOverAfterPowerFactor = 65
|
||||
);
|
||||
|
||||
PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0);
|
||||
|
||||
#define CRASH_OVER_AFTER_CRASH_FLIP_DEADBAND 20.0f
|
||||
#define CRASH_OVER_AFTER_CRASH_FLIP_STICK_MIN 0.15f
|
||||
|
||||
typedef void (*motorRateLimitingApplyFnPtr)(const float dT);
|
||||
static EXTENDED_FASTRAM motorRateLimitingApplyFnPtr motorRateLimitingApplyFn;
|
||||
|
||||
|
@ -319,6 +324,85 @@ static uint16_t handleOutputScaling(
|
|||
}
|
||||
return value;
|
||||
}
|
||||
static void applyFlipOverAfterCrashModeToMotors(void) {
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
const float flipPowerFactor = ((float)motorConfig()->flipOverAfterPowerFactor)/100.0f;
|
||||
const float stickDeflectionPitchAbs = ABS(((float) rcCommand[PITCH]) / 500.0f);
|
||||
const float stickDeflectionRollAbs = ABS(((float) rcCommand[ROLL]) / 500.0f);
|
||||
const float stickDeflectionYawAbs = ABS(((float) rcCommand[YAW]) / 500.0f);
|
||||
//deflection stick position
|
||||
|
||||
const float stickDeflectionPitchExpo =
|
||||
flipPowerFactor * stickDeflectionPitchAbs + power3(stickDeflectionPitchAbs) * (1 - flipPowerFactor);
|
||||
const float stickDeflectionRollExpo =
|
||||
flipPowerFactor * stickDeflectionRollAbs + power3(stickDeflectionRollAbs) * (1 - flipPowerFactor);
|
||||
const float stickDeflectionYawExpo =
|
||||
flipPowerFactor * stickDeflectionYawAbs + power3(stickDeflectionYawAbs) * (1 - flipPowerFactor);
|
||||
|
||||
float signPitch = rcCommand[PITCH] < 0 ? 1 : -1;
|
||||
float signRoll = rcCommand[ROLL] < 0 ? 1 : -1;
|
||||
float signYaw = (float)((rcCommand[YAW] < 0 ? 1 : -1) * (mixerConfig()->motorDirectionInverted ? 1 : -1));
|
||||
|
||||
float stickDeflectionLength = sqrtf(sq(stickDeflectionPitchAbs) + sq(stickDeflectionRollAbs));
|
||||
float stickDeflectionExpoLength = sqrtf(sq(stickDeflectionPitchExpo) + sq(stickDeflectionRollExpo));
|
||||
|
||||
if (stickDeflectionYawAbs > MAX(stickDeflectionPitchAbs, stickDeflectionRollAbs)) {
|
||||
// If yaw is the dominant, disable pitch and roll
|
||||
stickDeflectionLength = stickDeflectionYawAbs;
|
||||
stickDeflectionExpoLength = stickDeflectionYawExpo;
|
||||
signRoll = 0;
|
||||
signPitch = 0;
|
||||
} else {
|
||||
// If pitch/roll dominant, disable yaw
|
||||
signYaw = 0;
|
||||
}
|
||||
|
||||
const float cosPhi = (stickDeflectionLength > 0) ? (stickDeflectionPitchAbs + stickDeflectionRollAbs) /
|
||||
(sqrtf(2.0f) * stickDeflectionLength) : 0;
|
||||
const float cosThreshold = sqrtf(3.0f) / 2.0f; // cos(PI/6.0f)
|
||||
|
||||
if (cosPhi < cosThreshold) {
|
||||
// Enforce either roll or pitch exclusively, if not on diagonal
|
||||
if (stickDeflectionRollAbs > stickDeflectionPitchAbs) {
|
||||
signPitch = 0;
|
||||
} else {
|
||||
signRoll = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// Apply a reasonable amount of stick deadband
|
||||
const float crashFlipStickMinExpo =
|
||||
flipPowerFactor * CRASH_OVER_AFTER_CRASH_FLIP_STICK_MIN + power3(CRASH_OVER_AFTER_CRASH_FLIP_STICK_MIN) * (1 - flipPowerFactor);
|
||||
const float flipStickRange = 1.0f - crashFlipStickMinExpo;
|
||||
const float flipPower = MAX(0.0f, stickDeflectionExpoLength - crashFlipStickMinExpo) / flipStickRange;
|
||||
|
||||
for (int i = 0; i < motorCount; ++i) {
|
||||
|
||||
float motorOutputNormalised =
|
||||
signPitch * currentMixer[i].pitch +
|
||||
signRoll * currentMixer[i].roll +
|
||||
signYaw * currentMixer[i].yaw;
|
||||
|
||||
if (motorOutputNormalised < 0) {
|
||||
motorOutputNormalised = 0;
|
||||
}
|
||||
|
||||
motorOutputNormalised = MIN(1.0f, flipPower * motorOutputNormalised);
|
||||
|
||||
float motorOutput = (float)motorConfig()->mincommand + motorOutputNormalised * (float)motorConfig()->maxthrottle;
|
||||
|
||||
// Add a little bit to the motorOutputMin so props aren't spinning when sticks are centered
|
||||
motorOutput = (motorOutput < (float)motorConfig()->mincommand + CRASH_OVER_AFTER_CRASH_FLIP_DEADBAND) ? DSHOT_DISARM_COMMAND : (
|
||||
motorOutput - CRASH_OVER_AFTER_CRASH_FLIP_DEADBAND);
|
||||
|
||||
motor[i] = motorOutput;
|
||||
}
|
||||
} else {
|
||||
// Disarmed mode
|
||||
stopMotors();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void FAST_CODE writeMotors(void)
|
||||
|
@ -443,6 +527,13 @@ static int getReversibleMotorsThrottleDeadband(void)
|
|||
|
||||
void FAST_CODE mixTable(const float dT)
|
||||
{
|
||||
#ifdef USE_DSHOT
|
||||
if (FLIGHT_MODE(FLIP_OVER_AFTER_CRASH)) {
|
||||
applyFlipOverAfterCrashModeToMotors();
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
int16_t input[3]; // RPY, range [-500:+500]
|
||||
// Allow direct stick input to motors in passthrough mode on airplanes
|
||||
if (STATE(FIXED_WING_LEGACY) && FLIGHT_MODE(MANUAL_MODE)) {
|
||||
|
@ -572,6 +663,12 @@ void FAST_CODE mixTable(const float dT)
|
|||
motorRateLimitingApplyFn(dT);
|
||||
}
|
||||
|
||||
int16_t getThrottlePercent(void)
|
||||
{
|
||||
int16_t thr = (constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX ) - getThrottleIdleValue()) * 100 / (motorConfig()->maxthrottle - getThrottleIdleValue());
|
||||
return thr;
|
||||
}
|
||||
|
||||
motorStatus_e getMotorStatus(void)
|
||||
{
|
||||
if (failsafeRequiresMotorStop()) {
|
||||
|
|
|
@ -92,6 +92,7 @@ typedef struct motorConfig_s {
|
|||
float throttleIdle; // Throttle IDLE value based on min_command, max_throttle, in percent
|
||||
float throttleScale; // Scaling factor for throttle.
|
||||
uint8_t motorPoleCount; // Magnetic poles in the motors for calculating actual RPM from eRPM provided by ESC telemetry
|
||||
uint8_t flipOverAfterPowerFactor; // Power factor from 0 to 100% of flip over after crash
|
||||
} motorConfig_t;
|
||||
|
||||
PG_DECLARE(motorConfig_t, motorConfig);
|
||||
|
@ -113,6 +114,7 @@ extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
|||
extern int mixerThrottleCommand;
|
||||
|
||||
int getThrottleIdleValue(void);
|
||||
int16_t getThrottlePercent(void);
|
||||
uint8_t getMotorCount(void);
|
||||
float getMotorMixRange(void);
|
||||
bool mixerIsOutputSaturated(void);
|
||||
|
|
|
@ -30,6 +30,7 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/fp_pid.h"
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
@ -103,6 +104,7 @@ typedef struct {
|
|||
uint16_t pidSumLimit;
|
||||
filterApply4FnPtr ptermFilterApplyFn;
|
||||
bool itermLimitActive;
|
||||
bool itermFreezeActive;
|
||||
|
||||
biquadFilter_t rateTargetFilter;
|
||||
} pidState_t;
|
||||
|
@ -153,8 +155,9 @@ static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn;
|
|||
static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn;
|
||||
static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn;
|
||||
static EXTENDED_FASTRAM bool levelingEnabled = false;
|
||||
static EXTENDED_FASTRAM float fixedWingLevelTrim;
|
||||
|
||||
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 0);
|
||||
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 1);
|
||||
|
||||
PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
||||
.bank_mc = {
|
||||
|
@ -258,6 +261,7 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
.fixedWingCoordinatedYawGain = 1.0f,
|
||||
.fixedWingCoordinatedPitchGain = 1.0f,
|
||||
.fixedWingItermLimitOnStickPosition = 0.5f,
|
||||
.fixedWingYawItermBankFreeze = 0,
|
||||
|
||||
.loiter_direction = NAV_LOITER_RIGHT,
|
||||
.navVelXyDTermLpfHz = NAV_ACCEL_CUTOFF_FREQUENCY_HZ,
|
||||
|
@ -279,6 +283,7 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
.kalman_w = 4,
|
||||
.kalman_sharpness = 100,
|
||||
.kalmanEnabled = 0,
|
||||
.fixedWingLevelTrim = 0,
|
||||
);
|
||||
|
||||
bool pidInitFilters(void)
|
||||
|
@ -478,7 +483,7 @@ void updatePIDCoefficients()
|
|||
// Airplanes - scale all PIDs according to TPA
|
||||
pidState[axis].kP = pidBank()->pid[axis].P / FP_PID_RATE_P_MULTIPLIER * tpaFactor;
|
||||
pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER * tpaFactor;
|
||||
pidState[axis].kD = 0.0f;
|
||||
pidState[axis].kD = pidBank()->pid[axis].D / FP_PID_RATE_D_MULTIPLIER * tpaFactor;
|
||||
pidState[axis].kFF = pidBank()->pid[axis].FF / FP_PID_RATE_FF_MULTIPLIER * tpaFactor;
|
||||
pidState[axis].kCD = 0.0f;
|
||||
pidState[axis].kT = 0.0f;
|
||||
|
@ -492,7 +497,7 @@ void updatePIDCoefficients()
|
|||
pidState[axis].kFF = 0.0f;
|
||||
|
||||
// Tracking anti-windup requires P/I/D to be all defined which is only true for MC
|
||||
if ((pidBank()->pid[axis].P != 0) && (pidBank()->pid[axis].I != 0)) {
|
||||
if ((pidBank()->pid[axis].P != 0) && (pidBank()->pid[axis].I != 0) && (usedPidControllerType == PID_TYPE_PID)) {
|
||||
pidState[axis].kT = 2.0f / ((pidState[axis].kP / pidState[axis].kI) + (pidState[axis].kD / pidState[axis].kP));
|
||||
} else {
|
||||
pidState[axis].kT = 0;
|
||||
|
@ -533,6 +538,21 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h
|
|||
if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle())
|
||||
angleTarget += scaleRange(MAX(0, navConfig()->fw.cruise_throttle - rcCommand[THROTTLE]), 0, navConfig()->fw.cruise_throttle - PWM_RANGE_MIN, 0, mixerConfig()->fwMinThrottleDownPitchAngle);
|
||||
|
||||
|
||||
//PITCH trim applied by a AutoLevel flight mode and manual pitch trimming
|
||||
if (axis == FD_PITCH && STATE(AIRPLANE)) {
|
||||
/*
|
||||
* fixedWingLevelTrim has opposite sign to rcCommand.
|
||||
* Positive rcCommand means nose should point downwards
|
||||
* Negative rcCommand mean nose should point upwards
|
||||
* This is counter intuitive and a natural way suggests that + should mean UP
|
||||
* This is why fixedWingLevelTrim has opposite sign to rcCommand
|
||||
* Positive fixedWingLevelTrim means nose should point upwards
|
||||
* Negative fixedWingLevelTrim means nose should point downwards
|
||||
*/
|
||||
angleTarget -= DEGREES_TO_DECIDEGREES(fixedWingLevelTrim);
|
||||
}
|
||||
|
||||
const float angleErrorDeg = DECIDEGREES_TO_DEGREES(angleTarget - attitude.raw[axis]);
|
||||
|
||||
float angleRateTarget = constrainf(angleErrorDeg * (pidBank()->pid[PID_LEVEL].P / FP_PID_LEVEL_P_MULTIPLIER), -currentControlRateProfile->stabilized.rates[axis] * 10.0f, currentControlRateProfile->stabilized.rates[axis] * 10.0f);
|
||||
|
@ -590,66 +610,6 @@ static float pTermProcess(pidState_t *pidState, float rateError, float dT) {
|
|||
return pidState->ptermFilterApplyFn(&pidState->ptermLpfState, newPTerm, yawLpfHz, dT);
|
||||
}
|
||||
|
||||
static void applyItermLimiting(pidState_t *pidState) {
|
||||
if (pidState->itermLimitActive) {
|
||||
pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit);
|
||||
} else {
|
||||
pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf);
|
||||
}
|
||||
}
|
||||
|
||||
static void nullRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) {
|
||||
UNUSED(pidState);
|
||||
UNUSED(axis);
|
||||
UNUSED(dT);
|
||||
}
|
||||
|
||||
static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT)
|
||||
{
|
||||
const float rateError = pidState->rateTarget - pidState->gyroRate;
|
||||
const float newPTerm = pTermProcess(pidState, rateError, dT);
|
||||
const float newFFTerm = pidState->rateTarget * pidState->kFF;
|
||||
|
||||
// Calculate integral
|
||||
pidState->errorGyroIf += rateError * pidState->kI * dT;
|
||||
|
||||
applyItermLimiting(pidState);
|
||||
|
||||
if (pidProfile()->fixedWingItermThrowLimit != 0) {
|
||||
pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit);
|
||||
}
|
||||
|
||||
#ifdef USE_AUTOTUNE_FIXED_WING
|
||||
if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) {
|
||||
autotuneFixedWingUpdate(axis, pidState->rateTarget, pidState->gyroRate, newPTerm + newFFTerm);
|
||||
}
|
||||
#endif
|
||||
|
||||
axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidState->pidSumLimit, +pidState->pidSumLimit);
|
||||
|
||||
#ifdef USE_BLACKBOX
|
||||
axisPID_P[axis] = newPTerm;
|
||||
axisPID_I[axis] = pidState->errorGyroIf;
|
||||
axisPID_D[axis] = newFFTerm;
|
||||
axisPID_Setpoint[axis] = pidState->rateTarget;
|
||||
#endif
|
||||
}
|
||||
|
||||
static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, float itermErrorRate)
|
||||
{
|
||||
if (itermRelax) {
|
||||
if (axis < FD_YAW || itermRelax == ITERM_RELAX_RPY) {
|
||||
|
||||
const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint);
|
||||
const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf);
|
||||
|
||||
const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD);
|
||||
return itermErrorRate * itermRelaxFactor;
|
||||
}
|
||||
}
|
||||
|
||||
return itermErrorRate;
|
||||
}
|
||||
#ifdef USE_D_BOOST
|
||||
static float FAST_CODE applyDBoost(pidState_t *pidState, float dT) {
|
||||
|
||||
|
@ -676,10 +636,100 @@ static float applyDBoost(pidState_t *pidState, float dT) {
|
|||
}
|
||||
#endif
|
||||
|
||||
static float dTermProcess(pidState_t *pidState, float dT) {
|
||||
// Calculate new D-term
|
||||
float newDTerm = 0;
|
||||
if (pidState->kD == 0) {
|
||||
// optimisation for when D is zero, often used by YAW axis
|
||||
newDTerm = 0;
|
||||
} else {
|
||||
float delta = pidState->previousRateGyro - pidState->gyroRate;
|
||||
|
||||
delta = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, delta);
|
||||
delta = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, delta);
|
||||
|
||||
// Calculate derivative
|
||||
newDTerm = delta * (pidState->kD / dT) * applyDBoost(pidState, dT);
|
||||
}
|
||||
return(newDTerm);
|
||||
}
|
||||
|
||||
static void applyItermLimiting(pidState_t *pidState) {
|
||||
if (pidState->itermLimitActive) {
|
||||
pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit);
|
||||
} else
|
||||
{
|
||||
pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf);
|
||||
}
|
||||
}
|
||||
|
||||
static void nullRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) {
|
||||
UNUSED(pidState);
|
||||
UNUSED(axis);
|
||||
UNUSED(dT);
|
||||
}
|
||||
|
||||
static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT)
|
||||
{
|
||||
const float rateError = pidState->rateTarget - pidState->gyroRate;
|
||||
const float newPTerm = pTermProcess(pidState, rateError, dT);
|
||||
const float newDTerm = dTermProcess(pidState, dT);
|
||||
const float newFFTerm = pidState->rateTarget * pidState->kFF;
|
||||
|
||||
DEBUG_SET(DEBUG_FW_D, axis, newDTerm);
|
||||
/*
|
||||
* Integral should be updated only if axis Iterm is not frozen
|
||||
*/
|
||||
if (!pidState->itermFreezeActive) {
|
||||
pidState->errorGyroIf += rateError * pidState->kI * dT;
|
||||
}
|
||||
|
||||
applyItermLimiting(pidState);
|
||||
|
||||
if (pidProfile()->fixedWingItermThrowLimit != 0) {
|
||||
pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit);
|
||||
}
|
||||
|
||||
#ifdef USE_AUTOTUNE_FIXED_WING
|
||||
if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) {
|
||||
autotuneFixedWingUpdate(axis, pidState->rateTarget, pidState->gyroRate, newPTerm + newFFTerm);
|
||||
}
|
||||
#endif
|
||||
|
||||
axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit);
|
||||
|
||||
#ifdef USE_BLACKBOX
|
||||
axisPID_P[axis] = newPTerm;
|
||||
axisPID_I[axis] = pidState->errorGyroIf;
|
||||
axisPID_D[axis] = newDTerm;
|
||||
axisPID_Setpoint[axis] = pidState->rateTarget;
|
||||
#endif
|
||||
|
||||
pidState->previousRateGyro = pidState->gyroRate;
|
||||
|
||||
}
|
||||
|
||||
static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, float itermErrorRate)
|
||||
{
|
||||
if (itermRelax) {
|
||||
if (axis < FD_YAW || itermRelax == ITERM_RELAX_RPY) {
|
||||
|
||||
const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint);
|
||||
const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf);
|
||||
|
||||
const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD);
|
||||
return itermErrorRate * itermRelaxFactor;
|
||||
}
|
||||
}
|
||||
|
||||
return itermErrorRate;
|
||||
}
|
||||
|
||||
static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT)
|
||||
{
|
||||
const float rateError = pidState->rateTarget - pidState->gyroRate;
|
||||
const float newPTerm = pTermProcess(pidState, rateError, dT);
|
||||
const float newDTerm = dTermProcess(pidState, dT);
|
||||
|
||||
const float rateTargetDelta = pidState->rateTarget - pidState->previousRateTarget;
|
||||
const float rateTargetDeltaFiltered = biquadFilterApply(&pidState->rateTargetFilter, rateTargetDelta);
|
||||
|
@ -696,21 +746,6 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
|
|||
}
|
||||
DEBUG_SET(DEBUG_CD, axis, newCDTerm);
|
||||
|
||||
// Calculate new D-term
|
||||
float newDTerm;
|
||||
if (pidState->kD == 0) {
|
||||
// optimisation for when D8 is zero, often used by YAW axis
|
||||
newDTerm = 0;
|
||||
} else {
|
||||
float delta = pidState->previousRateGyro - pidState->gyroRate;
|
||||
|
||||
delta = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, delta);
|
||||
delta = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, delta);
|
||||
|
||||
// Calculate derivative
|
||||
newDTerm = delta * (pidState->kD / dT) * applyDBoost(pidState, dT);
|
||||
}
|
||||
|
||||
// TODO: Get feedback from mixer on available correction range for each axis
|
||||
const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm;
|
||||
const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit);
|
||||
|
@ -843,7 +878,7 @@ float pidHeadingHold(float dT)
|
|||
* TURN ASSISTANT mode is an assisted mode to do a Yaw rotation on a ground plane, allowing one-stick turn in RATE more
|
||||
* and keeping ROLL and PITCH attitude though the turn.
|
||||
*/
|
||||
static void NOINLINE pidTurnAssistant(pidState_t *pidState)
|
||||
static void NOINLINE pidTurnAssistant(pidState_t *pidState, float bankAngleTarget, float pitchAngleTarget)
|
||||
{
|
||||
fpVector3_t targetRates;
|
||||
targetRates.x = 0.0f;
|
||||
|
@ -871,8 +906,9 @@ static void NOINLINE pidTurnAssistant(pidState_t *pidState)
|
|||
airspeedForCoordinatedTurn = constrainf(airspeedForCoordinatedTurn, 300, 6000);
|
||||
|
||||
// Calculate rate of turn in Earth frame according to FAA's Pilot's Handbook of Aeronautical Knowledge
|
||||
float bankAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll);
|
||||
float coordinatedTurnRateEarthFrame = GRAVITY_CMSS * tan_approx(-bankAngle) / airspeedForCoordinatedTurn;
|
||||
bankAngleTarget = constrainf(bankAngleTarget, -DEGREES_TO_RADIANS(60), DEGREES_TO_RADIANS(60));
|
||||
float turnRatePitchAdjustmentFactor = cos_approx(fabsf(pitchAngleTarget));
|
||||
float coordinatedTurnRateEarthFrame = GRAVITY_CMSS * tan_approx(-bankAngleTarget) / airspeedForCoordinatedTurn * turnRatePitchAdjustmentFactor;
|
||||
|
||||
targetRates.z = RADIANS_TO_DEGREES(coordinatedTurnRateEarthFrame);
|
||||
}
|
||||
|
@ -933,6 +969,24 @@ void checkItermLimitingActive(pidState_t *pidState)
|
|||
pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate;
|
||||
}
|
||||
|
||||
void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis)
|
||||
{
|
||||
if (usedPidControllerType == PID_TYPE_PIFF && pidProfile()->fixedWingYawItermBankFreeze != 0 && axis == FD_YAW) {
|
||||
// Do not allow yaw I-term to grow when bank angle is too large
|
||||
float bankAngle = DECIDEGREES_TO_DEGREES(attitude.values.roll);
|
||||
if (fabsf(bankAngle) > pidProfile()->fixedWingYawItermBankFreeze && !(FLIGHT_MODE(AUTO_TUNE) || FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance())){
|
||||
pidState->itermFreezeActive = true;
|
||||
} else
|
||||
{
|
||||
pidState->itermFreezeActive = false;
|
||||
}
|
||||
} else
|
||||
{
|
||||
pidState->itermFreezeActive = false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void FAST_CODE pidController(float dT)
|
||||
{
|
||||
if (!pidFiltersConfigured) {
|
||||
|
@ -985,8 +1039,10 @@ void FAST_CODE pidController(float dT)
|
|||
levelingEnabled = false;
|
||||
}
|
||||
|
||||
if (FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance()) {
|
||||
pidTurnAssistant(pidState);
|
||||
if ((FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance()) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || navigationRequiresTurnAssistance())) {
|
||||
float bankAngleTarget = DECIDEGREES_TO_RADIANS(pidRcCommandToAngle(rcCommand[FD_ROLL], pidProfile()->max_angle_inclination[FD_ROLL]));
|
||||
float pitchAngleTarget = DECIDEGREES_TO_RADIANS(pidRcCommandToAngle(rcCommand[FD_PITCH], pidProfile()->max_angle_inclination[FD_PITCH]));
|
||||
pidTurnAssistant(pidState, bankAngleTarget, pitchAngleTarget);
|
||||
canUseFpvCameraMix = false; // FPVANGLEMIX is incompatible with TURN_ASSISTANT
|
||||
}
|
||||
|
||||
|
@ -1003,6 +1059,8 @@ void FAST_CODE pidController(float dT)
|
|||
|
||||
// Step 4: Run gyro-driven control
|
||||
checkItermLimitingActive(&pidState[axis]);
|
||||
checkItermFreezingActive(&pidState[axis], axis);
|
||||
|
||||
pidControllerApplyFn(&pidState[axis], axis, dT);
|
||||
}
|
||||
}
|
||||
|
@ -1107,6 +1165,8 @@ void pidInit(void)
|
|||
gyroKalmanInitialize(pidProfile()->kalman_q, pidProfile()->kalman_w, pidProfile()->kalman_sharpness);
|
||||
}
|
||||
#endif
|
||||
|
||||
fixedWingLevelTrim = pidProfile()->fixedWingLevelTrim;
|
||||
}
|
||||
|
||||
const pidBank_t * pidBank(void) {
|
||||
|
@ -1115,12 +1175,3 @@ const pidBank_t * pidBank(void) {
|
|||
pidBank_t * pidBankMutable(void) {
|
||||
return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc;
|
||||
}
|
||||
|
||||
uint16_t * getD_FFRefByBank(pidBank_t *pidBank, pidIndex_e pidIndex)
|
||||
{
|
||||
if (pidIndexGetType(pidIndex) == PID_TYPE_PIFF) {
|
||||
return &pidBank->pid[pidIndex].FF;
|
||||
} else {
|
||||
return &pidBank->pid[pidIndex].D;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -76,7 +76,7 @@ typedef enum {
|
|||
typedef enum {
|
||||
PID_TYPE_NONE = 0, // Not used in the current platform/mixer/configuration
|
||||
PID_TYPE_PID, // Uses P, I and D terms
|
||||
PID_TYPE_PIFF, // Uses P, I and FF, ignoring D
|
||||
PID_TYPE_PIFF, // Uses P, I, D and FF
|
||||
PID_TYPE_AUTO, // Autodetect
|
||||
} pidType_e;
|
||||
|
||||
|
@ -128,6 +128,7 @@ typedef struct pidProfile_s {
|
|||
float fixedWingCoordinatedYawGain; // This is the gain of the yaw rate required to keep the yaw rate consistent with the turn rate for a coordinated turn.
|
||||
float fixedWingCoordinatedPitchGain; // This is the gain of the pitch rate to keep the pitch angle constant during coordinated turns.
|
||||
float fixedWingItermLimitOnStickPosition; //Do not allow Iterm to grow when stick position is above this point
|
||||
uint16_t fixedWingYawItermBankFreeze; // Freeze yaw Iterm when bank angle is more than this many degrees
|
||||
|
||||
uint8_t loiter_direction; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise)
|
||||
float navVelXyDTermLpfHz;
|
||||
|
@ -150,6 +151,8 @@ typedef struct pidProfile_s {
|
|||
uint16_t kalman_w;
|
||||
uint16_t kalman_sharpness;
|
||||
uint8_t kalmanEnabled;
|
||||
|
||||
float fixedWingLevelTrim;
|
||||
} pidProfile_t;
|
||||
|
||||
typedef struct pidAutotuneConfig_s {
|
||||
|
@ -199,4 +202,3 @@ void autotuneUpdateState(void);
|
|||
void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRateDps, float reachedRateDps, float pidOutput);
|
||||
|
||||
pidType_e pidIndexGetType(pidIndex_e pidIndex);
|
||||
uint16_t * getD_FFRefByBank(pidBank_t *pidBank, pidIndex_e pidIndex);
|
||||
|
|
|
@ -230,15 +230,15 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa
|
|||
|
||||
switch (axis) {
|
||||
case FD_ROLL:
|
||||
blackboxLogAutotuneEvent(ADJUSTMENT_ROLL_D_FF, tuneCurrent[axis].gainFF);
|
||||
blackboxLogAutotuneEvent(ADJUSTMENT_ROLL_FF, tuneCurrent[axis].gainFF);
|
||||
break;
|
||||
|
||||
case FD_PITCH:
|
||||
blackboxLogAutotuneEvent(ADJUSTMENT_PITCH_D_FF, tuneCurrent[axis].gainFF);
|
||||
blackboxLogAutotuneEvent(ADJUSTMENT_PITCH_FF, tuneCurrent[axis].gainFF);
|
||||
break;
|
||||
|
||||
case FD_YAW:
|
||||
blackboxLogAutotuneEvent(ADJUSTMENT_YAW_D_FF, tuneCurrent[axis].gainFF);
|
||||
blackboxLogAutotuneEvent(ADJUSTMENT_YAW_FF, tuneCurrent[axis].gainFF);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -3252,6 +3252,7 @@ uint32_t afatfs_freadSync(afatfsFilePtr_t file, uint8_t *buffer, uint32_t length
|
|||
uint32_t leftToRead = length - bytesRead;
|
||||
uint32_t readNow = afatfs_fread(file, buffer, leftToRead);
|
||||
bytesRead += readNow;
|
||||
buffer += readNow;
|
||||
if (bytesRead < length) {
|
||||
|
||||
if (afatfs_feof(file)) {
|
||||
|
|
|
@ -72,7 +72,7 @@ void lightsUpdate(timeUs_t currentTimeUs)
|
|||
lightsSetStatus(IS_RC_MODE_ACTIVE(BOXLIGHTS), currentTimeUs);
|
||||
}
|
||||
|
||||
void lightsInit()
|
||||
void lightsInit(void)
|
||||
{
|
||||
lightsHardwareInit();
|
||||
}
|
||||
|
|
|
@ -33,6 +33,6 @@ typedef struct lightsConfig_s {
|
|||
PG_DECLARE(lightsConfig_t, lightsConfig);
|
||||
|
||||
void lightsUpdate(timeUs_t currentTimeUs);
|
||||
void lightsInit();
|
||||
void lightsInit(void);
|
||||
|
||||
#endif /* USE_LIGHTS */
|
||||
|
|
|
@ -87,6 +87,7 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "flight/pid.h"
|
||||
#include "flight/rth_estimator.h"
|
||||
#include "flight/wind_estimator.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
@ -185,7 +186,7 @@ static bool osdDisplayHasCanvas;
|
|||
|
||||
#define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees)
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 14);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 15);
|
||||
PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0);
|
||||
|
||||
static int digitCount(int32_t value)
|
||||
|
@ -712,6 +713,8 @@ static const char * osdArmingDisabledReasonMessage(void)
|
|||
return OSD_MESSAGE_STR(OSD_MSG_CLI_ACTIVE);
|
||||
case ARMING_DISABLED_PWM_OUTPUT_ERROR:
|
||||
return OSD_MESSAGE_STR(OSD_MSG_PWM_INIT_ERROR);
|
||||
case ARMING_DISABLED_NO_PREARM:
|
||||
return OSD_MESSAGE_STR(OSD_MSG_NO_PREARM);
|
||||
// Cases without message
|
||||
case ARMING_DISABLED_CMS_MENU:
|
||||
FALLTHROUGH;
|
||||
|
@ -869,18 +872,15 @@ void osdCrosshairPosition(uint8_t *x, uint8_t *y)
|
|||
**/
|
||||
static void osdFormatThrottlePosition(char *buff, bool autoThr, textAttributes_t *elemAttr)
|
||||
{
|
||||
const int minThrottle = getThrottleIdleValue();
|
||||
buff[0] = SYM_BLANK;
|
||||
buff[1] = SYM_THR;
|
||||
int16_t thr = (constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX ) - minThrottle) * 100 / (motorConfig()->maxthrottle - minThrottle);
|
||||
if (autoThr && navigationIsControllingThrottle()) {
|
||||
buff[0] = SYM_AUTO_THR0;
|
||||
buff[1] = SYM_AUTO_THR1;
|
||||
thr = (constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
|
||||
if (isFixedWingAutoThrottleManuallyIncreased())
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr);
|
||||
}
|
||||
tfp_sprintf(buff + 2, "%3d", thr);
|
||||
tfp_sprintf(buff + 2, "%3d", getThrottlePercent());
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -948,6 +948,14 @@ int16_t osdGetHeading(void)
|
|||
return attitude.values.yaw;
|
||||
}
|
||||
|
||||
int16_t osdPanServoHomeDirectionOffset(void)
|
||||
{
|
||||
int8_t servoIndex = osdConfig()->pan_servo_index;
|
||||
int16_t servoPosition = servo[servoIndex];
|
||||
int16_t servoMiddle = servoParams(servoIndex)->middle;
|
||||
return (int16_t)CENTIDEGREES_TO_DEGREES((servoPosition - servoMiddle) * osdConfig()->pan_servo_pwm2centideg);
|
||||
}
|
||||
|
||||
// Returns a heading angle in degrees normalized to [0, 360).
|
||||
int osdGetHeadingAngle(int angle)
|
||||
{
|
||||
|
@ -1121,13 +1129,6 @@ static void osdDrawRadar(uint16_t *drawn, uint32_t *usedScale)
|
|||
osdDrawMap(reference, 0, SYM_ARROW_UP, GPS_distanceToHome, poiDirection, SYM_HOME, drawn, usedScale);
|
||||
}
|
||||
|
||||
static int16_t osdGet3DSpeed(void)
|
||||
{
|
||||
int16_t vert_speed = getEstimatedActualVelocity(Z);
|
||||
int16_t hor_speed = gpsSol.groundSpeed;
|
||||
return (int16_t)sqrtf(sq(hor_speed) + sq(vert_speed));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
static void osdFormatPidControllerOutput(char *buff, const char *label, const pidController_t *pidController, uint8_t scale, bool showDecimal) {
|
||||
|
@ -1164,7 +1165,49 @@ static void osdDisplayBatteryVoltage(uint8_t elemPosX, uint8_t elemPosY, uint16_
|
|||
displayWriteWithAttr(osdDisplayPort, elemPosX + 1, elemPosY, buff, elemAttr);
|
||||
}
|
||||
|
||||
static void osdDisplayPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char *str, pidIndex_e pidIndex, adjustmentFunction_e adjFuncP, adjustmentFunction_e adjFuncI, adjustmentFunction_e adjFuncD)
|
||||
static void osdDisplayFlightPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char *str, pidIndex_e pidIndex, adjustmentFunction_e adjFuncP, adjustmentFunction_e adjFuncI, adjustmentFunction_e adjFuncD, adjustmentFunction_e adjFuncFF)
|
||||
{
|
||||
textAttributes_t elemAttr;
|
||||
char buff[4];
|
||||
|
||||
const pid8_t *pid = &pidBank()->pid[pidIndex];
|
||||
pidType_e pidType = pidIndexGetType(pidIndex);
|
||||
|
||||
displayWrite(osdDisplayPort, elemPosX, elemPosY, str);
|
||||
|
||||
if (pidType == PID_TYPE_NONE) {
|
||||
// PID is not used in this configuration. Draw dashes.
|
||||
// XXX: Keep this in sync with the %3d format and spacing used below
|
||||
displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - - -");
|
||||
return;
|
||||
}
|
||||
|
||||
elemAttr = TEXT_ATTRIBUTES_NONE;
|
||||
tfp_sprintf(buff, "%3d", pid->P);
|
||||
if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P))))
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr);
|
||||
|
||||
elemAttr = TEXT_ATTRIBUTES_NONE;
|
||||
tfp_sprintf(buff, "%3d", pid->I);
|
||||
if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I))))
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr);
|
||||
|
||||
elemAttr = TEXT_ATTRIBUTES_NONE;
|
||||
tfp_sprintf(buff, "%3d", pid->D);
|
||||
if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D))))
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr);
|
||||
|
||||
elemAttr = TEXT_ATTRIBUTES_NONE;
|
||||
tfp_sprintf(buff, "%3d", pid->FF);
|
||||
if ((isAdjustmentFunctionSelected(adjFuncFF)) || (((adjFuncFF == ADJUSTMENT_ROLL_FF) || (adjFuncFF == ADJUSTMENT_PITCH_FF)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_FF))))
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 16, elemPosY, buff, elemAttr);
|
||||
}
|
||||
|
||||
static void osdDisplayNavPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char *str, pidIndex_e pidIndex, adjustmentFunction_e adjFuncP, adjustmentFunction_e adjFuncI, adjustmentFunction_e adjFuncD)
|
||||
{
|
||||
textAttributes_t elemAttr;
|
||||
char buff[4];
|
||||
|
@ -1195,7 +1238,7 @@ static void osdDisplayPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char *
|
|||
|
||||
elemAttr = TEXT_ATTRIBUTES_NONE;
|
||||
tfp_sprintf(buff, "%3d", pidType == PID_TYPE_PIFF ? pid->FF : pid->D);
|
||||
if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D_FF) || (adjFuncD == ADJUSTMENT_PITCH_D_FF)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D_FF))))
|
||||
if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D))))
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr);
|
||||
}
|
||||
|
@ -1337,7 +1380,11 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
}
|
||||
else
|
||||
{
|
||||
int homeDirection = GPS_directionToHome - DECIDEGREES_TO_DEGREES(osdGetHeading());
|
||||
int16_t panHomeDirOffset = 0;
|
||||
if (!(osdConfig()->pan_servo_pwm2centideg == 0)){
|
||||
panHomeDirOffset = osdPanServoHomeDirectionOffset();
|
||||
}
|
||||
int homeDirection = GPS_directionToHome - DECIDEGREES_TO_DEGREES(osdGetHeading()) + panHomeDirOffset;
|
||||
osdDrawDirArrow(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), homeDirection);
|
||||
}
|
||||
} else {
|
||||
|
@ -1604,6 +1651,8 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
p = "ANGL";
|
||||
else if (FLIGHT_MODE(HORIZON_MODE))
|
||||
p = "HOR ";
|
||||
else if (FLIGHT_MODE(FLIP_OVER_AFTER_CRASH))
|
||||
p = "TURT";
|
||||
|
||||
displayWrite(osdDisplayPort, elemPosX, elemPosY, p);
|
||||
return true;
|
||||
|
@ -1688,7 +1737,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
}
|
||||
|
||||
case OSD_CRSF_SNR_DB: {
|
||||
const char* showsnr = "-12";
|
||||
const char* showsnr = "-20";
|
||||
const char* hidesnr = " ";
|
||||
int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR;
|
||||
if (osdSNR_Alarm <= osdConfig()->snr_alarm) {
|
||||
|
@ -1765,9 +1814,6 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
gpsLocation_t wp2;
|
||||
int j;
|
||||
|
||||
tfp_sprintf(buff, "W%u/%u", posControl.activeWaypointIndex, posControl.waypointCount);
|
||||
displayWrite(osdGetDisplayPort(), 13, osdConfig()->hud_margin_v - 1, buff);
|
||||
|
||||
for (int i = osdConfig()->hud_wp_disp - 1; i >= 0 ; i--) { // Display in reverse order so the next WP is always written on top
|
||||
j = posControl.activeWaypointIndex + i;
|
||||
if (posControl.waypointList[j].lat != 0 && posControl.waypointList[j].lon != 0 && j <= posControl.waypointCount) {
|
||||
|
@ -1860,35 +1906,35 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
#endif
|
||||
|
||||
case OSD_ROLL_PIDS:
|
||||
osdDisplayPIDValues(elemPosX, elemPosY, "ROL", PID_ROLL, ADJUSTMENT_ROLL_P, ADJUSTMENT_ROLL_I, ADJUSTMENT_ROLL_D_FF);
|
||||
osdDisplayFlightPIDValues(elemPosX, elemPosY, "ROL", PID_ROLL, ADJUSTMENT_ROLL_P, ADJUSTMENT_ROLL_I, ADJUSTMENT_ROLL_D, ADJUSTMENT_ROLL_FF);
|
||||
return true;
|
||||
|
||||
case OSD_PITCH_PIDS:
|
||||
osdDisplayPIDValues(elemPosX, elemPosY, "PIT", PID_PITCH, ADJUSTMENT_PITCH_P, ADJUSTMENT_PITCH_I, ADJUSTMENT_PITCH_D_FF);
|
||||
osdDisplayFlightPIDValues(elemPosX, elemPosY, "PIT", PID_PITCH, ADJUSTMENT_PITCH_P, ADJUSTMENT_PITCH_I, ADJUSTMENT_PITCH_D, ADJUSTMENT_PITCH_FF);
|
||||
return true;
|
||||
|
||||
case OSD_YAW_PIDS:
|
||||
osdDisplayPIDValues(elemPosX, elemPosY, "YAW", PID_YAW, ADJUSTMENT_YAW_P, ADJUSTMENT_YAW_I, ADJUSTMENT_YAW_D_FF);
|
||||
osdDisplayFlightPIDValues(elemPosX, elemPosY, "YAW", PID_YAW, ADJUSTMENT_YAW_P, ADJUSTMENT_YAW_I, ADJUSTMENT_YAW_D, ADJUSTMENT_YAW_FF);
|
||||
return true;
|
||||
|
||||
case OSD_LEVEL_PIDS:
|
||||
osdDisplayPIDValues(elemPosX, elemPosY, "LEV", PID_LEVEL, ADJUSTMENT_LEVEL_P, ADJUSTMENT_LEVEL_I, ADJUSTMENT_LEVEL_D);
|
||||
osdDisplayNavPIDValues(elemPosX, elemPosY, "LEV", PID_LEVEL, ADJUSTMENT_LEVEL_P, ADJUSTMENT_LEVEL_I, ADJUSTMENT_LEVEL_D);
|
||||
return true;
|
||||
|
||||
case OSD_POS_XY_PIDS:
|
||||
osdDisplayPIDValues(elemPosX, elemPosY, "PXY", PID_POS_XY, ADJUSTMENT_POS_XY_P, ADJUSTMENT_POS_XY_I, ADJUSTMENT_POS_XY_D);
|
||||
osdDisplayNavPIDValues(elemPosX, elemPosY, "PXY", PID_POS_XY, ADJUSTMENT_POS_XY_P, ADJUSTMENT_POS_XY_I, ADJUSTMENT_POS_XY_D);
|
||||
return true;
|
||||
|
||||
case OSD_POS_Z_PIDS:
|
||||
osdDisplayPIDValues(elemPosX, elemPosY, "PZ", PID_POS_Z, ADJUSTMENT_POS_Z_P, ADJUSTMENT_POS_Z_I, ADJUSTMENT_POS_Z_D);
|
||||
osdDisplayNavPIDValues(elemPosX, elemPosY, "PZ", PID_POS_Z, ADJUSTMENT_POS_Z_P, ADJUSTMENT_POS_Z_I, ADJUSTMENT_POS_Z_D);
|
||||
return true;
|
||||
|
||||
case OSD_VEL_XY_PIDS:
|
||||
osdDisplayPIDValues(elemPosX, elemPosY, "VXY", PID_VEL_XY, ADJUSTMENT_VEL_XY_P, ADJUSTMENT_VEL_XY_I, ADJUSTMENT_VEL_XY_D);
|
||||
osdDisplayNavPIDValues(elemPosX, elemPosY, "VXY", PID_VEL_XY, ADJUSTMENT_VEL_XY_P, ADJUSTMENT_VEL_XY_I, ADJUSTMENT_VEL_XY_D);
|
||||
return true;
|
||||
|
||||
case OSD_VEL_Z_PIDS:
|
||||
osdDisplayPIDValues(elemPosX, elemPosY, "VZ", PID_VEL_Z, ADJUSTMENT_VEL_Z_P, ADJUSTMENT_VEL_Z_I, ADJUSTMENT_VEL_Z_D);
|
||||
osdDisplayNavPIDValues(elemPosX, elemPosY, "VZ", PID_VEL_Z, ADJUSTMENT_VEL_Z_P, ADJUSTMENT_VEL_Z_I, ADJUSTMENT_VEL_Z_D);
|
||||
return true;
|
||||
|
||||
case OSD_HEADING_P:
|
||||
|
@ -2192,12 +2238,21 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_DEBUG:
|
||||
{
|
||||
// Longest representable string is -2147483648, hence 11 characters
|
||||
/*
|
||||
* Longest representable string is -2147483648 does not fit in the screen.
|
||||
* Only 7 digits for negative and 8 digits for positive values allowed
|
||||
*/
|
||||
for (uint8_t bufferIndex = 0; bufferIndex < DEBUG32_VALUE_COUNT; ++elemPosY, bufferIndex += 2) {
|
||||
tfp_sprintf(buff, "[%u]=%11ld [%u]=%11ld", bufferIndex, debug[bufferIndex], bufferIndex+1, debug[bufferIndex+1]);
|
||||
tfp_sprintf(
|
||||
buff,
|
||||
"[%u]=%8ld [%u]=%8ld",
|
||||
bufferIndex,
|
||||
constrain(debug[bufferIndex], -9999999, 99999999),
|
||||
bufferIndex+1,
|
||||
constrain(debug[bufferIndex+1], -9999999, 99999999)
|
||||
);
|
||||
displayWrite(osdDisplayPort, elemPosX, elemPosY, buff);
|
||||
}
|
||||
break;
|
||||
|
@ -2433,21 +2488,21 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
char buff[4];
|
||||
textAttributes_t attr;
|
||||
|
||||
displayWrite(osdDisplayPort, elemPosX, elemPosY, "TPA BP");
|
||||
|
||||
displayWrite(osdDisplayPort, elemPosX, elemPosY, "TPA");
|
||||
attr = TEXT_ATTRIBUTES_NONE;
|
||||
tfp_sprintf(buff, "TPA %3d", currentControlRateProfile->throttle.dynPID);
|
||||
tfp_sprintf(buff, "%3d", currentControlRateProfile->throttle.dynPID);
|
||||
if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA)) {
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(attr);
|
||||
}
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, attr);
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 5, elemPosY, buff, attr);
|
||||
|
||||
displayWrite(osdDisplayPort, elemPosX, elemPosY + 1, "BP");
|
||||
attr = TEXT_ATTRIBUTES_NONE;
|
||||
tfp_sprintf(buff, "BP %4d", currentControlRateProfile->throttle.pa_breakpoint);
|
||||
tfp_sprintf(buff, "%4d", currentControlRateProfile->throttle.pa_breakpoint);
|
||||
if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA_BREAKPOINT)) {
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(attr);
|
||||
}
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY + 1, buff, attr);
|
||||
displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY + 1, buff, attr);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
@ -2596,6 +2651,8 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
|
|||
.right_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE,
|
||||
.sidebar_scroll_arrows = 0,
|
||||
.osd_home_position_arm_screen = true,
|
||||
.pan_servo_index = 0,
|
||||
.pan_servo_pwm2centideg = 0,
|
||||
|
||||
.units = OSD_UNIT_METRIC,
|
||||
.main_voltage_decimals = 1,
|
||||
|
|
|
@ -76,6 +76,7 @@
|
|||
#define OSD_MSG_INVALID_SETTING "INVALID SETTING"
|
||||
#define OSD_MSG_CLI_ACTIVE "CLI IS ACTIVE"
|
||||
#define OSD_MSG_PWM_INIT_ERROR "PWM INIT ERROR"
|
||||
#define OSD_MSG_NO_PREARM "NO PREARM"
|
||||
#define OSD_MSG_RTH_FS "(RTH)"
|
||||
#define OSD_MSG_EMERG_LANDING_FS "(EMERGENCY LANDING)"
|
||||
#define OSD_MSG_MOVE_EXIT_FS "!MOVE STICKS TO EXIT FS!"
|
||||
|
@ -292,7 +293,7 @@ typedef struct osdConfig_s {
|
|||
float gforce_axis_alarm_min;
|
||||
float gforce_axis_alarm_max;
|
||||
#ifdef USE_SERIALRX_CRSF
|
||||
int16_t snr_alarm; //CRSF SNR alarm in dB
|
||||
int8_t snr_alarm; //CRSF SNR alarm in dB
|
||||
int8_t link_quality_alarm;
|
||||
#endif
|
||||
#ifdef USE_BARO
|
||||
|
@ -348,7 +349,8 @@ typedef struct osdConfig_s {
|
|||
uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type.
|
||||
uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar.
|
||||
bool osd_home_position_arm_screen;
|
||||
|
||||
uint8_t pan_servo_index; // Index of the pan servo used for home direction offset
|
||||
int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm
|
||||
uint8_t crsf_lq_format;
|
||||
|
||||
} osdConfig_t;
|
||||
|
|
|
@ -36,6 +36,8 @@
|
|||
#include "io/osd_common.h"
|
||||
#include "io/osd_grid.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#if defined(USE_OSD)
|
||||
|
||||
#define CANVAS_DEFAULT_GRID_ELEMENT_WIDTH OSD_CHAR_WIDTH
|
||||
|
@ -152,3 +154,12 @@ void osdDrawSidebars(displayPort_t *display, displayCanvas_t *canvas)
|
|||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_GPS
|
||||
int16_t osdGet3DSpeed(void)
|
||||
{
|
||||
int16_t vert_speed = getEstimatedActualVelocity(Z);
|
||||
int16_t hor_speed = gpsSol.groundSpeed;
|
||||
return (int16_t)sqrtf(sq(hor_speed) + sq(vert_speed));
|
||||
}
|
||||
#endif
|
|
@ -82,3 +82,8 @@ void osdDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *canvas, c
|
|||
// grid slots.
|
||||
void osdDrawHeadingGraph(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, int heading);
|
||||
void osdDrawSidebars(displayPort_t *display, displayCanvas_t *canvas);
|
||||
|
||||
#ifdef USE_GPS
|
||||
int16_t osdGet3DSpeed(void);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -58,6 +58,7 @@
|
|||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/osd_dji_hd.h"
|
||||
#include "io/osd_common.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
@ -68,6 +69,7 @@
|
|||
#include "sensors/acceleration.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
#include "sensors/temperature.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
|
||||
#include "msp/msp.h"
|
||||
#include "msp/msp_protocol.h"
|
||||
|
@ -118,11 +120,12 @@
|
|||
* but reuse the packet decoder to minimize code duplication
|
||||
*/
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig, PG_DJI_OSD_CONFIG, 1);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig, PG_DJI_OSD_CONFIG, 2);
|
||||
PG_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig,
|
||||
.use_name_for_messages = true,
|
||||
.esc_temperature_source = DJI_OSD_TEMP_ESC,
|
||||
.proto_workarounds = DJI_OSD_USE_NON_STANDARD_MSP_ESC_SENSOR_DATA,
|
||||
.speedSource = DJI_OSD_SPEED_GROUND,
|
||||
);
|
||||
|
||||
// External dependency on looptime
|
||||
|
@ -500,6 +503,8 @@ static const char * osdArmingDisabledReasonMessage(void)
|
|||
return OSD_MESSAGE_STR("CLI");
|
||||
case ARMING_DISABLED_PWM_OUTPUT_ERROR:
|
||||
return OSD_MESSAGE_STR("PWM ERR");
|
||||
case ARMING_DISABLED_NO_PREARM:
|
||||
return OSD_MESSAGE_STR("NO PREARM");
|
||||
// Cases without message
|
||||
case ARMING_DISABLED_CMS_MENU:
|
||||
FALLTHROUGH;
|
||||
|
@ -639,13 +644,6 @@ static int32_t osdConvertVelocityToUnit(int32_t vel)
|
|||
return -1;
|
||||
}
|
||||
|
||||
static int16_t osdDJIGet3DSpeed(void)
|
||||
{
|
||||
int16_t vert_speed = getEstimatedActualVelocity(Z);
|
||||
int16_t hor_speed = gpsSol.groundSpeed;
|
||||
return (int16_t)sqrtf(sq(hor_speed) + sq(vert_speed));
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts velocity into a string based on the current unit system.
|
||||
* @param alt Raw velocity (i.e. as taken from gpsSol.groundSpeed in centimeters/seconds)
|
||||
|
@ -670,7 +668,7 @@ static void osdDJIFormatThrottlePosition(char *buff, bool autoThr )
|
|||
thr = rcCommand[THROTTLE];
|
||||
}
|
||||
|
||||
tfp_sprintf(buff, "%3d%s", (constrain(thr, PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN), "%THR");
|
||||
tfp_sprintf(buff, "%3ld%s", (constrain(thr, PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN), "%THR");
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -766,7 +764,7 @@ static void djiSerializeCraftNameOverride(sbuf_t *dst, const char * name)
|
|||
osdDJIFormatThrottlePosition(djibuf,true);
|
||||
break;
|
||||
case 'S':
|
||||
osdDJIFormatVelocityStr(djibuf, osdDJIGet3DSpeed());
|
||||
osdDJIFormatVelocityStr(djibuf, osdGet3DSpeed());
|
||||
break;
|
||||
case 'E':
|
||||
osdDJIEfficiencyMahPerKM(djibuf);
|
||||
|
@ -1004,7 +1002,21 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms
|
|||
sbufWriteU32(dst, gpsSol.llh.lat);
|
||||
sbufWriteU32(dst, gpsSol.llh.lon);
|
||||
sbufWriteU16(dst, gpsSol.llh.alt / 100);
|
||||
sbufWriteU16(dst, gpsSol.groundSpeed);
|
||||
|
||||
int reportedSpeed = 0;
|
||||
if (djiOsdConfig()->speedSource == DJI_OSD_SPEED_GROUND) {
|
||||
reportedSpeed = gpsSol.groundSpeed;
|
||||
} else if (djiOsdConfig()->speedSource == DJI_OSD_SPEED_3D) {
|
||||
reportedSpeed = osdGet3DSpeed();
|
||||
} else if (djiOsdConfig()->speedSource == DJI_OSD_SPEED_AIR) {
|
||||
#ifdef USE_PITOT
|
||||
reportedSpeed = pitot.airSpeed;
|
||||
#else
|
||||
reportedSpeed = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
sbufWriteU16(dst, reportedSpeed);
|
||||
sbufWriteU16(dst, gpsSol.groundCourse);
|
||||
break;
|
||||
|
||||
|
|
|
@ -68,6 +68,12 @@ enum djiOsdTempSource_e {
|
|||
DJI_OSD_TEMP_BARO = 2
|
||||
};
|
||||
|
||||
enum djiOsdSpeedSource_e {
|
||||
DJI_OSD_SPEED_GROUND = 0,
|
||||
DJI_OSD_SPEED_3D = 1,
|
||||
DJI_OSD_SPEED_AIR = 2
|
||||
};
|
||||
|
||||
enum djiOsdProtoWorkarounds_e {
|
||||
DJI_OSD_USE_NON_STANDARD_MSP_ESC_SENSOR_DATA = 1 << 0,
|
||||
};
|
||||
|
@ -76,6 +82,7 @@ typedef struct djiOsdConfig_s {
|
|||
uint8_t use_name_for_messages;
|
||||
uint8_t esc_temperature_source;
|
||||
uint8_t proto_workarounds;
|
||||
uint8_t speedSource;
|
||||
} djiOsdConfig_t;
|
||||
|
||||
PG_DECLARE(djiOsdConfig_t, djiOsdConfig);
|
||||
|
|
|
@ -39,10 +39,11 @@
|
|||
|
||||
#if defined(USE_VTX_CONTROL)
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 3);
|
||||
|
||||
PG_RESET_TEMPLATE(vtxConfig_t, vtxConfig,
|
||||
.halfDuplex = true,
|
||||
.smartAudioEarlyAkkWorkaroundEnable = true,
|
||||
);
|
||||
|
||||
static uint8_t locked = 0;
|
||||
|
|
|
@ -31,6 +31,7 @@ typedef struct vtxChannelActivationCondition_s {
|
|||
typedef struct vtxConfig_s {
|
||||
vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
|
||||
uint8_t halfDuplex;
|
||||
uint8_t smartAudioEarlyAkkWorkaroundEnable;
|
||||
} vtxConfig_t;
|
||||
|
||||
PG_DECLARE(vtxConfig_t, vtxConfig);
|
||||
|
|
|
@ -506,7 +506,8 @@ static void saSendFrame(uint8_t *buf, int len)
|
|||
// XXX: Workaround for early AKK SAudio-enabled VTX bug,
|
||||
// shouldn't cause any problems with VTX with properly
|
||||
// implemented SAudio.
|
||||
serialWrite(smartAudioSerialPort, 0x00);
|
||||
//Update: causes problem with new AKK AIO camera connected to SoftUART
|
||||
if (vtxConfig()->smartAudioEarlyAkkWorkaroundEnable) serialWrite(smartAudioSerialPort, 0x00);
|
||||
|
||||
sa_lastTransmissionMs = millis();
|
||||
saStat.pktsent++;
|
||||
|
|
|
@ -63,6 +63,7 @@
|
|||
#define MSP2_INAV_GVAR_STATUS 0x2027
|
||||
#define MSP2_INAV_PROGRAMMING_PID 0x2028
|
||||
#define MSP2_INAV_SET_PROGRAMMING_PID 0x2029
|
||||
#define MSP2_INAV_PROGRAMMING_PID_STATUS 0x202A
|
||||
|
||||
#define MSP2_PID 0x2030
|
||||
#define MSP2_SET_PID 0x2031
|
||||
|
@ -77,3 +78,5 @@
|
|||
|
||||
#define MSP2_INAV_SAFEHOME 0x2038
|
||||
#define MSP2_INAV_SET_SAFEHOME 0x2039
|
||||
|
||||
#define MSP2_INAV_MISC2 0x203A
|
||||
|
|
|
@ -91,7 +91,7 @@ STATIC_ASSERT(NAV_MAX_WAYPOINTS < 254, NAV_MAX_WAYPOINTS_exceeded_allowable_rang
|
|||
PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 0);
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 9);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 10);
|
||||
|
||||
PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
||||
.general = {
|
||||
|
@ -144,6 +144,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
|||
.braking_bank_angle = 40, // Max braking angle
|
||||
.posDecelerationTime = 120, // posDecelerationTime * 100
|
||||
.posResponseExpo = 10, // posResponseExpo * 100
|
||||
.slowDownForTurning = true,
|
||||
},
|
||||
|
||||
// Fixed wing
|
||||
|
@ -159,7 +160,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
|||
.pitch_to_throttle = 10, // pwm units per degree of pitch (10pwm units ~ 1% throttle)
|
||||
.pitch_to_throttle_smooth = 6,
|
||||
.pitch_to_throttle_thresh = 50,
|
||||
.loiter_radius = 5000, // 50m
|
||||
.loiter_radius = 7500, // 75m
|
||||
|
||||
//Fixed wing landing
|
||||
.land_dive_angle = 2, // 2 degrees dive by default
|
||||
|
@ -1923,132 +1924,6 @@ static fpVector3_t * rthGetHomeTargetPosition(rthTargetMode_e mode)
|
|||
return &posControl.rthState.homeTmpWaypoint;
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Float point PID-controller implementation
|
||||
*-----------------------------------------------------------*/
|
||||
// Implementation of PID with back-calculation I-term anti-windup
|
||||
// Control System Design, Lecture Notes for ME 155A by Karl Johan Åström (p.228)
|
||||
// http://www.cds.caltech.edu/~murray/courses/cds101/fa02/caltech/astrom-ch6.pdf
|
||||
float navPidApply3(
|
||||
pidController_t *pid,
|
||||
const float setpoint,
|
||||
const float measurement,
|
||||
const float dt,
|
||||
const float outMin,
|
||||
const float outMax,
|
||||
const pidControllerFlags_e pidFlags,
|
||||
const float gainScaler,
|
||||
const float dTermScaler
|
||||
) {
|
||||
float newProportional, newDerivative, newFeedForward;
|
||||
float error = setpoint - measurement;
|
||||
|
||||
/* P-term */
|
||||
newProportional = error * pid->param.kP * gainScaler;
|
||||
|
||||
/* D-term */
|
||||
if (pid->reset) {
|
||||
pid->last_input = (pidFlags & PID_DTERM_FROM_ERROR) ? error : measurement;
|
||||
pid->reset = false;
|
||||
}
|
||||
|
||||
if (pidFlags & PID_DTERM_FROM_ERROR) {
|
||||
/* Error-tracking D-term */
|
||||
newDerivative = (error - pid->last_input) / dt;
|
||||
pid->last_input = error;
|
||||
} else {
|
||||
/* Measurement tracking D-term */
|
||||
newDerivative = -(measurement - pid->last_input) / dt;
|
||||
pid->last_input = measurement;
|
||||
}
|
||||
|
||||
if (pid->dTermLpfHz > 0) {
|
||||
newDerivative = pid->param.kD * pt1FilterApply4(&pid->dterm_filter_state, newDerivative, pid->dTermLpfHz, dt);
|
||||
} else {
|
||||
newDerivative = pid->param.kD * newDerivative;
|
||||
}
|
||||
|
||||
newDerivative = newDerivative * gainScaler * dTermScaler;
|
||||
|
||||
if (pidFlags & PID_ZERO_INTEGRATOR) {
|
||||
pid->integrator = 0.0f;
|
||||
}
|
||||
|
||||
/*
|
||||
* Compute FeedForward parameter
|
||||
*/
|
||||
newFeedForward = setpoint * pid->param.kFF * gainScaler;
|
||||
|
||||
/* Pre-calculate output and limit it if actuator is saturating */
|
||||
const float outVal = newProportional + (pid->integrator * gainScaler) + newDerivative + newFeedForward;
|
||||
const float outValConstrained = constrainf(outVal, outMin, outMax);
|
||||
|
||||
pid->proportional = newProportional;
|
||||
pid->integral = pid->integrator;
|
||||
pid->derivative = newDerivative;
|
||||
pid->feedForward = newFeedForward;
|
||||
pid->output_constrained = outValConstrained;
|
||||
|
||||
/* Update I-term */
|
||||
if (!(pidFlags & PID_ZERO_INTEGRATOR)) {
|
||||
const float newIntegrator = pid->integrator + (error * pid->param.kI * gainScaler * dt) + ((outValConstrained - outVal) * pid->param.kT * dt);
|
||||
|
||||
if (pidFlags & PID_SHRINK_INTEGRATOR) {
|
||||
// Only allow integrator to shrink
|
||||
if (fabsf(newIntegrator) < fabsf(pid->integrator)) {
|
||||
pid->integrator = newIntegrator;
|
||||
}
|
||||
}
|
||||
else {
|
||||
pid->integrator = newIntegrator;
|
||||
}
|
||||
}
|
||||
|
||||
if (pidFlags & PID_LIMIT_INTEGRATOR) {
|
||||
pid->integrator = constrainf(pid->integrator, outMin, outMax);
|
||||
}
|
||||
|
||||
return outValConstrained;
|
||||
}
|
||||
|
||||
float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags)
|
||||
{
|
||||
return navPidApply3(pid, setpoint, measurement, dt, outMin, outMax, pidFlags, 1.0f, 1.0f);
|
||||
}
|
||||
|
||||
void navPidReset(pidController_t *pid)
|
||||
{
|
||||
pid->reset = true;
|
||||
pid->proportional = 0.0f;
|
||||
pid->integral = 0.0f;
|
||||
pid->derivative = 0.0f;
|
||||
pid->integrator = 0.0f;
|
||||
pid->last_input = 0.0f;
|
||||
pid->feedForward = 0.0f;
|
||||
pt1FilterReset(&pid->dterm_filter_state, 0.0f);
|
||||
pid->output_constrained = 0.0f;
|
||||
}
|
||||
|
||||
void navPidInit(pidController_t *pid, float _kP, float _kI, float _kD, float _kFF, float _dTermLpfHz)
|
||||
{
|
||||
pid->param.kP = _kP;
|
||||
pid->param.kI = _kI;
|
||||
pid->param.kD = _kD;
|
||||
pid->param.kFF = _kFF;
|
||||
|
||||
if (_kI > 1e-6f && _kP > 1e-6f) {
|
||||
float Ti = _kP / _kI;
|
||||
float Td = _kD / _kP;
|
||||
pid->param.kT = 2.0f / (Ti + Td);
|
||||
}
|
||||
else {
|
||||
pid->param.kI = 0.0;
|
||||
pid->param.kT = 0.0;
|
||||
}
|
||||
pid->dTermLpfHz = _dTermLpfHz;
|
||||
navPidReset(pid);
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Detects if thrust vector is facing downwards
|
||||
*-----------------------------------------------------------*/
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/vector.h"
|
||||
#include "common/fp_pid.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
|
||||
|
@ -224,6 +225,7 @@ typedef struct navConfig_s {
|
|||
uint8_t braking_bank_angle; // Max angle [deg] that MR is allowed duing braking boost phase
|
||||
uint8_t posDecelerationTime; // Brake time parameter
|
||||
uint8_t posResponseExpo; // Position controller expo (taret vel expo for MC)
|
||||
bool slowDownForTurning; // Slow down during WP missions when changing heading on next waypoint
|
||||
} mc;
|
||||
|
||||
struct {
|
||||
|
@ -330,33 +332,6 @@ typedef struct navDestinationPath_s {
|
|||
int32_t bearing; // deg * 100
|
||||
} navDestinationPath_t;
|
||||
|
||||
typedef struct {
|
||||
float kP;
|
||||
float kI;
|
||||
float kD;
|
||||
float kT; // Tracking gain (anti-windup)
|
||||
float kFF; // FeedForward Component
|
||||
} pidControllerParam_t;
|
||||
|
||||
typedef struct {
|
||||
float kP;
|
||||
} pControllerParam_t;
|
||||
|
||||
typedef struct {
|
||||
bool reset;
|
||||
pidControllerParam_t param;
|
||||
pt1Filter_t dterm_filter_state; // last derivative for low-pass filter
|
||||
float dTermLpfHz; // dTerm low pass filter cutoff frequency
|
||||
float integrator; // integrator value
|
||||
float last_input; // last input for derivative
|
||||
|
||||
float integral; // used integral value in output
|
||||
float proportional; // used proportional value in output
|
||||
float derivative; // used derivative value in output
|
||||
float feedForward; // used FeedForward value in output
|
||||
float output_constrained; // controller output constrained
|
||||
} pidController_t;
|
||||
|
||||
typedef struct navigationPIDControllers_s {
|
||||
/* Multicopter PIDs */
|
||||
pidController_t pos[XYZ_AXIS_COUNT];
|
||||
|
|
|
@ -48,6 +48,8 @@
|
|||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
#define SWING_LAUNCH_MIN_ROTATION_RATE DEGREES_TO_RADIANS(100) // expect minimum 100dps rotation rate
|
||||
#define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms
|
||||
#define UNUSED(x) ((void)(x))
|
||||
|
@ -316,10 +318,11 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_DETECTION(timeU
|
|||
|
||||
const bool isBungeeLaunched = isForwardAccelerationHigh && isAircraftAlmostLevel;
|
||||
const bool isSwingLaunched = (swingVelocity > navConfig()->fw.launch_velocity_thresh) && (imuMeasuredAccelBF.x > 0);
|
||||
const bool isForwardLaunched = isGPSHeadingValid() && (gpsSol.groundSpeed > navConfig()->fw.launch_velocity_thresh) && (imuMeasuredAccelBF.x > 0);
|
||||
|
||||
applyThrottleIdleLogic(false);
|
||||
|
||||
if (isBungeeLaunched || isSwingLaunched) {
|
||||
if (isBungeeLaunched || isSwingLaunched || isForwardLaunched) {
|
||||
if (currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_time_thresh) {
|
||||
return FW_LAUNCH_EVENT_SUCCESS; // the launch is detected now, go to FW_LAUNCH_STATE_DETECTED
|
||||
}
|
||||
|
|
|
@ -406,7 +406,7 @@ bool adjustMulticopterPositionFromRCInput(int16_t rcPitchAdjustment, int16_t rcR
|
|||
static float getVelocityHeadingAttenuationFactor(void)
|
||||
{
|
||||
// In WP mode scale velocity if heading is different from bearing
|
||||
if (navGetCurrentStateFlags() & NAV_AUTO_WP) {
|
||||
if (navConfig()->mc.slowDownForTurning && (navGetCurrentStateFlags() & NAV_AUTO_WP)) {
|
||||
const int32_t headingError = constrain(wrap_18000(posControl.desiredState.yaw - posControl.actualState.yaw), -9000, 9000);
|
||||
const float velScaling = cos_approx(CENTIDEGREES_TO_RADIANS(headingError));
|
||||
|
||||
|
@ -438,7 +438,19 @@ static void updatePositionVelocityController_MC(const float maxSpeed)
|
|||
|
||||
// Scale velocity to respect max_speed
|
||||
float newVelTotal = sqrtf(sq(newVelX) + sq(newVelY));
|
||||
if (newVelTotal > maxSpeed) {
|
||||
|
||||
/*
|
||||
* We override computed speed with max speed in following cases:
|
||||
* 1 - computed velocity is > maxSpeed
|
||||
* 2 - in WP mission when: slowDownForTurning is OFF, we do not fly towards na last waypoint and computed speed is < maxSpeed
|
||||
*/
|
||||
if (
|
||||
(navGetCurrentStateFlags() & NAV_AUTO_WP &&
|
||||
!isApproachingLastWaypoint() &&
|
||||
newVelTotal < maxSpeed &&
|
||||
!navConfig()->mc.slowDownForTurning
|
||||
) || newVelTotal > maxSpeed
|
||||
) {
|
||||
newVelX = maxSpeed * (newVelX / newVelTotal);
|
||||
newVelY = maxSpeed * (newVelY / newVelTotal);
|
||||
newVelTotal = maxSpeed;
|
||||
|
|
|
@ -569,7 +569,7 @@ static bool estimationCalculateCorrection_Z(estimationContext_t * ctx)
|
|||
if (ctx->newFlags & EST_GPS_Z_VALID) {
|
||||
// Trust GPS velocity only if residual/error is less than 2.5 m/s, scale weight according to gaussian distribution
|
||||
const float gpsRocResidual = posEstimator.gps.vel.z - posEstimator.est.vel.z;
|
||||
const float gpsRocScaler = bellCurve(gpsRocResidual, 2.5f);
|
||||
const float gpsRocScaler = bellCurve(gpsRocResidual, 250.0f);
|
||||
ctx->estVelCorr.z += gpsRocResidual * positionEstimationConfig()->w_z_gps_v * gpsRocScaler * ctx->dt;
|
||||
}
|
||||
|
||||
|
|
|
@ -91,13 +91,6 @@ typedef struct navigationFlags_s {
|
|||
bool forcedRTHActivated;
|
||||
} navigationFlags_t;
|
||||
|
||||
typedef enum {
|
||||
PID_DTERM_FROM_ERROR = 1 << 0,
|
||||
PID_ZERO_INTEGRATOR = 1 << 1,
|
||||
PID_SHRINK_INTEGRATOR = 1 << 2,
|
||||
PID_LIMIT_INTEGRATOR = 1 << 3,
|
||||
} pidControllerFlags_e;
|
||||
|
||||
typedef struct {
|
||||
fpVector3_t pos;
|
||||
fpVector3_t vel;
|
||||
|
@ -392,21 +385,6 @@ extern multicopterPosXyCoefficients_t multicopterPosXyCoefficients;
|
|||
/* Internally used functions */
|
||||
const navEstimatedPosVel_t * navGetCurrentActualPositionAndVelocity(void);
|
||||
|
||||
float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags);
|
||||
float navPidApply3(
|
||||
pidController_t *pid,
|
||||
const float setpoint,
|
||||
const float measurement,
|
||||
const float dt,
|
||||
const float outMin,
|
||||
const float outMax,
|
||||
const pidControllerFlags_e pidFlags,
|
||||
const float gainScaler,
|
||||
const float dTermScaler
|
||||
);
|
||||
void navPidReset(pidController_t *pid);
|
||||
void navPidInit(pidController_t *pid, float _kP, float _kI, float _kD, float _kFF, float _dTermLpfHz);
|
||||
|
||||
bool isThrustFacingDownwards(void);
|
||||
uint32_t calculateDistanceToDestination(const fpVector3_t * destinationPos);
|
||||
int32_t calculateBearingToDestination(const fpVector3_t * destinationPos);
|
||||
|
|
|
@ -44,6 +44,8 @@
|
|||
#include "flight/imu.h"
|
||||
#include "flight/pid.h"
|
||||
#include "drivers/io_port_expander.h"
|
||||
#include "io/osd_common.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
@ -317,6 +319,20 @@ static int logicConditionCompute(
|
|||
return true;
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_SET_HEADING_TARGET:
|
||||
temporaryValue = CENTIDEGREES_TO_DEGREES(wrap_36000(DEGREES_TO_CENTIDEGREES(operandA)));
|
||||
updateHeadingHoldTarget(temporaryValue);
|
||||
return temporaryValue;
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_MODULUS:
|
||||
if (operandB != 0) {
|
||||
return constrain(operandA % operandB, INT16_MIN, INT16_MAX);
|
||||
} else {
|
||||
return operandA;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return false;
|
||||
break;
|
||||
|
@ -377,7 +393,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
|
|||
return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99);
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_VBAT: // V / 10
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_VBAT: // V / 100
|
||||
return getBatteryVoltage();
|
||||
break;
|
||||
|
||||
|
@ -393,7 +409,15 @@ static int logicConditionGetFlightOperandValue(int operand) {
|
|||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_GPS_SATS:
|
||||
if (getHwGPSStatus() == HW_SENSOR_UNAVAILABLE || getHwGPSStatus() == HW_SENSOR_UNHEALTHY) {
|
||||
return 0;
|
||||
} else {
|
||||
return gpsSol.numSat;
|
||||
}
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID: // 0/1
|
||||
return STATE(GPS_FIX) ? 1 : 0;
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_GROUD_SPEED: // cm/s
|
||||
|
@ -402,7 +426,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
|
|||
|
||||
//FIXME align with osdGet3DSpeed
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_3D_SPEED: // cm/s
|
||||
return (int) sqrtf(sq(gpsSol.groundSpeed) + sq((int)getEstimatedActualVelocity(Z)));
|
||||
return osdGet3DSpeed();
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED: // cm/s
|
||||
|
@ -418,7 +442,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
|
|||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_VERTICAL_SPEED: // cm/s
|
||||
return constrain(getEstimatedActualVelocity(Z), 0, INT16_MAX);
|
||||
return constrain(getEstimatedActualVelocity(Z), INT16_MIN, INT16_MAX);
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_TROTTLE_POS: // %
|
||||
|
|
|
@ -68,7 +68,9 @@ typedef enum {
|
|||
LOGIC_CONDITION_MAP_INPUT = 36,
|
||||
LOGIC_CONDITION_MAP_OUTPUT = 37,
|
||||
LOGIC_CONDITION_RC_CHANNEL_OVERRIDE = 38,
|
||||
LOGIC_CONDITION_LAST = 39,
|
||||
LOGIC_CONDITION_SET_HEADING_TARGET = 39,
|
||||
LOGIC_CONDITION_MODULUS = 40,
|
||||
LOGIC_CONDITION_LAST = 41,
|
||||
} logicOperation_e;
|
||||
|
||||
typedef enum logicOperandType_s {
|
||||
|
@ -117,6 +119,7 @@ typedef enum {
|
|||
LOGIC_CONDITION_OPERAND_FLIGHT_3D_HOME_DISTANCE, // 31
|
||||
LOGIC_CONDITION_OPERAND_FLIGHT_CRSF_LQ, // 32
|
||||
LOGIC_CONDITION_OPERAND_FLIGHT_CRSF_SNR, // 33
|
||||
LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID, // 0/1 // 34
|
||||
|
||||
} logicFlightOperands_e;
|
||||
|
||||
|
|
|
@ -110,7 +110,7 @@ void programmingPidInit(void)
|
|||
}
|
||||
}
|
||||
|
||||
int programmingPidGetOutput(uint8_t i) {
|
||||
int32_t programmingPidGetOutput(uint8_t i) {
|
||||
return programmingPidState[constrain(i, 0, MAX_PROGRAMMING_PID_COUNT)].output;
|
||||
}
|
||||
|
||||
|
|
|
@ -26,11 +26,11 @@
|
|||
|
||||
#include "config/parameter_group.h"
|
||||
#include "common/time.h"
|
||||
#include "common/fp_pid.h"
|
||||
|
||||
#include "programming/logic_condition.h"
|
||||
#include "common/axis.h"
|
||||
#include "flight/pid.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#define MAX_PROGRAMMING_PID_COUNT 4
|
||||
|
||||
|
@ -51,4 +51,4 @@ typedef struct programmingPidState_s {
|
|||
void programmingPidUpdateTask(timeUs_t currentTimeUs);
|
||||
void programmingPidInit(void);
|
||||
void programmingPidReset(void);
|
||||
int programmingPidGetOutput(uint8_t i);
|
||||
int32_t programmingPidGetOutput(uint8_t i);
|
|
@ -65,6 +65,8 @@ typedef enum {
|
|||
GHST_DL_LINK_STAT = 0x21,
|
||||
GHST_DL_VTX_STAT = 0x22,
|
||||
GHST_DL_PACK_STAT = 0x23, // Battery (Pack) Status
|
||||
GHST_DL_GPS_PRIMARY = 0x25, // Primary GPS data (position)
|
||||
GHST_DL_GPS_SECONDARY = 0x26 // Secondary GPS data (auxiliary)
|
||||
} ghstDl_e;
|
||||
|
||||
#define GHST_RC_CTR_VAL_12BIT 0x7C0 // servo center for 12 bit values (0x3e0 << 1)
|
||||
|
@ -76,6 +78,9 @@ typedef enum {
|
|||
|
||||
#define GHST_FRAME_SIZE_MAX 24
|
||||
|
||||
#define GPS_FLAGS_FIX 0x01
|
||||
#define GPS_FLAGS_FIX_HOME 0x02
|
||||
|
||||
typedef struct ghstFrameDef_s {
|
||||
uint8_t addr;
|
||||
uint8_t len;
|
||||
|
|
|
@ -50,6 +50,7 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "drivers/accgyro/accgyro_adxl345.h"
|
||||
#include "drivers/accgyro/accgyro_mma845x.h"
|
||||
#include "drivers/accgyro/accgyro_bma280.h"
|
||||
#include "drivers/accgyro/accgyro_bmi088.h"
|
||||
#include "drivers/accgyro/accgyro_bmi160.h"
|
||||
#include "drivers/accgyro/accgyro_icm20689.h"
|
||||
#include "drivers/accgyro/accgyro_fake.h"
|
||||
|
@ -240,6 +241,19 @@ static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse)
|
|||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#if defined(USE_IMU_BMI088)
|
||||
case ACC_BMI088:
|
||||
if (bmi088AccDetect(dev)) {
|
||||
accHardware = ACC_BMI088;
|
||||
break;
|
||||
}
|
||||
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
|
||||
if (accHardwareToUse != ACC_AUTODETECT) {
|
||||
break;
|
||||
}
|
||||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#ifdef USE_IMU_ICM20689
|
||||
case ACC_ICM20689:
|
||||
if (icm20689AccDetect(dev)) {
|
||||
|
|
|
@ -45,7 +45,8 @@ typedef enum {
|
|||
ACC_MPU9250 = 9,
|
||||
ACC_BMI160 = 10,
|
||||
ACC_ICM20689 = 11,
|
||||
ACC_FAKE = 12,
|
||||
ACC_BMI088 = 12,
|
||||
ACC_FAKE = 13,
|
||||
ACC_MAX = ACC_FAKE
|
||||
} accelerationSensor_e;
|
||||
|
||||
|
|
|
@ -56,7 +56,7 @@
|
|||
|
||||
baro_t baro; // barometer access functions
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 2);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 3);
|
||||
|
||||
#ifdef USE_BARO
|
||||
#define BARO_HARDWARE_DEFAULT BARO_AUTODETECT
|
||||
|
@ -65,7 +65,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER
|
|||
#endif
|
||||
PG_RESET_TEMPLATE(barometerConfig_t, barometerConfig,
|
||||
.baro_hardware = BARO_HARDWARE_DEFAULT,
|
||||
.use_median_filtering = 0,
|
||||
.use_median_filtering = 1,
|
||||
.baro_calibration_tolerance = 150
|
||||
);
|
||||
|
||||
|
|
|
@ -40,6 +40,7 @@
|
|||
#include "drivers/compass/compass_qmc5883l.h"
|
||||
#include "drivers/compass/compass_mpu9250.h"
|
||||
#include "drivers/compass/compass_lis3mdl.h"
|
||||
#include "drivers/compass/compass_rm3100.h"
|
||||
#include "drivers/compass/compass_msp.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
@ -264,6 +265,22 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
|
|||
}
|
||||
FALLTHROUGH;
|
||||
|
||||
case MAG_RM3100:
|
||||
#ifdef USE_MAG_RM3100
|
||||
if (rm3100MagDetect(dev)) {
|
||||
#ifdef MAG_RM3100_ALIGN
|
||||
dev->magAlign.onBoard = MAG_RM3100_ALIGN;
|
||||
#endif
|
||||
magHardware = MAG_RM3100;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
|
||||
if (magHardwareToUse != MAG_AUTODETECT) {
|
||||
break;
|
||||
}
|
||||
FALLTHROUGH;
|
||||
|
||||
case MAG_FAKE:
|
||||
#ifdef USE_FAKE_MAG
|
||||
if (fakeMagDetect(dev)) {
|
||||
|
@ -350,7 +367,7 @@ void compassUpdate(timeUs_t currentTimeUs)
|
|||
static sensorCalibrationState_t calState;
|
||||
static timeUs_t calStartedAt = 0;
|
||||
static int16_t magPrev[XYZ_AXIS_COUNT];
|
||||
static int magGain[XYZ_AXIS_COUNT] = {-4096, -4096, -4096};
|
||||
static int magAxisDeviation[XYZ_AXIS_COUNT];
|
||||
|
||||
// Check magZero
|
||||
if (
|
||||
|
@ -381,6 +398,7 @@ void compassUpdate(timeUs_t currentTimeUs)
|
|||
compassConfigMutable()->magZero.raw[axis] = 0;
|
||||
compassConfigMutable()->magGain[axis] = 1024;
|
||||
magPrev[axis] = 0;
|
||||
magAxisDeviation[axis] = 0; // Gain is based on the biggest absolute deviation from the mag zero point. Gain computation starts at 0
|
||||
}
|
||||
|
||||
beeper(BEEPER_ACTION_SUCCESS);
|
||||
|
@ -400,9 +418,9 @@ void compassUpdate(timeUs_t currentTimeUs)
|
|||
diffMag += (mag.magADC[axis] - magPrev[axis]) * (mag.magADC[axis] - magPrev[axis]);
|
||||
avgMag += (mag.magADC[axis] + magPrev[axis]) * (mag.magADC[axis] + magPrev[axis]) / 4.0f;
|
||||
|
||||
const int32_t sample = ABS(mag.magADC[axis]);
|
||||
if (sample > magGain[axis]) {
|
||||
magGain[axis] = sample;
|
||||
// Find the biggest sample deviation together with sample' sign
|
||||
if (ABS(mag.magADC[axis]) > ABS(magAxisDeviation[axis])) {
|
||||
magAxisDeviation[axis] = mag.magADC[axis];
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -429,7 +447,7 @@ void compassUpdate(timeUs_t currentTimeUs)
|
|||
* It is dirty, but worth checking if this will solve the problem of changing mag vector when UAV is tilted
|
||||
*/
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
compassConfigMutable()->magGain[axis] = magGain[axis] - compassConfig()->magZero.raw[axis];
|
||||
compassConfigMutable()->magGain[axis] = ABS(magAxisDeviation[axis] - compassConfig()->magZero.raw[axis]);
|
||||
}
|
||||
|
||||
calStartedAt = 0;
|
||||
|
|
|
@ -42,7 +42,8 @@ typedef enum {
|
|||
MAG_IST8308 = 10,
|
||||
MAG_LIS3MDL = 11,
|
||||
MAG_MSP = 12,
|
||||
MAG_FAKE = 13,
|
||||
MAG_RM3100 = 13,
|
||||
MAG_FAKE = 14,
|
||||
MAG_MAX = MAG_FAKE
|
||||
} magSensor_e;
|
||||
|
||||
|
|
|
@ -52,6 +52,7 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "drivers/accgyro/accgyro_adxl345.h"
|
||||
#include "drivers/accgyro/accgyro_mma845x.h"
|
||||
#include "drivers/accgyro/accgyro_bma280.h"
|
||||
#include "drivers/accgyro/accgyro_bmi088.h"
|
||||
#include "drivers/accgyro/accgyro_bmi160.h"
|
||||
#include "drivers/accgyro/accgyro_icm20689.h"
|
||||
#include "drivers/accgyro/accgyro_fake.h"
|
||||
|
@ -207,6 +208,15 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard
|
|||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#ifdef USE_IMU_BMI088
|
||||
case GYRO_BMI088:
|
||||
if (bmi088GyroDetect(dev)) {
|
||||
gyroHardware = GYRO_BMI088;
|
||||
break;
|
||||
}
|
||||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#ifdef USE_IMU_ICM20689
|
||||
case GYRO_ICM20689:
|
||||
if (icm20689GyroDetect(dev)) {
|
||||
|
|
|
@ -36,6 +36,7 @@ typedef enum {
|
|||
GYRO_MPU9250,
|
||||
GYRO_BMI160,
|
||||
GYRO_ICM20689,
|
||||
GYRO_BMI088,
|
||||
GYRO_FAKE
|
||||
} gyroSensor_e;
|
||||
|
||||
|
|
|
@ -75,7 +75,7 @@ static float opflowCalibrationFlowAcc;
|
|||
#define OPFLOW_UPDATE_TIMEOUT_US 200000 // At least 5Hz updates required
|
||||
#define OPFLOW_CALIBRATE_TIME_MS 30000 // 30 second calibration time
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(opticalFlowConfig_t, opticalFlowConfig, PG_OPFLOW_CONFIG, 1);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(opticalFlowConfig_t, opticalFlowConfig, PG_OPFLOW_CONFIG, 2);
|
||||
|
||||
PG_RESET_TEMPLATE(opticalFlowConfig_t, opticalFlowConfig,
|
||||
.opflow_hardware = OPFLOW_NONE,
|
||||
|
|
|
@ -30,10 +30,9 @@
|
|||
|
||||
typedef enum {
|
||||
OPFLOW_NONE = 0,
|
||||
OPFLOW_PMW3901 = 1,
|
||||
OPFLOW_CXOF = 2,
|
||||
OPFLOW_MSP = 3,
|
||||
OPFLOW_FAKE = 4,
|
||||
OPFLOW_CXOF = 1,
|
||||
OPFLOW_MSP = 2,
|
||||
OPFLOW_FAKE = 3,
|
||||
} opticalFlowSensor_e;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -40,6 +40,7 @@
|
|||
#include "drivers/rangefinder/rangefinder_srf10.h"
|
||||
#include "drivers/rangefinder/rangefinder_hcsr04_i2c.h"
|
||||
#include "drivers/rangefinder/rangefinder_vl53l0x.h"
|
||||
#include "drivers/rangefinder/rangefinder_vl53l1x.h"
|
||||
#include "drivers/rangefinder/rangefinder_virtual.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
@ -131,6 +132,15 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar
|
|||
#endif
|
||||
break;
|
||||
|
||||
case RANGEFINDER_VL53L1X:
|
||||
#if defined(USE_RANGEFINDER_VL53L1X)
|
||||
if (vl53l1xDetect(dev)) {
|
||||
rangefinderHardware = RANGEFINDER_VL53L1X;
|
||||
rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_VL53L1X_TASK_PERIOD_MS));
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
case RANGEFINDER_MSP:
|
||||
#if defined(USE_RANGEFINDER_MSP)
|
||||
if (virtualRangefinderDetect(dev, &rangefinderMSPVtable)) {
|
||||
|
|
|
@ -30,6 +30,7 @@ typedef enum {
|
|||
RANGEFINDER_MSP = 5,
|
||||
RANGEFINDER_UNUSED = 6, // Was UIB
|
||||
RANGEFINDER_BENEWAKE = 7,
|
||||
RANGEFINDER_VL53L1X = 8,
|
||||
} rangefinderType_e;
|
||||
|
||||
typedef struct rangefinderConfig_s {
|
||||
|
|
|
@ -28,9 +28,9 @@ const timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 (2,2)
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 (2,6)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 (2,1) (2.3 2.6)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 (2,4) (2.2)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 (1,2)
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 (1,5)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S5 (2,4) (2.2)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S6 (1,2)
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S7 (2,3)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 (2,7)
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED STRIP(1,0)
|
||||
|
||||
|
|
|
@ -140,8 +140,13 @@
|
|||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC_CHANNEL_1_PIN PA1
|
||||
#ifdef FLYWOOF411_V2
|
||||
#define ADC_CHANNEL_2_PIN PB1
|
||||
#define ADC_CHANNEL_3_PIN PB0
|
||||
#else
|
||||
#define ADC_CHANNEL_2_PIN PA0
|
||||
#define ADC_CHANNEL_3_PIN PB1
|
||||
#endif
|
||||
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_2
|
||||
|
|
|
@ -42,8 +42,8 @@ const timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5)
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3)
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 UP1-6 D(1, 0, 2)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8 UP1-6 D(1, 3, 2)
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 UP1-6 D(1, 0, 2)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8 UP1-6 D(1, 3, 2)
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0)
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2
|
||||
|
|
|
@ -40,7 +40,7 @@ const timerHardware_t timerHardware[] = {
|
|||
#else
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP(2,5)
|
||||
#endif
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S7 D(1,7)!S5 UP(2,6)
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 D(1,7)!S5 UP(2,6)
|
||||
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2
|
||||
|
||||
|
|
1
src/main/target/MATEKF405CAN/CMakeLists.txt
Normal file
1
src/main/target/MATEKF405CAN/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32f405xg(MATEKF405CAN)
|
31
src/main/target/MATEKF405CAN/config.c
Normal file
31
src/main/target/MATEKF405CAN/config.c
Normal file
|
@ -0,0 +1,31 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include "platform.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_GPS;
|
||||
// serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].gps_baudrateIndex = BAUD_115200;
|
||||
|
||||
}
|
44
src/main/target/MATEKF405CAN/target.c
Normal file
44
src/main/target/MATEKF405CAN/target.c
Normal file
|
@ -0,0 +1,44 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S1 D(2,2,7)
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S2 D(2,3,7)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S3 D(2,4,7)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4 D(2,7,7)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S5 D(1,7,5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S6 D(1,2,5)
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S7 D(1,0,2)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S8 D(1,3,2)
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_BEEPER, 0, 0), // BEEPER PWM
|
||||
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), //2812LED D(1,5,3)
|
||||
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //RX2
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
174
src/main/target/MATEKF405CAN/target.h
Normal file
174
src/main/target/MATEKF405CAN/target.h
Normal file
|
@ -0,0 +1,174 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "MF4C"
|
||||
#define USBD_PRODUCT_STRING "Matek_F405CAN"
|
||||
|
||||
#define LED0 PA14 //Blue
|
||||
#define LED1 PA13 //Green
|
||||
|
||||
#define BEEPER PA8
|
||||
#define BEEPER_INVERTED
|
||||
#define BEEPER_PWM
|
||||
#define BEEPER_PWM_FREQUENCY 2500
|
||||
|
||||
// *************** SPI1 Gyro & ACC *******************
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_IMU_MPU6500
|
||||
#define IMU_MPU6500_ALIGN CW180_DEG_FLIP
|
||||
#define MPU6500_CS_PIN PA4
|
||||
#define MPU6500_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_EXTI
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
|
||||
// *************** I2C /Baro/Mag *********************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C2_SCL PB10
|
||||
#define I2C2_SDA PB11
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C2
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_AK8963
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define USE_RANGEFINDER_HCSR04_I2C
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C2
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PCA9685_I2C_BUS BUS_I2C2
|
||||
|
||||
|
||||
// *************** SPI2 RM3100 **************************
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_MAG_RM3100
|
||||
#define MAG_RM3100_ALIGN CW0_DEG_FLIP
|
||||
#define RM3100_CS_PIN PB12
|
||||
#define RM3100_SPI_BUS BUS_SPI2
|
||||
|
||||
// *************** SPI3 SD Card ********************
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
#define SDCARD_SPI_BUS BUS_SPI3
|
||||
#define SDCARD_CS_PIN PC14
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_TX_PIN PC10
|
||||
#define UART3_RX_PIN PC11
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PA0
|
||||
#define UART4_RX_PIN PA1
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_TX_PIN PC12
|
||||
#define UART5_RX_PIN PD2
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_TX_PIN PA2 //TX2 pad
|
||||
#define SOFTSERIAL_1_RX_PIN PA2 //TX2 pad
|
||||
|
||||
#define SERIAL_PORT_COUNT 7
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
||||
// *************** ADC ***************************
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
#define ADC_CHANNEL_3_PIN PC2
|
||||
#define ADC_CHANNEL_4_PIN PC3
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
#define AIRSPEED_ADC_CHANNEL ADC_CHN_4
|
||||
|
||||
// *************** LED2812 ************************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA15
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER
|
||||
#define WS2811_DMA_STREAM DMA1_Stream5
|
||||
#define WS2811_DMA_CHANNEL DMA_Channel_3
|
||||
|
||||
// *************** OTHERS *************************
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_GPS | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
|
||||
#define VBAT_SCALE 2100 //1K:20K
|
||||
|
||||
#define USE_SPEKTRUM_BIND
|
||||
#define BIND_PIN PA3 // RX2
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
|
@ -1 +1,3 @@
|
|||
target_stm32f411xe(MATEKF411SE)
|
||||
target_stm32f411xe(MATEKF411SE_PINIO)
|
||||
target_stm32f411xe(MATEKF411SE_FD_SFTSRL1)
|
||||
|
|
|
@ -25,4 +25,7 @@
|
|||
void targetConfiguration(void)
|
||||
{
|
||||
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
|
||||
#ifdef MATEKF411SE_PINIO
|
||||
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -35,7 +35,9 @@ const timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 pad -softserial_tx2
|
||||
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //RX2 Pad -PPM
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_LED, 0, 0), //LED 2812 D(1,1,3)
|
||||
#ifndef MATEKF411SE_PINIO
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_ANY, 0, 0), // softserial_rx1 - LED 2812 D(1,1,3)
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
|
|
|
@ -70,7 +70,11 @@
|
|||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_TX_PIN PB9 // ST1 pad
|
||||
#ifdef MATEKF411SE_FD_SFTSRL1
|
||||
#define SOFTSERIAL_1_RX_PIN PB10 // LED pad
|
||||
#else
|
||||
#define SOFTSERIAL_1_RX_PIN PB9
|
||||
#endif
|
||||
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SOFTSERIAL_2_TX_PIN PA2 // TX2 pad
|
||||
|
@ -131,13 +135,18 @@
|
|||
#define AIRSPEED_ADC_CHANNEL ADC_CHN_4
|
||||
|
||||
// *************** LED2812 ************************
|
||||
#if !defined(MATEKF411SE_PINIO) && !defined(MATEKF411SE_FD_SFTSRL1)
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PB10
|
||||
#endif
|
||||
|
||||
// *************** PINIO ***************************
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PA13 // Camera switcher
|
||||
#ifdef MATEKF411SE_PINIO
|
||||
#define PINIO2_PIN PB10 // External PINIO (LED pad)
|
||||
#endif
|
||||
|
||||
// *************** OTHERS *************************
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL )
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue