mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 16:55:29 +03:00
Merge remote-tracking branch 'upstream/master' into abo_fix_modes_craft_type
This commit is contained in:
commit
672d65f1c2
114 changed files with 2276 additions and 1789 deletions
|
@ -6,6 +6,9 @@ When armed, the aircraft is ready to fly and the motors will spin when throttle
|
|||
|
||||
Arming and disarming is done using a switch, set up on the modes page. (NOTE: Stick arming was removed in iNav 2.2)
|
||||
|
||||
**YAW STICK ARMING OVERRIDE:**
|
||||
Arming is disabled when Nav modes are configured and no GPS lock is available or if a WP mission is loaded but the first WP is farther than the `nav_wp_safe_distance` setting. This Arming block can be bypassed if need be by setting `nav_extra_arming_safety` to `ALLOW_BYPASS` and moving the Yaw stick to the high position when the Arm switch is used. This bypasses GPS Arm blocking pre INAV 4.0.0 and both GPS and "First WP too far" Arm blocking from INAV 4.0.0.
|
||||
|
||||
## Stick Positions
|
||||
|
||||
The three stick positions are:
|
||||
|
@ -36,6 +39,9 @@ The stick positions are combined to activate different functions:
|
|||
| Save current waypoint mission | LOW | CENTER | HIGH | LOW |
|
||||
| Load current waypoint mission | LOW | CENTER | HIGH | HIGH |
|
||||
| Unload waypoint mission | LOW | CENTER | LOW | HIGH |
|
||||
| Increase WP mission index | LOW | CENTER | CENTER | HIGH |
|
||||
| Decrease WP mission index | LOW | CENTER | CENTER | LOW |
|
||||
| Bypass Nav Arm disable | LOW | HIGH | CENTER | CENTER |
|
||||
| Save setting | LOW | LOW | LOW | HIGH |
|
||||
| Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER |
|
||||
|
||||
|
|
|
@ -9,8 +9,8 @@ Failsafe is a state the flight controller is meant to enter when the radio recei
|
|||
If the failsafe happens while the flight controller is disarmed, it only prevent arming. If it happens while armed, the failsafe policy configured in `failsafe_procedure` is engaged. The available procedures are:
|
||||
|
||||
* __DROP:__ Just kill the motors and disarm (crash the craft).
|
||||
* __LAND:__ (replaces **SET-THR** from INAV V3.1.0) Performs an Emergency Landing. Enables auto-level mode (for multirotor) or enters a preconfigured roll/pitch/yaw spiral down (for airplanes). If altitude sensors are working an actively controlled descent is performed using the Emergency Landing descent speed (`nav_emerg_landing_speed`). If altitude sensors are unavailable descent is performed with the throttle set to a predefined value (`failsafe_throttle`). The descent can be limited to a predefined time (`failsafe_off_delay`) after which the craft disarms. This is meant to get the craft to a safe-ish landing (or more realistically, a controlled crash), Other than using altitude sensors for an actively controlled descent it doesn't require any extra sensors other than gyros and accelerometers.
|
||||
* __SET-THR:__ (Pre INAV V3.1.0) Same as **LAND** except it doesn't use an Emergency Landing but is limited instead to just setting the throttle to a predefined value (`failsafe_throttle`) to perform a descent. It doesn't require any extra sensors other than gyros and accelerometers.
|
||||
* __LAND:__ (replaces **SET-THR** from INAV 4.0) Performs an Emergency Landing. Enables auto-level mode (for multirotor) or enters a preconfigured roll/pitch/yaw spiral down (for airplanes). If altitude sensors are working an actively controlled descent is performed using the Emergency Landing descent speed (`nav_emerg_landing_speed`). If altitude sensors are unavailable descent is performed with the throttle set to a predefined value (`failsafe_throttle`). The descent can be limited to a predefined time (`failsafe_off_delay`) after which the craft disarms. This is meant to get the craft to a safe-ish landing (or more realistically, a controlled crash). Other than using altitude sensors for an actively controlled descent it doesn't require any extra sensors other than basic gyros and accelerometers.
|
||||
* __SET-THR:__ (Pre INAV 4.0) Same as **LAND** except it doesn't use an Emergency Landing but is limited instead to just setting the throttle to a predefined value (`failsafe_throttle`) to perform a descent. It doesn't require any extra sensors other than basic gyros and accelerometers.
|
||||
* __RTH:__ (Return To Home) One of the key features of INAV, it automatically navigates the craft back to the home position and (optionally) lands it. Similarly to all other automated navigation methods, it requires GPS for any type of craft, plus compass and barometer for multicopters.
|
||||
* __NONE:__ Do nothing. This is meant to let the craft perform a fully automated flight (eg. waypoint flight) outside of radio range. Highly unsafe when used with manual flight.
|
||||
|
||||
|
|
|
@ -49,6 +49,10 @@ When deciding what altitude to maintain, RTH has 6 different modes of operation
|
|||
* 4 (NAV_RTH_AT_LEAST_ALT) - same as 2 (NAV_RTH_CONST_ALT), but only climb, do not descend
|
||||
* 5 (NAV_RTH_AT_LEAST_ALT_LINEAR_DESCENT) - Same as 4 (NAV_RTH_AT_LEAST_ALT). But, if above the RTH Altitude, the aircraft will gradually descend to the RTH Altitude. The target is to reach the RTH Altitude as it arrives at the home point. This is to save energy during the RTH.
|
||||
|
||||
## NAV WP - Waypoint mode
|
||||
|
||||
NAV WP allows the craft to autonomously navigate a set route defined by waypoints that are loaded into the FC as a predefined mission.
|
||||
|
||||
## CLI command `wp` to manage waypoints
|
||||
|
||||
`wp` - List all waypoints.
|
||||
|
@ -81,7 +85,7 @@ Parameters:
|
|||
|
||||
* `<p3>` - Reserved for future use. If `p2` is provided, then `p3` is also required.
|
||||
|
||||
* `<flag>` - Last waypoint must have set `flag` to 165 (0xA5), otherwise 0.
|
||||
* `<flag>` - Last waypoint must have `flag` set to 165 (0xA5).
|
||||
|
||||
`wp save` - Checks list of waypoints and save from FC to EEPROM (warning: it also saves all unsaved CLI settings like normal `save`).
|
||||
|
||||
|
@ -111,3 +115,45 @@ wp 59 0 0 0 0 0 0 0 0
|
|||
```
|
||||
|
||||
Note that the `wp` CLI command shows waypoint list indices, while the MW-XML definition used by mwp, ezgui and the configurator use WP numbers.
|
||||
|
||||
**Multi-missions**\
|
||||
Multi-missions allows up to 9 missions to be stored in the FC at the same time. It is possible to load them into the FC using the CLI. This is acheived by entering single missions into the CLI followed by `wp save` **after** the final mission has been entered (the single missions can be entered one after the other or as a single block entry, it doesn't matter). All missions will then be saved as a Multi Mission in the FC. Saved multi missions display consecutive WP indices from 0 to the last WP in the last mission when displayed using the `wp` command.
|
||||
|
||||
E.g. to enter 3 missions in the CLI enter each mission as a single mission (start WP index for each mission must be 0).
|
||||
```
|
||||
wp 0 1 545722109 -32869291 5000 0 0 0 0
|
||||
wp 1 1 545708178 -32642698 5000 0 0 0 0
|
||||
wp 2 1 545698227 -32385206 5000 0 0 0 165
|
||||
...
|
||||
wp 0 1 545599696 -32958555 5000 0 0 0 0
|
||||
wp 1 1 545537978 -32958555 5000 0 0 0 0
|
||||
wp 2 1 545547933 -32864141 5000 0 0 0 0
|
||||
wp 3 1 545597705 -32695913 5000 0 0 0 0
|
||||
wp 4 1 545552910 -32598066 5000 0 0 0 0
|
||||
wp 5 6 0 0 0 0 0 0 165
|
||||
...
|
||||
wp 0 1 545714148 -32501936 5000 0 0 0 165
|
||||
|
||||
# wp save
|
||||
```
|
||||
|
||||
Multi Mission after saving:
|
||||
```
|
||||
# wp
|
||||
# wp 10 valid
|
||||
wp 0 1 545722109 -32869291 5000 0 0 0 0
|
||||
wp 1 1 545708178 -32642698 5000 0 0 0 0
|
||||
wp 2 1 545698227 -32385206 5000 0 0 0 165
|
||||
wp 3 1 545599696 -32958555 5000 0 0 0 0
|
||||
wp 4 1 545537978 -32958555 5000 0 0 0 0
|
||||
wp 5 1 545547933 -32864141 5000 0 0 0 0
|
||||
wp 6 1 545597705 -32695913 5000 0 0 0 0
|
||||
wp 7 1 545552910 -32598066 5000 0 0 0 0
|
||||
wp 8 6 0 0 0 0 0 0 165
|
||||
wp 9 1 545714148 -32501936 5000 0 0 0 165
|
||||
wp 10 0 0 0 0 0 0 0 0
|
||||
wp 11 0 0 0 0 0 0 0 0
|
||||
wp 12 0 0 0 0 0 0 0 0
|
||||
...
|
||||
wp 59 0 0 0 0 0 0 0 0
|
||||
```
|
172
docs/Settings.md
172
docs/Settings.md
|
@ -388,7 +388,7 @@ Selection of baro hardware. See Wiki Sensor auto detect and hardware failure det
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -458,7 +458,7 @@ Allows disabling PWM mode for beeper on some targets. Switch from ON to OFF if t
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -518,7 +518,7 @@ This option is only available on certain architectures (F3 CPUs at the moment).
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -638,7 +638,7 @@ Disarms the motors independently of throttle value. Setting to OFF reverts to th
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -648,7 +648,7 @@ OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values a
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -698,7 +698,7 @@ Show inflight adjustments in craft name field
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -708,7 +708,7 @@ Re-purpose the craft name field for messages.
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -728,7 +728,7 @@ Whether using DShot motors as beepers is enabled
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -788,7 +788,7 @@ Enable/disable dynamic gyro notch also known as Matrix Filter
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -838,7 +838,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -868,7 +868,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -888,7 +888,7 @@ Enable when BLHeli32 Auto Telemetry function is used. Disable in every other cas
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -938,7 +938,7 @@ Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The tar
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -988,7 +988,7 @@ If set to `OFF` the failsafe procedure won't be triggered and the mission will c
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1058,7 +1058,7 @@ Auto-arm fixed wing aircraft on throttle above min_check, and disarming with sti
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1118,7 +1118,7 @@ S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw acc
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1438,7 +1438,7 @@ Automatic configuration of GPS baudrate(The specified baudrate in configured in
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1448,7 +1448,7 @@ Enable automatic configuration of UBlox GPS receivers.
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1498,7 +1498,7 @@ Enable use of Galileo satellites. This is at the expense of other regional const
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1598,7 +1598,7 @@ Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1608,7 +1608,7 @@ Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1788,7 +1788,7 @@ If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1798,7 +1798,7 @@ If set to ON, Secondary IMU data will be used for Analog OSD heading
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1808,7 +1808,7 @@ If set to ON, Secondary IMU data will be used for Angle, Horizon and all other m
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1878,7 +1878,7 @@ Defines if inav will dead-reckon over short GPS outages. May also be useful for
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1888,7 +1888,7 @@ Automatic setting of magnetic declination based on GPS position. When used manua
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1958,7 +1958,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1968,7 +1968,7 @@ Defined if iNav should use velocity data provided by GPS module for doing positi
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -2118,7 +2118,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -2768,7 +2768,7 @@ Use if you need to inverse yaw motor direction.
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -2848,7 +2848,7 @@ If set to ON, iNav disarms the FC after landing
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -2878,7 +2878,7 @@ Enable the possibility to manually increase the throttle in auto throttle contro
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3278,7 +3278,7 @@ Stops motor when Soaring mode enabled.
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3668,7 +3668,7 @@ When ON, NAV engine will slow down when switching to the next waypoint. This pri
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3688,7 +3688,7 @@ With Reset ON WP Mission Planner waypoint count can be reset to 0 by toggling th
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3738,7 +3738,7 @@ If set to ON RTH altitude and CLIMB FIRST settings can be overridden during the
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3798,7 +3798,7 @@ If set to ON, aircraft will execute initial climb regardless of position sensor
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3818,7 +3818,7 @@ If set to ON drone will return tail-first. Obviously meaningless for airplanes.
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3828,7 +3828,7 @@ Enables or Disables the use of the heading PID controller on fixed wing. Heading
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3838,7 +3838,7 @@ If set to OFF, the FC remembers your throttle stick position when enabling ALTHO
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3858,7 +3858,7 @@ If set to ON, waypoints will be automatically loaded from EEPROM to the FC durin
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3928,7 +3928,7 @@ Shows a border/corners around the AHI region (pixel OSD only)
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3938,7 +3938,7 @@ When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For examp
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3968,7 +3968,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4168,7 +4168,7 @@ Use wind estimation for remaining flight time/distance estimation
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4178,7 +4178,7 @@ If enabled the OSD automatically switches to the first layout during failsafe
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4188,7 +4188,7 @@ Force OSD to work in grid mode even if the OSD device supports pixel level acces
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4228,7 +4228,7 @@ Should home position coordinates be displayed on the arming screen.
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4248,7 +4248,7 @@ To 3D-display the home point location in the hud
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4258,7 +4258,7 @@ To display little arrows around the crossair showing where the home point is in
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4292,16 +4292,6 @@ Maximum count of nearby aircrafts or points of interest to display in the hud, a
|
|||
|
||||
---
|
||||
|
||||
### osd_hud_radar_nearest
|
||||
|
||||
To display an extra bar of informations at the bottom of the hud area for the closest radar aircraft found, if closest than the set value, in meters. Shows relative altitude (meters or feet, with an up or down arrow to indicate if above or below), speed (in m/s or f/s), and absolute heading (in °, 0 is north, 90 is east, 180 is south, 270 is west). Set to 0 (zero) to disable.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 0 | 0 | 4000 |
|
||||
|
||||
---
|
||||
|
||||
### osd_hud_radar_range_max
|
||||
|
||||
In meters, radar aircrafts further away than this will not be displayed in the hud
|
||||
|
@ -4492,6 +4482,26 @@ RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm
|
|||
|
||||
---
|
||||
|
||||
### osd_rssi_dbm_max
|
||||
|
||||
RSSI dBm upper end of curve. Perfect rssi (max) = 100%
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| -30 | -50 | 0 |
|
||||
|
||||
---
|
||||
|
||||
### osd_rssi_dbm_min
|
||||
|
||||
RSSI dBm lower end of curve or RX sensitivity level. Worst rssi (min) = 0%
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| -120 | -130 | 0 |
|
||||
|
||||
---
|
||||
|
||||
### osd_sidebar_height
|
||||
|
||||
Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD)
|
||||
|
@ -4518,7 +4528,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4778,7 +4788,7 @@ Selection of rangefinder hardware.
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4918,7 +4928,7 @@ S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -4938,7 +4948,7 @@ Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rot
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5138,7 +5148,7 @@ Reverse the serial inversion of the serial RX protocol. When this value is OFF,
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5208,7 +5218,7 @@ Enable Kalman filter on the gyro data
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5298,7 +5308,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5308,7 +5318,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5358,7 +5368,7 @@ _// TODO_
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5378,7 +5388,7 @@ General switch of the statistics recording feature (a.k.a. odometer)
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5428,7 +5438,7 @@ S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5438,7 +5448,7 @@ Determines if the telemetry protocol default signal inversion is reversed. This
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5448,7 +5458,7 @@ Which aux channel to use to change serial output & baud rate (MSP / Telemetry).
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | | |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5538,7 +5548,7 @@ On tricopter mix only, if this is set to ON, servo will always be correcting reg
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5668,7 +5678,7 @@ Use half duplex UART to communicate with the VTX, using only a TX pin in the FC.
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
@ -5712,13 +5722,23 @@ VTX RF power level to use. The exact number of mw depends on the VTX hardware.
|
|||
|
||||
---
|
||||
|
||||
### vtx_smartaudio_alternate_softserial_method
|
||||
|
||||
Enable the alternate softserial method. This is the method used in iNav 3.0 and ealier.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
### vtx_smartaudio_early_akk_workaround
|
||||
|
||||
Enable workaround for early AKK SAudio-enabled VTX bug.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| ON | | |
|
||||
| ON | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
|
|
Binary file not shown.
Before Width: | Height: | Size: 666 KiB After Width: | Height: | Size: 819 KiB |
File diff suppressed because it is too large
Load diff
Before Width: | Height: | Size: 46 KiB After Width: | Height: | Size: 54 KiB |
Binary file not shown.
Before Width: | Height: | Size: 696 KiB After Width: | Height: | Size: 666 KiB |
|
@ -5,13 +5,14 @@
|
|||
* For Omnibus F4 Pro (with BMP280 baro, current sensor and SD Card) use **OMNIBUSF4PRO** target (LED strip on dedicated connection)
|
||||
* For Onnibus F4 Pro clones (Banggood, AliExpress, eBay, etc.) use **OMNIBUSF4PRO_LEDSTRIPM5** target (LED strip on M5 pin)
|
||||
* For Omnibus F4 Pro Corner use **OMNIBUSF4PRO** target
|
||||
* For Omnibus F4 AIO, see targets listed below
|
||||
|
||||
## Features
|
||||
|
||||
* STM32F405 CPU
|
||||
* Integrated Accelerometer/Gyro MPU6000 or MPU6500 via SPI bus
|
||||
* 6 motor outputs
|
||||
* 3 UART ports (UART1, UART3, UART6)
|
||||
* 3-5 UART ports (UART1, UART3, UART6)
|
||||
* External I2C bus, pins shared with UART3, cannot be used simultaneously
|
||||
* Inverter for SBUS
|
||||
* Blackbox via SDCard or integrated 128mbit flash memory
|
||||
|
@ -51,6 +52,14 @@ More target options:
|
|||
* PPM and UART6 cannot be used together, there is no jumper to disconnect PPM input from UART6 RX
|
||||
* Uses target **OMNIBUSF4V3**
|
||||
|
||||
### Omnibus F4 v6
|
||||
|
||||
* Adds more UARTs (total of 5)
|
||||
* Softserial 1 is on TX1 for Smartport
|
||||
* Note that in multirotor configuration, servos are not enabled on S5 and S6
|
||||
* Uses target **OMNIBUSF4V6**
|
||||
|
||||
|
||||
### [Omnibus F4 Pro](https://inavflight.com/shop/p/OMNIBUSF4PRO)
|
||||
|
||||
* Sometimes called Omnibus F4 v2 Pro, but also exists v3, v4 & v5 versions with no functional differences
|
||||
|
|
|
@ -84,14 +84,8 @@ main_sources(COMMON_SRC
|
|||
drivers/accgyro/accgyro_icm20689.h
|
||||
drivers/accgyro/accgyro_icm42605.c
|
||||
drivers/accgyro/accgyro_icm42605.h
|
||||
drivers/accgyro/accgyro_l3gd20.c
|
||||
drivers/accgyro/accgyro_l3gd20.h
|
||||
drivers/accgyro/accgyro_lsm303dlhc.c
|
||||
drivers/accgyro/accgyro_lsm303dlhc.h
|
||||
drivers/accgyro/accgyro_mpu.c
|
||||
drivers/accgyro/accgyro_mpu.h
|
||||
drivers/accgyro/accgyro_mpu3050.c
|
||||
drivers/accgyro/accgyro_mpu3050.h
|
||||
drivers/accgyro/accgyro_mpu6000.c
|
||||
drivers/accgyro/accgyro_mpu6000.h
|
||||
drivers/accgyro/accgyro_mpu6050.c
|
||||
|
|
|
@ -104,8 +104,8 @@ PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
|
|||
.rate_num = SETTING_BLACKBOX_RATE_NUM_DEFAULT,
|
||||
.rate_denom = SETTING_BLACKBOX_RATE_DENOM_DEFAULT,
|
||||
.invertedCardDetection = BLACKBOX_INVERTED_CARD_DETECTION,
|
||||
.includeFlags = BLACKBOX_FEATURE_NAV_PID | BLACKBOX_FEATURE_NAV_POS |
|
||||
BLACKBOX_FEATURE_MAG | BLACKBOX_FEATURE_ACC | BLACKBOX_FEATURE_ATTITUDE |
|
||||
.includeFlags = BLACKBOX_FEATURE_NAV_PID | BLACKBOX_FEATURE_NAV_POS |
|
||||
BLACKBOX_FEATURE_MAG | BLACKBOX_FEATURE_ACC | BLACKBOX_FEATURE_ATTITUDE |
|
||||
BLACKBOX_FEATURE_RC_DATA | BLACKBOX_FEATURE_RC_COMMAND | BLACKBOX_FEATURE_MOTORS,
|
||||
);
|
||||
|
||||
|
@ -653,18 +653,11 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
#endif
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV:
|
||||
#ifdef USE_NAV
|
||||
|
||||
return STATE(FIXED_WING_LEGACY) && blackboxIncludeFlag(BLACKBOX_FEATURE_NAV_PID);
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_MC_NAV:
|
||||
#ifdef USE_NAV
|
||||
return !STATE(FIXED_WING_LEGACY) && blackboxIncludeFlag(BLACKBOX_FEATURE_NAV_PID);
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_RSSI:
|
||||
// Assumes blackboxStart() is called after rxInit(), which should be true since
|
||||
|
@ -855,7 +848,7 @@ static void writeIntraframe(void)
|
|||
}
|
||||
|
||||
blackboxWriteSigned16VBArray(blackboxCurrent->gyroADC, XYZ_AXIS_COUNT);
|
||||
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
|
||||
blackboxWriteSigned16VBArray(blackboxCurrent->accADC, XYZ_AXIS_COUNT);
|
||||
}
|
||||
|
@ -1111,7 +1104,7 @@ static void writeInterframe(void)
|
|||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ATTITUDE)) {
|
||||
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, attitude), XYZ_AXIS_COUNT);
|
||||
}
|
||||
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
|
||||
blackboxWriteArrayUsingAveragePredictor32(offsetof(blackboxMainState_t, debug), DEBUG32_VALUE_COUNT);
|
||||
}
|
||||
|
@ -1266,7 +1259,7 @@ static void loadSlowState(blackboxSlowState_t *slow)
|
|||
#endif
|
||||
|
||||
#ifdef USE_ESC_SENSOR
|
||||
escSensorData_t * escSensor = escSensorGetData();
|
||||
escSensorData_t * escSensor = escSensorGetData();
|
||||
slow->escRPM = escSensor->rpm;
|
||||
slow->escTemperature = escSensor->temperature;
|
||||
#endif
|
||||
|
@ -1468,9 +1461,7 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
|
||||
blackboxCurrent->time = currentTimeUs;
|
||||
|
||||
#ifdef USE_NAV
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
#endif
|
||||
|
||||
for (int i = 0; i < XYZ_AXIS_COUNT; i++) {
|
||||
blackboxCurrent->axisPID_Setpoint[i] = axisPID_Setpoint[i];
|
||||
|
@ -1483,7 +1474,6 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
#ifdef USE_MAG
|
||||
blackboxCurrent->magADC[i] = mag.magADC[i];
|
||||
#endif
|
||||
#ifdef USE_NAV
|
||||
if (!STATE(FIXED_WING_LEGACY)) {
|
||||
// log requested velocity in cm/s
|
||||
blackboxCurrent->mcPosAxisP[i] = lrintf(nav_pids->pos[i].output_constrained);
|
||||
|
@ -1495,10 +1485,8 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
blackboxCurrent->mcVelAxisPID[3][i] = lrintf(nav_pids->vel[i].feedForward);
|
||||
blackboxCurrent->mcVelAxisOutput[i] = lrintf(nav_pids->vel[i].output_constrained);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_NAV
|
||||
if (STATE(FIXED_WING_LEGACY)) {
|
||||
|
||||
// log requested pitch in decidegrees
|
||||
|
@ -1519,7 +1507,6 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
blackboxCurrent->mcSurfacePID[2] = lrintf(nav_pids->surface.derivative / 10);
|
||||
blackboxCurrent->mcSurfacePIDOutput = lrintf(nav_pids->surface.output_constrained / 10);
|
||||
}
|
||||
#endif
|
||||
|
||||
for (int i = 0; i < 4; i++) {
|
||||
blackboxCurrent->rcData[i] = rxGetChannelValue(i);
|
||||
|
|
|
@ -101,9 +101,7 @@ static const OSD_Entry menuFeaturesEntries[] =
|
|||
OSD_LABEL_ENTRY("--- FEATURES ---"),
|
||||
OSD_SUBMENU_ENTRY("BLACKBOX", &cmsx_menuBlackbox),
|
||||
OSD_SUBMENU_ENTRY("MIXER & SERVOS", &cmsx_menuMixerServo),
|
||||
#if defined(USE_NAV)
|
||||
OSD_SUBMENU_ENTRY("NAVIGATION", &cmsx_menuNavigation),
|
||||
#endif
|
||||
#if defined(USE_VTX_CONTROL)
|
||||
OSD_SUBMENU_ENTRY("VTX", &cmsx_menuVtxControl),
|
||||
#endif // VTX_CONTROL
|
||||
|
|
|
@ -26,8 +26,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
|
@ -195,8 +193,9 @@ static const OSD_Entry cmsx_menuMissionSettingsEntries[] =
|
|||
OSD_SETTING_ENTRY("WP LOAD ON BOOT", SETTING_NAV_WP_LOAD_ON_BOOT),
|
||||
OSD_SETTING_ENTRY("WP REACHED RADIUS", SETTING_NAV_WP_RADIUS),
|
||||
OSD_SETTING_ENTRY("WP SAFE DISTANCE", SETTING_NAV_WP_SAFE_DISTANCE),
|
||||
#ifdef USE_MULTI_MISSION
|
||||
OSD_SETTING_ENTRY("MULTI MISSION NUMBER", SETTING_NAV_WP_MULTI_MISSION_INDEX),
|
||||
|
||||
#endif
|
||||
OSD_BACK_AND_END_ENTRY,
|
||||
};
|
||||
|
||||
|
@ -233,5 +232,3 @@ const CMS_Menu cmsx_menuNavigation = {
|
|||
.onGlobalExit = NULL,
|
||||
.entries = cmsx_menuNavigationEntries
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
|
@ -146,6 +146,7 @@ static const OSD_Entry menuCrsfRxEntries[]=
|
|||
OSD_SETTING_ENTRY("LQ FORMAT", SETTING_OSD_CRSF_LQ_FORMAT),
|
||||
OSD_SETTING_ENTRY("LQ ALARM LEVEL", SETTING_OSD_LINK_QUALITY_ALARM),
|
||||
OSD_SETTING_ENTRY("SNR ALARM LEVEL", SETTING_OSD_SNR_ALARM),
|
||||
OSD_SETTING_ENTRY("RX SENSITIVITY", SETTING_OSD_RSSI_DBM_MIN),
|
||||
OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_CRSF_RSSI_DBM),
|
||||
OSD_ELEMENT_ENTRY("RX LQ", OSD_CRSF_LQ),
|
||||
OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_CRSF_SNR_DB),
|
||||
|
@ -426,7 +427,6 @@ static const OSD_Entry menuOsdHud2Entries[] = {
|
|||
OSD_SETTING_ENTRY("RADAR MAX AIRCRAFT", SETTING_OSD_HUD_RADAR_DISP),
|
||||
OSD_SETTING_ENTRY("RADAR MIN RANGE", SETTING_OSD_HUD_RADAR_RANGE_MIN),
|
||||
OSD_SETTING_ENTRY("RADAR MAX RANGE", SETTING_OSD_HUD_RADAR_RANGE_MAX),
|
||||
OSD_SETTING_ENTRY("RADAR DET. NEAREST", SETTING_OSD_HUD_RADAR_NEAREST),
|
||||
OSD_SETTING_ENTRY("NEXT WAYPOINTS", SETTING_OSD_HUD_WP_DISP),
|
||||
OSD_BACK_ENTRY,
|
||||
OSD_END_ENTRY,
|
||||
|
|
|
@ -274,8 +274,8 @@ static bool bmi270AccReadScratchpad(accDev_t *acc)
|
|||
bmi270ContextData_t * ctx = busDeviceGetScratchpadMemory(acc->busDev);
|
||||
|
||||
if (ctx->lastReadStatus) {
|
||||
acc->ADCRaw[X] = (int16_t)((ctx->accRaw[1] << 8) | ctx->accRaw[0]);
|
||||
acc->ADCRaw[Y] = (int16_t)((ctx->accRaw[3] << 8) | ctx->accRaw[2]);
|
||||
acc->ADCRaw[X] = -(int16_t)((ctx->accRaw[1] << 8) | ctx->accRaw[0]);
|
||||
acc->ADCRaw[Y] = -(int16_t)((ctx->accRaw[3] << 8) | ctx->accRaw[2]);
|
||||
acc->ADCRaw[Z] = (int16_t)((ctx->accRaw[5] << 8) | ctx->accRaw[4]);
|
||||
return true;
|
||||
}
|
||||
|
@ -349,6 +349,7 @@ bool bmi270GyroDetect(gyroDev_t *gyro)
|
|||
gyro->temperatureFn = bmi270TemperatureRead;
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->scale = 1.0f / 16.4f; // 2000 dps
|
||||
gyro->gyroAlign = gyro->busDev->param;
|
||||
return true;
|
||||
}
|
||||
#endif // USE_IMU_BMI270
|
||||
|
|
|
@ -1,124 +0,0 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_l3gd20.h"
|
||||
|
||||
#ifdef USE_IMU_L3GD20
|
||||
|
||||
#define READ_CMD ((uint8_t)0x80)
|
||||
#define MULTIPLEBYTE_CMD ((uint8_t)0x40)
|
||||
#define DUMMY_BYTE ((uint8_t)0x00)
|
||||
|
||||
#define CTRL_REG1_ADDR 0x20
|
||||
#define CTRL_REG4_ADDR 0x23
|
||||
#define CTRL_REG5_ADDR 0x24
|
||||
#define OUT_TEMP_ADDR 0x26
|
||||
#define OUT_X_L_ADDR 0x28
|
||||
|
||||
#define MODE_ACTIVE ((uint8_t)0x08)
|
||||
|
||||
#define OUTPUT_DATARATE_1 ((uint8_t)0x00)
|
||||
#define OUTPUT_DATARATE_2 ((uint8_t)0x40)
|
||||
#define OUTPUT_DATARATE_3 ((uint8_t)0x80)
|
||||
#define OUTPUT_DATARATE_4 ((uint8_t)0xC0)
|
||||
|
||||
#define AXES_ENABLE ((uint8_t)0x07)
|
||||
|
||||
#define BANDWIDTH_1 ((uint8_t)0x00)
|
||||
#define BANDWIDTH_2 ((uint8_t)0x10)
|
||||
#define BANDWIDTH_3 ((uint8_t)0x20)
|
||||
#define BANDWIDTH_4 ((uint8_t)0x30)
|
||||
|
||||
#define FULLSCALE_250 ((uint8_t)0x00)
|
||||
#define FULLSCALE_500 ((uint8_t)0x10)
|
||||
#define FULLSCALE_2000 ((uint8_t)0x20)
|
||||
|
||||
#define BLOCK_DATA_UPDATE_CONTINUOUS ((uint8_t)0x00)
|
||||
|
||||
#define BLE_MSB ((uint8_t)0x40)
|
||||
|
||||
#define BOOT ((uint8_t)0x80)
|
||||
|
||||
void l3gd20GyroInit(gyroDev_t *gyro)
|
||||
{
|
||||
busWrite(gyro->busDev, CTRL_REG5_ADDR, BOOT);
|
||||
delay(1);
|
||||
|
||||
busWrite(gyro->busDev, CTRL_REG1_ADDR, MODE_ACTIVE | OUTPUT_DATARATE_3 | AXES_ENABLE | BANDWIDTH_3);
|
||||
delay(1);
|
||||
|
||||
busWrite(gyro->busDev, CTRL_REG4_ADDR, BLOCK_DATA_UPDATE_CONTINUOUS | BLE_MSB | FULLSCALE_2000);
|
||||
delay(100);
|
||||
}
|
||||
|
||||
static bool l3gd20GyroRead(gyroDev_t *gyro)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
busReadBuf(gyro->busDev, OUT_X_L_ADDR | READ_CMD | MULTIPLEBYTE_CMD, buf, 6);
|
||||
|
||||
gyro->gyroADCRaw[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyro->gyroADCRaw[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyro->gyroADCRaw[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool deviceDetect(busDevice_t * dev)
|
||||
{
|
||||
UNUSED(dev);
|
||||
return true; // blindly assume it's present, for now.
|
||||
}
|
||||
|
||||
bool l3gd20Detect(gyroDev_t *gyro)
|
||||
{
|
||||
gyro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_L3GD20, gyro->imuSensorToUse, OWNER_MPU);
|
||||
if (gyro->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!deviceDetect(gyro->busDev)) {
|
||||
busDeviceDeInit(gyro->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
gyro->initFn = l3gd20GyroInit;
|
||||
gyro->readFn = l3gd20GyroRead;
|
||||
|
||||
// Page 9 in datasheet, So - Sensitivity, Full Scale = 2000, 70 mdps/digit
|
||||
gyro->scale = 0.07f;
|
||||
gyro->gyroAlign = gyro->busDev->param;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,170 +0,0 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_IMU_LSM303DLHC
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_lsm303dlhc.h"
|
||||
|
||||
// Addresses (7 bit address format)
|
||||
|
||||
#define LSM303DLHC_ACCEL_ADDRESS 0x19
|
||||
#define LSM303DLHC_MAG_ADDRESS 0x1E
|
||||
|
||||
/**
|
||||
* Address Auto Increment - See LSM303DLHC datasheet, Section 5.1.1 I2C operation.
|
||||
* http://www.st.com/web/en/resource/technical/document/datasheet/DM00027543.pdf
|
||||
*
|
||||
* "The I2C embedded inside the LSM303DLHC behaves like a slave device and the following protocol must be adhered to.
|
||||
* After the START condition (ST) a slave address is sent, once a slave acknowledge (SAK) has been returned, an 8-bit
|
||||
* sub-address (SUB) is transmitted; the 7 LSBs represent the actual register address while the MSB enables address
|
||||
* autoincrement.
|
||||
*
|
||||
* If the MSB of the SUB field is ‘1’, the SUB (register address) is automatically increased to allow multiple data
|
||||
* Read/Write.
|
||||
*
|
||||
* To minimize the communication between the master and magnetic digital interface of LSM303DLHC, the address pointer
|
||||
* updates automatically without master intervention. This automatic address pointer update has two additional
|
||||
* features. First, when address 12 or higher is accessed, the pointer updates to address 00, and secondly, when
|
||||
* address 08 is reached, the pointer rolls back to address 03. Logically, the address pointer operation functions
|
||||
* as shown below.
|
||||
* 1) If (address pointer = 08) then the address pointer = 03
|
||||
* Or else, if (address pointer >= 12) then the address pointer = 0
|
||||
* Or else, (address pointer) = (address pointer) + 1
|
||||
*
|
||||
* The address pointer value itself cannot be read via the I2C bus"
|
||||
*/
|
||||
#define AUTO_INCREMENT_ENABLE 0x80
|
||||
|
||||
// Registers
|
||||
|
||||
#define LSM303DLHC_STATUS_REG_A 0x27 /* Status register acceleration */
|
||||
#define CTRL_REG1_A 0x20
|
||||
#define CTRL_REG4_A 0x23
|
||||
#define CTRL_REG5_A 0x24
|
||||
#define OUT_X_L_A 0x28
|
||||
#define CRA_REG_M 0x00
|
||||
#define CRB_REG_M 0x01
|
||||
#define MR_REG_M 0x02
|
||||
#define OUT_X_H_M 0x03
|
||||
|
||||
///////////////////////////////////////
|
||||
|
||||
#define ODR_1344_HZ 0x90
|
||||
#define AXES_ENABLE 0x07
|
||||
|
||||
#define FULLSCALE_2G 0x00
|
||||
#define FULLSCALE_4G 0x10
|
||||
#define FULLSCALE_8G 0x20
|
||||
#define FULLSCALE_16G 0x30
|
||||
|
||||
#define BOOT 0x80
|
||||
|
||||
///////////////////////////////////////
|
||||
|
||||
#define ODR_75_HZ 0x18
|
||||
#define ODR_15_HZ 0x10
|
||||
|
||||
#define FS_1P3_GA 0x20
|
||||
#define FS_1P9_GA 0x40
|
||||
#define FS_2P5_GA 0x60
|
||||
#define FS_4P0_GA 0x80
|
||||
#define FS_4P7_GA 0xA0
|
||||
#define FS_5P6_GA 0xC0
|
||||
#define FS_8P1_GA 0xE0
|
||||
|
||||
#define CONTINUOUS_CONVERSION 0x00
|
||||
|
||||
void lsm303dlhcAccInit(accDev_t *acc)
|
||||
{
|
||||
busWrite(acc->busDev, CTRL_REG5_A, BOOT);
|
||||
delay(100);
|
||||
|
||||
busWrite(acc->busDev, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE);
|
||||
delay(10);
|
||||
|
||||
busWrite(acc->busDev, CTRL_REG4_A, FULLSCALE_4G);
|
||||
delay(100);
|
||||
|
||||
acc->acc_1G = 512 * 8;
|
||||
}
|
||||
|
||||
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
|
||||
static bool lsm303dlhcAccRead(accDev_t *acc)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
bool ack = busReadBuf(acc->busDev, AUTO_INCREMENT_ENABLE | OUT_X_L_A, buf, 6);
|
||||
|
||||
if (!ack) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// the values range from -8192 to +8191
|
||||
acc->ADCRaw[X] = (int16_t)((buf[1] << 8) | buf[0]) / 2;
|
||||
acc->ADCRaw[Y] = (int16_t)((buf[3] << 8) | buf[2]) / 2;
|
||||
acc->ADCRaw[Z] = (int16_t)((buf[5] << 8) | buf[4]) / 2;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool deviceDetect(busDevice_t * busDev)
|
||||
{
|
||||
bool ack = false;
|
||||
uint8_t status = 0;
|
||||
|
||||
ack = busRead(busDev, LSM303DLHC_STATUS_REG_A, &status);
|
||||
if (!ack)
|
||||
return false;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool lsm303dlhcAccDetect(accDev_t *acc)
|
||||
{
|
||||
acc->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_LSM303DLHC, acc->imuSensorToUse, OWNER_MPU);
|
||||
if (acc->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!deviceDetect(acc->busDev)) {
|
||||
busDeviceDeInit(acc->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
acc->initFn = lsm303dlhcAccInit;
|
||||
acc->readFn = lsm303dlhcAccRead;
|
||||
acc->accAlign = acc->busDev->param;
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -26,7 +26,7 @@
|
|||
// MPU6050
|
||||
#define MPU_RA_WHO_AM_I_LEGACY 0x00
|
||||
|
||||
#define MPUx0x0_WHO_AM_I_CONST (0x68) // MPU3050, 6000 and 6050
|
||||
#define MPUx0x0_WHO_AM_I_CONST (0x68) // MPU6000 and 6050
|
||||
#define MPU6000_WHO_AM_I_CONST (0x68)
|
||||
#define MPU6500_WHO_AM_I_CONST (0x70)
|
||||
#define MPU9250_WHO_AM_I_CONST (0x71)
|
||||
|
|
|
@ -1,139 +0,0 @@
|
|||
/*
|
||||
* 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 <stdbool.h>
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
#include "drivers/accgyro/accgyro_mpu3050.h"
|
||||
|
||||
#ifdef USE_IMU_MPU3050
|
||||
|
||||
// MPU3050, Standard address 0x68
|
||||
#define MPU3050_ADDRESS 0x68
|
||||
|
||||
// Bits
|
||||
#define MPU3050_FS_SEL_2000DPS 0x18
|
||||
#define MPU3050_DLPF_10HZ 0x05
|
||||
#define MPU3050_DLPF_20HZ 0x04
|
||||
#define MPU3050_DLPF_42HZ 0x03
|
||||
#define MPU3050_DLPF_98HZ 0x02
|
||||
#define MPU3050_DLPF_188HZ 0x01
|
||||
#define MPU3050_DLPF_256HZ 0x00
|
||||
|
||||
#define MPU3050_SMPLRT_DIV 0x15
|
||||
#define MPU3050_DLPF_FS_SYNC 0x16
|
||||
#define MPU3050_INT_CFG 0x17
|
||||
#define MPU3050_TEMP_OUT 0x1B
|
||||
#define MPU3050_GYRO_OUT 0x1D
|
||||
#define MPU3050_USER_CTRL 0x3D
|
||||
#define MPU3050_PWR_MGM 0x3E
|
||||
|
||||
#define MPU3050_USER_RESET 0x01
|
||||
#define MPU3050_CLK_SEL_PLL_GX 0x01
|
||||
|
||||
#define MPU_INQUIRY_MASK 0x7E
|
||||
|
||||
static void mpu3050Init(gyroDev_t *gyro)
|
||||
{
|
||||
bool ack;
|
||||
busDevice_t * busDev = gyro->busDev;
|
||||
const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs);
|
||||
gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz;
|
||||
|
||||
delay(25); // datasheet page 13 says 20ms. other stuff could have been running meanwhile. but we'll be safe
|
||||
|
||||
ack = busWrite(busDev, MPU3050_SMPLRT_DIV, config->gyroConfigValues[1]);
|
||||
if (!ack) {
|
||||
failureMode(FAILURE_ACC_INIT);
|
||||
}
|
||||
|
||||
busWrite(busDev, MPU3050_DLPF_FS_SYNC, MPU3050_FS_SEL_2000DPS | config->gyroConfigValues[0]);
|
||||
busWrite(busDev, MPU3050_INT_CFG, 0);
|
||||
busWrite(busDev, MPU3050_USER_CTRL, MPU3050_USER_RESET);
|
||||
busWrite(busDev, MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);
|
||||
}
|
||||
|
||||
static bool mpu3050GyroRead(gyroDev_t *gyro)
|
||||
{
|
||||
uint8_t data[6];
|
||||
|
||||
const bool ack = busReadBuf(gyro->busDev, MPU3050_GYRO_OUT, data, 6);
|
||||
if (!ack) {
|
||||
return false;
|
||||
}
|
||||
|
||||
gyro->gyroADCRaw[X] = (int16_t)((data[0] << 8) | data[1]);
|
||||
gyro->gyroADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]);
|
||||
gyro->gyroADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool deviceDetect(busDevice_t * busDev)
|
||||
{
|
||||
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
|
||||
|
||||
for (int retry = 0; retry < 5; retry++) {
|
||||
uint8_t inquiryResult;
|
||||
|
||||
delay(150);
|
||||
|
||||
bool ack = busRead(busDev, MPU_RA_WHO_AM_I_LEGACY, &inquiryResult);
|
||||
inquiryResult &= MPU_INQUIRY_MASK;
|
||||
if (ack && inquiryResult == MPUx0x0_WHO_AM_I_CONST) {
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool mpu3050Detect(gyroDev_t *gyro)
|
||||
{
|
||||
gyro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_MPU3050, gyro->imuSensorToUse, OWNER_MPU);
|
||||
if (gyro->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!deviceDetect(gyro->busDev)) {
|
||||
busDeviceDeInit(gyro->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
gyro->initFn = mpu3050Init;
|
||||
gyro->readFn = mpu3050GyroRead;
|
||||
gyro->intStatusFn = gyroCheckDataReady;
|
||||
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
|
||||
gyro->gyroAlign = gyro->busDev->param;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -75,14 +75,7 @@ typedef enum {
|
|||
typedef enum {
|
||||
DEVHW_NONE = 0,
|
||||
|
||||
/* Dedicated ACC chips */
|
||||
DEVHW_LSM303DLHC,
|
||||
|
||||
/* Dedicated GYRO chips */
|
||||
DEVHW_L3GD20,
|
||||
|
||||
/* Combined ACC/GYRO chips */
|
||||
DEVHW_MPU3050,
|
||||
DEVHW_MPU6000,
|
||||
DEVHW_MPU6050,
|
||||
DEVHW_MPU6500,
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
#define IRLOCK_FRAME_SYNC ((uint32_t)(IRLOCK_OBJECT_SYNC | (IRLOCK_OBJECT_SYNC << 16)))
|
||||
|
||||
|
||||
#if defined(USE_NAV) && defined(USE_IRLOCK)
|
||||
#if defined(USE_IRLOCK)
|
||||
|
||||
static bool irlockHealthy = false;
|
||||
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
#include "drivers/sensor.h"
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
#if defined(USE_NAV) && defined(USE_IRLOCK)
|
||||
#if defined(USE_IRLOCK)
|
||||
|
||||
#define IRLOCK_RES_X 320
|
||||
#define IRLOCK_RES_Y 200
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
#define WS2811_BIT_COMPARE_1 ((WS2811_PERIOD * 2) / 3)
|
||||
#define WS2811_BIT_COMPARE_0 (WS2811_PERIOD / 3)
|
||||
|
||||
static timerDMASafeType_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
static DMA_RAM timerDMASafeType_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
|
||||
static IO_t ws2811IO = IO_NONE;
|
||||
static TCH_t * ws2811TCH = NULL;
|
||||
|
|
|
@ -164,9 +164,13 @@ static uartDevice_t uart7 =
|
|||
{
|
||||
.dev = UART7,
|
||||
.rx = IO_TAG(UART7_RX_PIN),
|
||||
#ifdef UART7_TX_PIN
|
||||
.tx = IO_TAG(UART7_TX_PIN),
|
||||
#endif
|
||||
.af_rx = UART_PIN_AF_HELPER(7, UART7_RX_PIN),
|
||||
#ifdef UART7_TX_PIN
|
||||
.af_tx = UART_PIN_AF_HELPER(7, UART7_TX_PIN),
|
||||
#endif
|
||||
.rcc = RCC_APB1L(UART7),
|
||||
.irq = UART7_IRQn,
|
||||
};
|
||||
|
|
|
@ -169,7 +169,7 @@ static const char * const blackboxIncludeFlagNames[] = {
|
|||
|
||||
/* Sensor names (used in lookup tables for *_hardware settings and in status command output) */
|
||||
// sync with gyroSensor_e
|
||||
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"};
|
||||
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"};
|
||||
|
||||
// sync this with sensors_e
|
||||
static const char * const sensorTypeNames[] = {
|
||||
|
@ -1351,7 +1351,7 @@ static void cliSafeHomes(char *cmdline)
|
|||
}
|
||||
|
||||
#endif
|
||||
#if defined(USE_NAV) && defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) && defined(NAV_NON_VOLATILE_WAYPOINT_CLI)
|
||||
#if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) && defined(NAV_NON_VOLATILE_WAYPOINT_CLI)
|
||||
static void printWaypoints(uint8_t dumpMask, const navWaypoint_t *navWaypoint, const navWaypoint_t *defaultNavWaypoint)
|
||||
{
|
||||
cliPrintLinef("#wp %d %svalid", posControl.waypointCount, posControl.waypointListValid ? "" : "in"); //int8_t bool
|
||||
|
@ -1395,8 +1395,9 @@ static void printWaypoints(uint8_t dumpMask, const navWaypoint_t *navWaypoint, c
|
|||
|
||||
static void cliWaypoints(char *cmdline)
|
||||
{
|
||||
#ifdef USE_MULTI_MISSION
|
||||
static int8_t multiMissionWPCounter = 0;
|
||||
|
||||
#endif
|
||||
if (isEmpty(cmdline)) {
|
||||
printWaypoints(DUMP_MASTER, posControl.waypointList, NULL);
|
||||
} else if (sl_strcasecmp(cmdline, "reset") == 0) {
|
||||
|
@ -1408,6 +1409,7 @@ static void cliWaypoints(char *cmdline)
|
|||
for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) {
|
||||
if (!(posControl.waypointList[i].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP || posControl.waypointList[i].action == NAV_WP_ACTION_RTH || posControl.waypointList[i].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[i].action == NAV_WP_ACTION_LAND || posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD)) break;
|
||||
if (posControl.waypointList[i].flag == NAV_WP_FLAG_LAST) {
|
||||
#ifdef USE_MULTI_MISSION
|
||||
if (posControl.multiMissionCount == 1) {
|
||||
posControl.waypointCount = i + 1;
|
||||
posControl.waypointListValid = true;
|
||||
|
@ -1417,6 +1419,11 @@ static void cliWaypoints(char *cmdline)
|
|||
} else {
|
||||
posControl.multiMissionCount -= 1;
|
||||
}
|
||||
#else
|
||||
posControl.waypointCount = i + 1;
|
||||
posControl.waypointListValid = true;
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
if (posControl.waypointListValid) {
|
||||
|
@ -1431,7 +1438,11 @@ static void cliWaypoints(char *cmdline)
|
|||
uint8_t validArgumentCount = 0;
|
||||
const char *ptr = cmdline;
|
||||
i = fastA2I(ptr);
|
||||
#ifdef USE_MULTI_MISSION
|
||||
if (i + multiMissionWPCounter >= 0 && i + multiMissionWPCounter < NAV_MAX_WAYPOINTS) {
|
||||
#else
|
||||
if (i >= 0 && i < NAV_MAX_WAYPOINTS) {
|
||||
#endif
|
||||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
action = fastA2I(ptr);
|
||||
|
@ -1484,6 +1495,7 @@ static void cliWaypoints(char *cmdline)
|
|||
} else if (!(action == 0 || action == NAV_WP_ACTION_WAYPOINT || action == NAV_WP_ACTION_RTH || action == NAV_WP_ACTION_JUMP || action == NAV_WP_ACTION_HOLD_TIME || action == NAV_WP_ACTION_LAND || action == NAV_WP_ACTION_SET_POI || action == NAV_WP_ACTION_SET_HEAD) || !(flag == 0 || flag == NAV_WP_FLAG_LAST || flag == NAV_WP_FLAG_HOME)) {
|
||||
cliShowParseError();
|
||||
} else {
|
||||
#ifdef USE_MULTI_MISSION
|
||||
if (i + multiMissionWPCounter == 0) {
|
||||
posControl.multiMissionCount = 0;
|
||||
}
|
||||
|
@ -1503,6 +1515,16 @@ static void cliWaypoints(char *cmdline)
|
|||
multiMissionWPCounter += i + 1;
|
||||
posControl.multiMissionCount += 1;
|
||||
}
|
||||
#else
|
||||
posControl.waypointList[i].action = action;
|
||||
posControl.waypointList[i].lat = lat;
|
||||
posControl.waypointList[i].lon = lon;
|
||||
posControl.waypointList[i].alt = alt;
|
||||
posControl.waypointList[i].p1 = p1;
|
||||
posControl.waypointList[i].p2 = p2;
|
||||
posControl.waypointList[i].p3 = p3;
|
||||
posControl.waypointList[i].flag = flag;
|
||||
#endif
|
||||
}
|
||||
} else {
|
||||
cliShowArgumentRangeError("wp index", 0, NAV_MAX_WAYPOINTS - 1);
|
||||
|
@ -3669,7 +3691,7 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
printTempSensor(dumpMask, tempSensorConfig_CopyArray, tempSensorConfig(0));
|
||||
#endif
|
||||
|
||||
#if defined(USE_NAV) && defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) && defined(NAV_NON_VOLATILE_WAYPOINT_CLI)
|
||||
#if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) && defined(NAV_NON_VOLATILE_WAYPOINT_CLI)
|
||||
cliPrintHashLine("wp");
|
||||
printWaypoints(dumpMask, posControl.waypointList, nonVolatileWaypointList(0));
|
||||
#endif
|
||||
|
@ -3910,7 +3932,7 @@ const clicmd_t cmdTable[] = {
|
|||
CLI_COMMAND_DEF("temp_sensor", "change temp sensor settings", NULL, cliTempSensor),
|
||||
#endif
|
||||
CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
|
||||
#if defined(USE_NAV) && defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) && defined(NAV_NON_VOLATILE_WAYPOINT_CLI)
|
||||
#if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) && defined(NAV_NON_VOLATILE_WAYPOINT_CLI)
|
||||
CLI_COMMAND_DEF("wp", "waypoint list", NULL, cliWaypoints),
|
||||
#endif
|
||||
#ifdef USE_OSD
|
||||
|
|
|
@ -144,13 +144,11 @@ PG_RESET_TEMPLATE(adcChannelConfig_t, adcChannelConfig,
|
|||
}
|
||||
);
|
||||
|
||||
#ifdef USE_NAV
|
||||
void validateNavConfig(void)
|
||||
{
|
||||
// Make sure minAlt is not more than maxAlt, maxAlt cannot be set lower than 500.
|
||||
navConfigMutable()->general.land_slowdown_minalt = MIN(navConfig()->general.land_slowdown_minalt, navConfig()->general.land_slowdown_maxalt - 100);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// Stubs to handle target-specific configs
|
||||
|
@ -232,10 +230,8 @@ void validateAndFixConfig(void)
|
|||
pgResetCopy(serialConfigMutable(), PG_SERIAL_CONFIG);
|
||||
}
|
||||
|
||||
#if defined(USE_NAV)
|
||||
// Ensure sane values of navConfig settings
|
||||
validateNavConfig();
|
||||
#endif
|
||||
|
||||
// Limitations of different protocols
|
||||
#if !defined(USE_DSHOT)
|
||||
|
@ -352,9 +348,7 @@ static void activateConfig(void)
|
|||
|
||||
pidInit();
|
||||
|
||||
#ifdef USE_NAV
|
||||
navigationUsePIDs();
|
||||
#endif
|
||||
}
|
||||
|
||||
void readEEPROM(void)
|
||||
|
|
|
@ -158,11 +158,9 @@ bool areSensorsCalibrating(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_NAV
|
||||
if (!navIsCalibrationComplete()) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!accIsCalibrationComplete() && sensors(SENSOR_ACC)) {
|
||||
return true;
|
||||
|
@ -248,7 +246,6 @@ static void updateArmingStatus(void)
|
|||
DISABLE_ARMING_FLAG(ARMING_DISABLED_SYSTEM_OVERLOADED);
|
||||
}
|
||||
|
||||
#if defined(USE_NAV)
|
||||
/* CHECK: Navigation safety */
|
||||
if (navigationIsBlockingArming(NULL) != NAV_ARMING_BLOCKER_NONE) {
|
||||
ENABLE_ARMING_FLAG(ARMING_DISABLED_NAVIGATION_UNSAFE);
|
||||
|
@ -256,7 +253,6 @@ static void updateArmingStatus(void)
|
|||
else {
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_NAVIGATION_UNSAFE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_MAG)
|
||||
/* CHECK: */
|
||||
|
@ -515,8 +511,9 @@ void releaseSharedTelemetryPorts(void) {
|
|||
|
||||
void tryArm(void)
|
||||
{
|
||||
#ifdef USE_MULTI_MISSION
|
||||
setMultiMissionOnArm();
|
||||
|
||||
#endif
|
||||
updateArmingStatus();
|
||||
|
||||
#ifdef USE_DSHOT
|
||||
|
@ -551,7 +548,6 @@ void tryArm(void)
|
|||
return;
|
||||
}
|
||||
|
||||
#if defined(USE_NAV)
|
||||
// If nav_extra_arming_safety was bypassed we always
|
||||
// allow bypassing it even without the sticks set
|
||||
// in the correct position to allow re-arming quickly
|
||||
|
@ -561,7 +557,6 @@ void tryArm(void)
|
|||
if (usedBypass) {
|
||||
ENABLE_STATE(NAV_EXTRA_ARMING_SAFETY_BYPASSED);
|
||||
}
|
||||
#endif
|
||||
|
||||
lastDisarmReason = DISARM_NONE;
|
||||
|
||||
|
@ -590,15 +585,11 @@ void tryArm(void)
|
|||
#endif
|
||||
|
||||
//beep to indicate arming
|
||||
#ifdef USE_NAV
|
||||
if (navigationPositionEstimateIsHealthy()) {
|
||||
beeper(BEEPER_ARMING_GPS_FIX);
|
||||
} else {
|
||||
beeper(BEEPER_ARMING);
|
||||
}
|
||||
#else
|
||||
beeper(BEEPER_ARMING);
|
||||
#endif
|
||||
|
||||
statsOnArm();
|
||||
|
||||
|
@ -864,11 +855,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
cycleTime = getTaskDeltaTime(TASK_SELF);
|
||||
dT = (float)cycleTime * 0.000001f;
|
||||
|
||||
#if defined(USE_NAV)
|
||||
if (ARMING_FLAG(ARMED) && (!STATE(FIXED_WING_LEGACY) || !isNavLaunchEnabled() || (isNavLaunchEnabled() && fixedWingLaunchStatus() >= FW_LAUNCH_DETECTED))) {
|
||||
#else
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
#endif
|
||||
flightTime += cycleTime;
|
||||
armTime += cycleTime;
|
||||
updateAccExtremes();
|
||||
|
@ -888,18 +875,14 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
rcInterpolationApply(isRXDataNew);
|
||||
}
|
||||
|
||||
#if defined(USE_NAV)
|
||||
if (isRXDataNew) {
|
||||
updateWaypointsAndNavigationMode();
|
||||
}
|
||||
#endif
|
||||
|
||||
isRXDataNew = false;
|
||||
|
||||
#if defined(USE_NAV)
|
||||
updatePositionEstimator();
|
||||
applyWaypointNavigationAndAltitudeHold();
|
||||
#endif
|
||||
|
||||
// Apply throttle tilt compensation
|
||||
if (!STATE(FIXED_WING_LEGACY)) {
|
||||
|
|
|
@ -581,9 +581,7 @@ void init(void)
|
|||
#endif
|
||||
|
||||
|
||||
#ifdef USE_NAV
|
||||
navigationInit();
|
||||
#endif
|
||||
|
||||
#ifdef USE_LED_STRIP
|
||||
ledStripInit();
|
||||
|
|
|
@ -607,13 +607,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
break;
|
||||
|
||||
case MSP_ALTITUDE:
|
||||
#if defined(USE_NAV)
|
||||
sbufWriteU32(dst, lrintf(getEstimatedActualPosition(Z)));
|
||||
sbufWriteU16(dst, lrintf(getEstimatedActualVelocity(Z)));
|
||||
#else
|
||||
sbufWriteU32(dst, 0);
|
||||
sbufWriteU16(dst, 0);
|
||||
#endif
|
||||
#if defined(USE_BARO)
|
||||
sbufWriteU32(dst, baroGetLatestAltitude());
|
||||
#else
|
||||
|
@ -923,7 +918,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU16(dst, GPS_directionToHome);
|
||||
sbufWriteU8(dst, gpsSol.flags.gpsHeartbeat ? 1 : 0);
|
||||
break;
|
||||
#ifdef USE_NAV
|
||||
case MSP_NAV_STATUS:
|
||||
sbufWriteU8(dst, NAV_Status.mode);
|
||||
sbufWriteU8(dst, NAV_Status.state);
|
||||
|
@ -933,7 +927,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
//sbufWriteU16(dst, (int16_t)(target_bearing/100));
|
||||
sbufWriteU16(dst, getHeadingHoldTarget());
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
||||
case MSP_GPSSVINFO:
|
||||
/* Compatibility stub - return zero SVs */
|
||||
|
@ -1315,7 +1309,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#endif
|
||||
break;
|
||||
|
||||
#ifdef USE_NAV
|
||||
case MSP_NAV_POSHOLD:
|
||||
sbufWriteU8(dst, navConfig()->general.flags.user_control_mode);
|
||||
sbufWriteU16(dst, navConfig()->general.max_auto_speed);
|
||||
|
@ -1353,7 +1346,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, currentBatteryProfile->nav.fw.pitch_to_throttle);
|
||||
sbufWriteU16(dst, navConfig()->fw.loiter_radius);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP_CALIBRATION_DATA:
|
||||
sbufWriteU8(dst, accGetCalibrationAxisFlags());
|
||||
|
@ -1393,7 +1385,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
break;
|
||||
|
||||
case MSP_POSITION_ESTIMATION_CONFIG:
|
||||
#ifdef USE_NAV
|
||||
|
||||
sbufWriteU16(dst, positionEstimationConfig()->w_z_baro_p * 100); // inav_w_z_baro_p float as value * 100
|
||||
sbufWriteU16(dst, positionEstimationConfig()->w_z_gps_p * 100); // 2 inav_w_z_gps_p float as value * 100
|
||||
|
@ -1403,15 +1394,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, gpsConfigMutable()->gpsMinSats); // 1
|
||||
sbufWriteU8(dst, positionEstimationConfig()->use_gps_velned); // 1 inav_use_gps_velned ON/OFF
|
||||
|
||||
#else
|
||||
sbufWriteU16(dst, 0);
|
||||
sbufWriteU16(dst, 0);
|
||||
sbufWriteU16(dst, 0);
|
||||
sbufWriteU16(dst, 0);
|
||||
sbufWriteU16(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
#endif
|
||||
break;
|
||||
|
||||
case MSP_REBOOT:
|
||||
|
@ -1423,17 +1405,10 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
break;
|
||||
|
||||
case MSP_WP_GETINFO:
|
||||
#ifdef USE_NAV
|
||||
sbufWriteU8(dst, 0); // Reserved for waypoint capabilities
|
||||
sbufWriteU8(dst, NAV_MAX_WAYPOINTS); // Maximum number of waypoints supported
|
||||
sbufWriteU8(dst, isWaypointListValid()); // Is current mission valid
|
||||
sbufWriteU8(dst, getWaypointCount()); // Number of waypoints in current mission
|
||||
#else
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
#endif
|
||||
break;
|
||||
|
||||
case MSP_TX_INFO:
|
||||
|
@ -1622,7 +1597,6 @@ static mspResult_e mspFcSafeHomeOutCommand(sbuf_t *dst, sbuf_t *src)
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_NAV
|
||||
static void mspFcWaypointOutCommand(sbuf_t *dst, sbuf_t *src)
|
||||
{
|
||||
const uint8_t msp_wp_no = sbufReadU8(src); // get the wp number
|
||||
|
@ -1638,7 +1612,6 @@ static void mspFcWaypointOutCommand(sbuf_t *dst, sbuf_t *src)
|
|||
sbufWriteU16(dst, msp_wp.p3); // P3
|
||||
sbufWriteU8(dst, msp_wp.flag); // flags
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
static void mspFcDataFlashReadCommand(sbuf_t *dst, sbuf_t *src)
|
||||
|
@ -1728,9 +1701,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
pidBankMutable()->pid[i].D = sbufReadU8(src);
|
||||
}
|
||||
schedulePidGainsUpdate();
|
||||
#if defined(USE_NAV)
|
||||
navigationUsePIDs();
|
||||
#endif
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
@ -1744,9 +1715,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
pidBankMutable()->pid[i].FF = sbufReadU8(src);
|
||||
}
|
||||
schedulePidGainsUpdate();
|
||||
#if defined(USE_NAV)
|
||||
navigationUsePIDs();
|
||||
#endif
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
@ -2284,7 +2253,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
#ifdef USE_NAV
|
||||
case MSP_SET_NAV_POSHOLD:
|
||||
if (dataSize >= 13) {
|
||||
navConfigMutable()->general.flags.user_control_mode = sbufReadU8(src);
|
||||
|
@ -2331,7 +2299,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP_SET_CALIBRATION_DATA:
|
||||
if (dataSize >= 18) {
|
||||
|
@ -2373,7 +2340,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
#ifdef USE_NAV
|
||||
case MSP_SET_POSITION_ESTIMATION_CONFIG:
|
||||
if (dataSize >= 12) {
|
||||
positionEstimationConfigMutable()->w_z_baro_p = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f);
|
||||
|
@ -2386,7 +2352,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP_RESET_CONF:
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
|
@ -2576,7 +2541,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#ifdef USE_NAV
|
||||
case MSP_SET_WP:
|
||||
if (dataSize >= 21) {
|
||||
const uint8_t msp_wp_no = sbufReadU8(src); // get the waypoint number
|
||||
|
@ -2606,7 +2570,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP_SET_FEATURE:
|
||||
if (dataSize >= 4) {
|
||||
|
@ -3314,12 +3277,10 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
|
|||
{
|
||||
switch (cmdMSP) {
|
||||
|
||||
#if defined(USE_NAV)
|
||||
case MSP_WP:
|
||||
mspFcWaypointOutCommand(dst, src);
|
||||
*ret = MSP_RESULT_ACK;
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if defined(USE_FLASHFS)
|
||||
case MSP_DATAFLASH_READ:
|
||||
|
|
|
@ -225,7 +225,7 @@ void taskUpdateRangefinder(timeUs_t currentTimeUs)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_NAV) && defined(USE_IRLOCK)
|
||||
#if defined(USE_IRLOCK)
|
||||
void taskUpdateIrlock(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
|
|
@ -251,7 +251,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
|||
}
|
||||
|
||||
|
||||
#if defined(USE_NAV) && defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE)
|
||||
#if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE)
|
||||
// Save waypoint list
|
||||
if (rcSticks == THR_LO + YAW_CE + PIT_HI + ROL_LO) {
|
||||
const bool success = saveNonVolatileWaypointList();
|
||||
|
@ -263,7 +263,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
|||
const bool success = loadNonVolatileWaypointList(false);
|
||||
beeper(success ? BEEPER_ACTION_SUCCESS : BEEPER_ACTION_FAIL);
|
||||
}
|
||||
|
||||
#ifdef USE_MULTI_MISSION
|
||||
// Increment multi mission index up
|
||||
if (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_HI) {
|
||||
selectMultiMissionIndex(1);
|
||||
|
@ -277,7 +277,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
|
|||
rcDelayCommand = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
#endif
|
||||
if (rcSticks == THR_LO + YAW_CE + PIT_LO + ROL_HI) {
|
||||
resetWaypointList();
|
||||
beeper(BEEPER_ACTION_FAIL); // The above cannot fail, but traditionally, we play FAIL for not-loading
|
||||
|
|
|
@ -39,9 +39,7 @@
|
|||
#include "rx/rx.h"
|
||||
|
||||
static uint8_t specifiedConditionCountPerMode[CHECKBOX_ITEM_COUNT];
|
||||
#ifdef USE_NAV
|
||||
static bool isUsingNAVModes = false;
|
||||
#endif
|
||||
|
||||
boxBitmask_t rcModeActivationMask; // one bit per mode defined in boxId_e
|
||||
|
||||
|
@ -84,7 +82,7 @@ static void processAirmodeMultirotor(void) {
|
|||
*/
|
||||
DISABLE_STATE(AIRMODE_ACTIVE);
|
||||
} else if (
|
||||
!STATE(AIRMODE_ACTIVE) &&
|
||||
!STATE(AIRMODE_ACTIVE) &&
|
||||
rcCommand[THROTTLE] > rcControlsConfig()->airmodeThrottleThreshold &&
|
||||
(feature(FEATURE_AIRMODE) || IS_RC_MODE_ACTIVE(BOXAIRMODE))
|
||||
) {
|
||||
|
@ -119,13 +117,10 @@ void processAirmode(void) {
|
|||
|
||||
}
|
||||
|
||||
#if defined(USE_NAV)
|
||||
bool isUsingNavigationModes(void)
|
||||
{
|
||||
return isUsingNAVModes;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
bool IS_RC_MODE_ACTIVE(boxId_e boxId)
|
||||
{
|
||||
|
@ -208,13 +203,11 @@ void updateUsedModeActivationConditionFlags(void)
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_NAV
|
||||
isUsingNAVModes = isModeActivationConditionPresent(BOXNAVPOSHOLD) ||
|
||||
isModeActivationConditionPresent(BOXNAVRTH) ||
|
||||
isModeActivationConditionPresent(BOXNAVCOURSEHOLD) ||
|
||||
isModeActivationConditionPresent(BOXNAVCRUISE) ||
|
||||
isModeActivationConditionPresent(BOXNAVWP);
|
||||
#endif
|
||||
}
|
||||
|
||||
void configureModeActivationCondition(int macIndex, boxId_e modeId, uint8_t auxChannelIndex, uint16_t startPwm, uint16_t endPwm)
|
||||
|
|
|
@ -4,7 +4,7 @@ tables:
|
|||
- name: gyro_lpf
|
||||
values: ["256HZ", "188HZ", "98HZ", "42HZ", "20HZ", "10HZ"]
|
||||
- name: acc_hardware
|
||||
values: ["NONE", "AUTO", "MPU6050", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"]
|
||||
values: ["NONE", "AUTO", "MPU6050", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"]
|
||||
enum: accelerationSensor_e
|
||||
- name: rangefinder_hardware
|
||||
values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"]
|
||||
|
@ -1885,7 +1885,6 @@ groups:
|
|||
description: "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."
|
||||
default_value: "RIGHT"
|
||||
field: loiter_direction
|
||||
condition: USE_NAV
|
||||
table: direction
|
||||
- name: fw_reference_airspeed
|
||||
description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present."
|
||||
|
@ -1954,21 +1953,18 @@ groups:
|
|||
- name: nav_mc_pos_z_p
|
||||
description: "P gain of altitude PID controller (Multirotor)"
|
||||
field: bank_mc.pid[PID_POS_Z].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 50
|
||||
- name: nav_mc_vel_z_p
|
||||
description: "P gain of velocity PID controller"
|
||||
field: bank_mc.pid[PID_VEL_Z].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 100
|
||||
- name: nav_mc_vel_z_i
|
||||
description: "I gain of velocity PID controller"
|
||||
field: bank_mc.pid[PID_VEL_Z].I
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 50
|
||||
|
@ -1976,41 +1972,35 @@ groups:
|
|||
description: "D gain of velocity PID controller"
|
||||
default_value: 10
|
||||
field: bank_mc.pid[PID_VEL_Z].D
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 10
|
||||
- name: nav_mc_pos_xy_p
|
||||
description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity"
|
||||
field: bank_mc.pid[PID_POS_XY].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 65
|
||||
- name: nav_mc_vel_xy_p
|
||||
description: "P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause \"nervous\" behavior and oscillations"
|
||||
field: bank_mc.pid[PID_VEL_XY].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 40
|
||||
- name: nav_mc_vel_xy_i
|
||||
description: "I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot"
|
||||
field: bank_mc.pid[PID_VEL_XY].I
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 15
|
||||
- name: nav_mc_vel_xy_d
|
||||
description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target."
|
||||
field: bank_mc.pid[PID_VEL_XY].D
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 100
|
||||
- name: nav_mc_vel_xy_ff
|
||||
field: bank_mc.pid[PID_VEL_XY].FF
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
default_value: 40
|
||||
|
@ -2018,7 +2008,6 @@ groups:
|
|||
description: "P gain of Heading Hold controller (Multirotor)"
|
||||
default_value: 60
|
||||
field: bank_mc.pid[PID_HEADING].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_mc_vel_xy_dterm_lpf_hz
|
||||
|
@ -2048,70 +2037,60 @@ groups:
|
|||
description: "P gain of altitude PID controller (Fixedwing)"
|
||||
default_value: 40
|
||||
field: bank_fw.pid[PID_POS_Z].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_z_i
|
||||
description: "I gain of altitude PID controller (Fixedwing)"
|
||||
default_value: 5
|
||||
field: bank_fw.pid[PID_POS_Z].I
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_z_d
|
||||
description: "D gain of altitude PID controller (Fixedwing)"
|
||||
default_value: 10
|
||||
field: bank_fw.pid[PID_POS_Z].D
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_xy_p
|
||||
description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH"
|
||||
default_value: 75
|
||||
field: bank_fw.pid[PID_POS_XY].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_xy_i
|
||||
description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
|
||||
default_value: 5
|
||||
field: bank_fw.pid[PID_POS_XY].I
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_xy_d
|
||||
description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
|
||||
default_value: 8
|
||||
field: bank_fw.pid[PID_POS_XY].D
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_heading_p
|
||||
description: "P gain of Heading Hold controller (Fixedwing)"
|
||||
default_value: 60
|
||||
field: bank_fw.pid[PID_HEADING].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_hdg_p
|
||||
description: "P gain of heading PID controller. (Fixedwing, rovers, boats)"
|
||||
default_value: 30
|
||||
field: bank_fw.pid[PID_POS_HEADING].P
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_hdg_i
|
||||
description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
|
||||
default_value: 2
|
||||
field: bank_fw.pid[PID_POS_HEADING].I
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_hdg_d
|
||||
description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
|
||||
default_value: 0
|
||||
field: bank_fw.pid[PID_POS_HEADING].D
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_fw_pos_hdg_pidsum_limit
|
||||
|
@ -2244,7 +2223,6 @@ groups:
|
|||
|
||||
- name: PG_POSITION_ESTIMATION_CONFIG
|
||||
type: positionEstimationConfig_t
|
||||
condition: USE_NAV
|
||||
members:
|
||||
- name: inav_auto_mag_decl
|
||||
description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored."
|
||||
|
@ -2376,7 +2354,6 @@ groups:
|
|||
- name: PG_NAV_CONFIG
|
||||
type: navConfig_t
|
||||
headers: ["navigation/navigation.h"]
|
||||
condition: USE_NAV
|
||||
members:
|
||||
- name: nav_disarm_on_landing
|
||||
description: "If set to ON, iNav disarms the FC after landing"
|
||||
|
@ -2429,6 +2406,7 @@ groups:
|
|||
description: "Index of mission selected from multi mission WP entry loaded in flight controller. 1 is the first useable WP mission in the entry. Limited to a maximum of 9 missions. Set index to 0 to display current active WP count in OSD Mission field."
|
||||
default_value: 1
|
||||
field: general.waypoint_multi_mission_index
|
||||
condition: USE_MULTI_MISSION
|
||||
min: 0
|
||||
max: 9
|
||||
- name: nav_auto_speed
|
||||
|
@ -2668,14 +2646,12 @@ groups:
|
|||
description: "Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting"
|
||||
default_value: 120
|
||||
field: mc.posDecelerationTime
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_mc_pos_expo
|
||||
description: "Expo for PosHold control"
|
||||
default_value: 10
|
||||
field: mc.posResponseExpo
|
||||
condition: USE_NAV
|
||||
min: 0
|
||||
max: 255
|
||||
- name: nav_mc_wp_slowdown
|
||||
|
@ -3221,6 +3197,20 @@ groups:
|
|||
field: rssi_dbm_alarm
|
||||
min: -130
|
||||
max: 0
|
||||
- name: osd_rssi_dbm_max
|
||||
condition: USE_SERIALRX_CRSF
|
||||
description: "RSSI dBm upper end of curve. Perfect rssi (max) = 100%"
|
||||
default_value: -30
|
||||
field: rssi_dbm_max
|
||||
min: -50
|
||||
max: 0
|
||||
- name: osd_rssi_dbm_min
|
||||
condition: USE_SERIALRX_CRSF
|
||||
description: "RSSI dBm lower end of curve or RX sensitivity level. Worst rssi (min) = 0%"
|
||||
default_value: -120
|
||||
field: rssi_dbm_min
|
||||
min: -130
|
||||
max: 0
|
||||
- name: osd_temp_label_align
|
||||
description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`"
|
||||
default_value: "LEFT"
|
||||
|
@ -3334,12 +3324,6 @@ groups:
|
|||
field: hud_radar_range_max
|
||||
min: 100
|
||||
max: 9990
|
||||
- name: osd_hud_radar_nearest
|
||||
description: "To display an extra bar of informations at the bottom of the hud area for the closest radar aircraft found, if closest than the set value, in meters. Shows relative altitude (meters or feet, with an up or down arrow to indicate if above or below), speed (in m/s or f/s), and absolute heading (in °, 0 is north, 90 is east, 180 is south, 270 is west). Set to 0 (zero) to disable."
|
||||
default_value: 0
|
||||
field: hud_radar_nearest
|
||||
min: 0
|
||||
max: 4000
|
||||
- name: osd_hud_wp_disp
|
||||
description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2)"
|
||||
default_value: 0
|
||||
|
@ -3601,6 +3585,11 @@ groups:
|
|||
default_value: ON
|
||||
field: smartAudioEarlyAkkWorkaroundEnable
|
||||
type: bool
|
||||
- name: vtx_smartaudio_alternate_softserial_method
|
||||
description: "Enable the alternate softserial method. This is the method used in iNav 3.0 and ealier."
|
||||
default_value: ON
|
||||
field: smartAudioAltSoftSerialMethod
|
||||
type: bool
|
||||
|
||||
- name: PG_VTX_SETTINGS_CONFIG
|
||||
type: vtxSettingsConfig_t
|
||||
|
|
|
@ -26,6 +26,8 @@
|
|||
|
||||
#ifdef USE_DYNAMIC_FILTERS
|
||||
|
||||
FILE_COMPILE_FOR_SPEED
|
||||
|
||||
#include <stdint.h>
|
||||
#include "dynamic_gyro_notch.h"
|
||||
#include "fc/config.h"
|
||||
|
@ -33,7 +35,12 @@
|
|||
#include "sensors/gyro.h"
|
||||
|
||||
void dynamicGyroNotchFiltersInit(dynamicGyroNotchState_t *state) {
|
||||
state->filtersApplyFn = nullFilterApply;
|
||||
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
|
||||
state->filtersApplyFn[axis][i] = nullFilterApply;
|
||||
}
|
||||
}
|
||||
|
||||
state->dynNotchQ = gyroConfig()->dynamicGyroNotchQ / 100.0f;
|
||||
state->enabled = gyroConfig()->dynamicGyroNotchEnabled;
|
||||
|
@ -45,27 +52,32 @@ void dynamicGyroNotchFiltersInit(dynamicGyroNotchState_t *state) {
|
|||
*/
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
//Any initial notch Q is valid sice it will be updated immediately after
|
||||
biquadFilterInit(&state->filters[axis][0], DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, state->looptime, 1.0f, FILTER_NOTCH);
|
||||
biquadFilterInit(&state->filters[axis][1], DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, state->looptime, 1.0f, FILTER_NOTCH);
|
||||
biquadFilterInit(&state->filters[axis][2], DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, state->looptime, 1.0f, FILTER_NOTCH);
|
||||
for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
|
||||
biquadFilterInit(&state->filters[axis][i], DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, state->looptime, 1.0f, FILTER_NOTCH);
|
||||
state->filtersApplyFn[axis][i] = (filterApplyFnPtr)biquadFilterApplyDF1;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
state->filtersApplyFn = (filterApplyFnPtr)biquadFilterApplyDF1;
|
||||
}
|
||||
}
|
||||
|
||||
void dynamicGyroNotchFiltersUpdate(dynamicGyroNotchState_t *state, int axis, uint16_t frequency) {
|
||||
void dynamicGyroNotchFiltersUpdate(dynamicGyroNotchState_t *state, int axis, float frequency[]) {
|
||||
|
||||
state->frequency[axis] = frequency;
|
||||
|
||||
DEBUG_SET(DEBUG_DYNAMIC_FILTER_FREQUENCY, axis, frequency);
|
||||
|
||||
if (state->enabled) {
|
||||
biquadFilterUpdate(&state->filters[0][axis], frequency, state->looptime, state->dynNotchQ, FILTER_NOTCH);
|
||||
biquadFilterUpdate(&state->filters[1][axis], frequency, state->looptime, state->dynNotchQ, FILTER_NOTCH);
|
||||
biquadFilterUpdate(&state->filters[2][axis], frequency, state->looptime, state->dynNotchQ, FILTER_NOTCH);
|
||||
if (axis == FD_ROLL) {
|
||||
for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
|
||||
DEBUG_SET(DEBUG_DYNAMIC_FILTER_FREQUENCY, i, frequency[i]);
|
||||
}
|
||||
}
|
||||
|
||||
if (state->enabled) {
|
||||
for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
|
||||
// Filter update happens only if peak was detected
|
||||
if (frequency[i] > 0.0f) {
|
||||
biquadFilterUpdate(&state->filters[axis][i], frequency[i], state->looptime, state->dynNotchQ, FILTER_NOTCH);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
float dynamicGyroNotchFiltersApply(dynamicGyroNotchState_t *state, int axis, float input) {
|
||||
|
@ -75,9 +87,9 @@ float dynamicGyroNotchFiltersApply(dynamicGyroNotchState_t *state, int axis, flo
|
|||
* We always apply all filters. If a filter dimension is disabled, one of
|
||||
* the function pointers will be a null apply function
|
||||
*/
|
||||
output = state->filtersApplyFn((filter_t *)&state->filters[axis][0], output);
|
||||
output = state->filtersApplyFn((filter_t *)&state->filters[axis][1], output);
|
||||
output = state->filtersApplyFn((filter_t *)&state->filters[axis][2], output);
|
||||
for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
|
||||
output = state->filtersApplyFn[axis][i]((filter_t *)&state->filters[axis][i], output);
|
||||
}
|
||||
|
||||
return output;
|
||||
}
|
||||
|
|
|
@ -27,23 +27,22 @@
|
|||
#include <stdint.h>
|
||||
#include "common/axis.h"
|
||||
#include "common/filter.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#define DYNAMIC_NOTCH_DEFAULT_CENTER_HZ 350
|
||||
|
||||
typedef struct dynamicGyroNotchState_s {
|
||||
uint16_t frequency[XYZ_AXIS_COUNT];
|
||||
// uint16_t frequency[XYZ_AXIS_COUNT];
|
||||
float dynNotchQ;
|
||||
float dynNotch1Ctr;
|
||||
float dynNotch2Ctr;
|
||||
uint32_t looptime;
|
||||
uint8_t enabled;
|
||||
/*
|
||||
* Dynamic gyro filter can be 3x1, 3x2 or 3x3 depending on filter type
|
||||
*/
|
||||
biquadFilter_t filters[XYZ_AXIS_COUNT][XYZ_AXIS_COUNT];
|
||||
filterApplyFnPtr filtersApplyFn;
|
||||
|
||||
biquadFilter_t filters[XYZ_AXIS_COUNT][DYN_NOTCH_PEAK_COUNT];
|
||||
filterApplyFnPtr filtersApplyFn[XYZ_AXIS_COUNT][DYN_NOTCH_PEAK_COUNT];
|
||||
} dynamicGyroNotchState_t;
|
||||
|
||||
void dynamicGyroNotchFiltersInit(dynamicGyroNotchState_t *state);
|
||||
void dynamicGyroNotchFiltersUpdate(dynamicGyroNotchState_t *state, int axis, uint16_t frequency);
|
||||
void dynamicGyroNotchFiltersUpdate(dynamicGyroNotchState_t *state, int axis, float frequency[]);
|
||||
float dynamicGyroNotchFiltersApply(dynamicGyroNotchState_t *state, int axis, float input);
|
||||
|
|
|
@ -87,9 +87,6 @@ PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
|
|||
typedef enum {
|
||||
FAILSAFE_CHANNEL_HOLD, // Hold last known good value
|
||||
FAILSAFE_CHANNEL_NEUTRAL, // RPY = zero, THR = zero
|
||||
#if !defined(USE_NAV)
|
||||
FAILSAFE_CHANNEL_AUTO, // Defined by failsafe configured values
|
||||
#endif
|
||||
} failsafeChannelBehavior_e;
|
||||
|
||||
typedef struct {
|
||||
|
@ -101,7 +98,6 @@ typedef struct {
|
|||
static const failsafeProcedureLogic_t failsafeProcedureLogic[] = {
|
||||
[FAILSAFE_PROCEDURE_AUTO_LANDING] = {
|
||||
.forceAngleMode = true,
|
||||
#if defined(USE_NAV)
|
||||
.bypassNavigation = false,
|
||||
.channelBehavior = {
|
||||
FAILSAFE_CHANNEL_NEUTRAL, // ROLL
|
||||
|
@ -109,15 +105,6 @@ static const failsafeProcedureLogic_t failsafeProcedureLogic[] = {
|
|||
FAILSAFE_CHANNEL_NEUTRAL, // YAW
|
||||
FAILSAFE_CHANNEL_HOLD // THROTTLE
|
||||
}
|
||||
#else
|
||||
.bypassNavigation = true,
|
||||
.channelBehavior = {
|
||||
FAILSAFE_CHANNEL_AUTO, // ROLL
|
||||
FAILSAFE_CHANNEL_AUTO, // PITCH
|
||||
FAILSAFE_CHANNEL_AUTO, // YAW
|
||||
FAILSAFE_CHANNEL_AUTO // THROTTLE
|
||||
}
|
||||
#endif
|
||||
},
|
||||
|
||||
[FAILSAFE_PROCEDURE_DROP_IT] = {
|
||||
|
@ -184,7 +171,6 @@ void failsafeInit(void)
|
|||
failsafeState.suspended = false;
|
||||
}
|
||||
|
||||
#ifdef USE_NAV
|
||||
bool failsafeBypassNavigation(void)
|
||||
{
|
||||
return failsafeState.active &&
|
||||
|
@ -197,7 +183,6 @@ bool failsafeMayRequireNavigationMode(void)
|
|||
return (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_RTH) ||
|
||||
(failsafeConfig()->failsafe_min_distance_procedure == FAILSAFE_PROCEDURE_RTH);
|
||||
}
|
||||
#endif
|
||||
|
||||
failsafePhase_e failsafePhase(void)
|
||||
{
|
||||
|
@ -228,16 +213,10 @@ bool failsafeRequiresAngleMode(void)
|
|||
|
||||
bool failsafeRequiresMotorStop(void)
|
||||
{
|
||||
#if defined(USE_NAV)
|
||||
return failsafeState.active &&
|
||||
failsafeState.activeProcedure == FAILSAFE_PROCEDURE_AUTO_LANDING &&
|
||||
posControl.flags.estAltStatus < EST_USABLE &&
|
||||
currentBatteryProfile->failsafe_throttle < getThrottleIdleValue();
|
||||
#else
|
||||
return failsafeState.active &&
|
||||
failsafeState.activeProcedure == FAILSAFE_PROCEDURE_AUTO_LANDING &&
|
||||
currentBatteryProfile->failsafe_throttle < getThrottleIdleValue();
|
||||
#endif
|
||||
}
|
||||
|
||||
void failsafeStartMonitoring(void)
|
||||
|
@ -277,22 +256,6 @@ void failsafeUpdateRcCommandValues(void)
|
|||
|
||||
void failsafeApplyControlInput(void)
|
||||
{
|
||||
#if !defined(USE_NAV)
|
||||
// Prepare FAILSAFE_CHANNEL_AUTO values for rcCommand
|
||||
int16_t autoRcCommand[4];
|
||||
if (STATE(FIXED_WING_LEGACY)) {
|
||||
autoRcCommand[ROLL] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_roll_angle, pidProfile()->max_angle_inclination[FD_ROLL]);
|
||||
autoRcCommand[PITCH] = pidAngleToRcCommand(failsafeConfig()->failsafe_fw_pitch_angle, pidProfile()->max_angle_inclination[FD_PITCH]);
|
||||
autoRcCommand[YAW] = -pidRateToRcCommand(failsafeConfig()->failsafe_fw_yaw_rate, currentControlRateProfile->stabilized.rates[FD_YAW]);
|
||||
autoRcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle;
|
||||
}
|
||||
else {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
autoRcCommand[i] = 0;
|
||||
}
|
||||
autoRcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle;
|
||||
}
|
||||
#endif
|
||||
// Apply channel values
|
||||
for (int idx = 0; idx < 4; idx++) {
|
||||
switch (failsafeProcedureLogic[failsafeState.activeProcedure].channelBehavior[idx]) {
|
||||
|
@ -313,11 +276,6 @@ void failsafeApplyControlInput(void)
|
|||
break;
|
||||
}
|
||||
break;
|
||||
#if !defined(USE_NAV)
|
||||
case FAILSAFE_CHANNEL_AUTO:
|
||||
rcCommand[idx] = autoRcCommand[idx];
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -461,9 +419,7 @@ void failsafeUpdateState(void)
|
|||
case FAILSAFE_PROCEDURE_AUTO_LANDING:
|
||||
// Use Emergency Landing if Nav defined (otherwise stabilize and set Throttle to specified level).
|
||||
failsafeActivate(FAILSAFE_LANDING);
|
||||
#if defined(USE_NAV)
|
||||
activateForcedEmergLanding();
|
||||
#endif
|
||||
break;
|
||||
|
||||
case FAILSAFE_PROCEDURE_DROP_IT:
|
||||
|
@ -472,13 +428,11 @@ void failsafeUpdateState(void)
|
|||
failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_3_SECONDS; // require 3 seconds of valid rxData
|
||||
break;
|
||||
|
||||
#if defined(USE_NAV)
|
||||
case FAILSAFE_PROCEDURE_RTH:
|
||||
// Proceed to handling & monitoring RTH navigation
|
||||
failsafeActivate(FAILSAFE_RETURN_TO_HOME);
|
||||
activateForcedRTH();
|
||||
break;
|
||||
#endif
|
||||
case FAILSAFE_PROCEDURE_NONE:
|
||||
default:
|
||||
// Do nothing procedure
|
||||
|
@ -497,7 +451,6 @@ void failsafeUpdateState(void)
|
|||
}
|
||||
break;
|
||||
|
||||
#if defined(USE_NAV)
|
||||
case FAILSAFE_RETURN_TO_HOME:
|
||||
if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) {
|
||||
abortForcedRTH();
|
||||
|
@ -533,20 +486,16 @@ void failsafeUpdateState(void)
|
|||
}
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
case FAILSAFE_LANDING:
|
||||
if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) {
|
||||
#if defined(USE_NAV)
|
||||
abortForcedEmergLanding();
|
||||
#endif
|
||||
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
|
||||
reprocessState = true;
|
||||
} else {
|
||||
if (armed) {
|
||||
beeperMode = BEEPER_RX_LOST_LANDING;
|
||||
}
|
||||
#if defined(USE_NAV)
|
||||
bool emergLanded = false;
|
||||
switch (getStateOfForcedEmergLanding()) {
|
||||
case EMERG_LAND_IN_PROGRESS:
|
||||
|
@ -566,9 +515,6 @@ void failsafeUpdateState(void)
|
|||
break;
|
||||
}
|
||||
if (emergLanded || failsafeShouldHaveCausedLandingByNow() || !armed) {
|
||||
#else
|
||||
if (failsafeShouldHaveCausedLandingByNow() || !armed) {
|
||||
#endif
|
||||
failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_30_SECONDS; // require 30 seconds of valid rxData
|
||||
failsafeState.phase = FAILSAFE_LANDED;
|
||||
reprocessState = true;
|
||||
|
|
|
@ -70,7 +70,6 @@ typedef enum {
|
|||
* Note that this phase is only used when
|
||||
* failsafe_procedure = NONE.
|
||||
*/
|
||||
#if defined(USE_NAV)
|
||||
FAILSAFE_RETURN_TO_HOME,
|
||||
/* Failsafe is executing RTH. This phase is the first one
|
||||
* enabled when failsafe_procedure = RTH if an RTH is
|
||||
|
@ -79,10 +78,10 @@ typedef enum {
|
|||
* sensors are not working at the moment). If RTH can't
|
||||
* be started, this phase will transition to FAILSAFE_LANDING.
|
||||
*/
|
||||
#endif
|
||||
FAILSAFE_LANDING,
|
||||
/* Pergorms NAV Emergency Landing if USE_NAV defined.
|
||||
* Otherwise Failsafe mode performs a simplified landing procedure.
|
||||
/* Performs NAV Emergency Landing using controlled descent rate if
|
||||
* altitude sensors available.
|
||||
* Otherwise Emergency Landing performs a simplified landing procedure.
|
||||
* This is done by setting throttle and roll/pitch/yaw controls
|
||||
* to a pre-configured values that will allow aircraft
|
||||
* to reach ground in somewhat safe "controlled crash" way.
|
||||
|
@ -123,7 +122,6 @@ typedef enum {
|
|||
FAILSAFE_PROCEDURE_NONE
|
||||
} failsafeProcedure_e;
|
||||
|
||||
#if defined(USE_NAV)
|
||||
typedef enum {
|
||||
RTH_IDLE = 0, // RTH is waiting
|
||||
RTH_IN_PROGRESS, // RTH is active
|
||||
|
@ -135,7 +133,6 @@ typedef enum {
|
|||
EMERG_LAND_IN_PROGRESS, // Emergency landing is active
|
||||
EMERG_LAND_HAS_LANDED // Emergency landing is active and has landed.
|
||||
} emergLandState_e;
|
||||
#endif
|
||||
|
||||
typedef struct failsafeState_s {
|
||||
int16_t events;
|
||||
|
|
|
@ -61,7 +61,7 @@ enum {
|
|||
// NB FFT_WINDOW_SIZE is set to 32 in gyroanalyse.h
|
||||
#define FFT_BIN_COUNT (FFT_WINDOW_SIZE / 2)
|
||||
// smoothing frequency for FFT centre frequency
|
||||
#define DYN_NOTCH_SMOOTH_FREQ_HZ 50
|
||||
#define DYN_NOTCH_SMOOTH_FREQ_HZ 25
|
||||
|
||||
/*
|
||||
* Slow down gyro sample acquisition. This lowers the max frequency but increases the resolution.
|
||||
|
@ -93,11 +93,12 @@ void gyroDataAnalyseStateInit(
|
|||
const uint32_t filterUpdateUs = targetLooptimeUs * STEP_COUNT * XYZ_AXIS_COUNT;
|
||||
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
// any init value
|
||||
state->centerFreq[axis] = state->maxFrequency;
|
||||
state->prevCenterFreq[axis] = state->maxFrequency;
|
||||
|
||||
for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
|
||||
state->centerFrequency[axis][i] = state->maxFrequency;
|
||||
pt1FilterInit(&state->detectedFrequencyFilter[axis][i], DYN_NOTCH_SMOOTH_FREQ_HZ, filterUpdateUs * 1e-6f);
|
||||
}
|
||||
|
||||
biquadFilterInitLPF(&state->detectedFrequencyFilter[axis], DYN_NOTCH_SMOOTH_FREQ_HZ, filterUpdateUs);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -135,18 +136,6 @@ void stage_rfft_f32(arm_rfft_fast_instance_f32 *S, float32_t *p, float32_t *pOut
|
|||
void arm_cfft_radix8by4_f32(arm_cfft_instance_f32 *S, float32_t *p1);
|
||||
void arm_bitreversal_32(uint32_t *pSrc, const uint16_t bitRevLen, const uint16_t *pBitRevTable);
|
||||
|
||||
static uint8_t findPeakBinIndex(gyroAnalyseState_t *state) {
|
||||
uint8_t peakBinIndex = state->fftStartBin;
|
||||
float peakValue = 0;
|
||||
for (int i = state->fftStartBin; i < FFT_BIN_COUNT; i++) {
|
||||
if (state->fftData[i] > peakValue) {
|
||||
peakValue = state->fftData[i];
|
||||
peakBinIndex = i;
|
||||
}
|
||||
}
|
||||
return peakBinIndex;
|
||||
}
|
||||
|
||||
static float computeParabolaMean(gyroAnalyseState_t *state, uint8_t peakBinIndex) {
|
||||
float preciseBin = peakBinIndex;
|
||||
|
||||
|
@ -190,38 +179,78 @@ static NOINLINE void gyroDataAnalyseUpdate(gyroAnalyseState_t *state)
|
|||
// 8us
|
||||
arm_cmplx_mag_f32(state->rfftData, state->fftData, FFT_BIN_COUNT);
|
||||
|
||||
//Find peak frequency
|
||||
uint8_t peakBin = findPeakBinIndex(state);
|
||||
//Zero the data structure
|
||||
for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
|
||||
state->peaks[i].bin = 0;
|
||||
state->peaks[i].value = 0.0f;
|
||||
}
|
||||
|
||||
// Failsafe to ensure the last bin is not a peak bin
|
||||
peakBin = constrain(peakBin, state->fftStartBin, FFT_BIN_COUNT - 1);
|
||||
// Find peaks
|
||||
for (int bin = (state->fftStartBin + 1); bin < FFT_BIN_COUNT - 1; bin++) {
|
||||
/*
|
||||
* Peak is defined if the current bin is greater than the previous bin and the next bin
|
||||
*/
|
||||
if (
|
||||
state->fftData[bin] > state->fftData[bin - 1] &&
|
||||
state->fftData[bin] > state->fftData[bin + 1]
|
||||
) {
|
||||
/*
|
||||
* We are only interested in N biggest peaks
|
||||
* Check previously found peaks and update the structure if necessary
|
||||
*/
|
||||
for (int p = 0; p < DYN_NOTCH_PEAK_COUNT; p++) {
|
||||
if (state->fftData[bin] > state->peaks[p].value) {
|
||||
for (int k = DYN_NOTCH_PEAK_COUNT - 1; k > p; k--) {
|
||||
state->peaks[k] = state->peaks[k - 1];
|
||||
}
|
||||
state->peaks[p].bin = bin;
|
||||
state->peaks[p].value = state->fftData[bin];
|
||||
break;
|
||||
}
|
||||
}
|
||||
bin++; // If bin is peak, next bin can't be peak => jump it
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Calculate center frequency using the parabola method
|
||||
*/
|
||||
float preciseBin = computeParabolaMean(state, peakBin);
|
||||
float peakFrequency = preciseBin * state->fftResolution;
|
||||
// Sort N biggest peaks in ascending bin order (example: 3, 8, 25, 0, 0, ..., 0)
|
||||
for (int p = DYN_NOTCH_PEAK_COUNT - 1; p > 0; p--) {
|
||||
for (int k = 0; k < p; k++) {
|
||||
// Swap peaks but ignore swapping void peaks (bin = 0). This leaves
|
||||
// void peaks at the end of peaks array without moving them
|
||||
if (state->peaks[k].bin > state->peaks[k + 1].bin && state->peaks[k + 1].bin != 0) {
|
||||
peak_t temp = state->peaks[k];
|
||||
state->peaks[k] = state->peaks[k + 1];
|
||||
state->peaks[k + 1] = temp;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
peakFrequency = biquadFilterApply(&state->detectedFrequencyFilter[state->updateAxis], peakFrequency);
|
||||
peakFrequency = constrainf(peakFrequency, state->minFrequency, state->maxFrequency);
|
||||
|
||||
state->prevCenterFreq[state->updateAxis] = state->centerFreq[state->updateAxis];
|
||||
state->centerFreq[state->updateAxis] = peakFrequency;
|
||||
break;
|
||||
}
|
||||
case STEP_UPDATE_FILTERS_AND_HANNING:
|
||||
{
|
||||
// 7us
|
||||
// calculate cutoffFreq and notch Q, update notch filter =1.8+((A2-150)*0.004)
|
||||
if (state->prevCenterFreq[state->updateAxis] != state->centerFreq[state->updateAxis]) {
|
||||
/*
|
||||
* Filters will be updated inside dynamicGyroNotchFiltersUpdate()
|
||||
*/
|
||||
state->filterUpdateExecute = true;
|
||||
state->filterUpdateAxis = state->updateAxis;
|
||||
state->filterUpdateFrequency = state->centerFreq[state->updateAxis];
|
||||
|
||||
/*
|
||||
* Update frequencies
|
||||
*/
|
||||
for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) {
|
||||
|
||||
if (state->peaks[i].bin > 0) {
|
||||
const int bin = constrain(state->peaks[i].bin, state->fftStartBin, FFT_BIN_COUNT - 1);
|
||||
float frequency = computeParabolaMean(state, bin) * state->fftResolution;
|
||||
|
||||
state->centerFrequency[state->updateAxis][i] = pt1FilterApply(&state->detectedFrequencyFilter[state->updateAxis][i], frequency);
|
||||
} else {
|
||||
state->centerFrequency[state->updateAxis][i] = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Filters will be updated inside dynamicGyroNotchFiltersUpdate()
|
||||
*/
|
||||
state->filterUpdateExecute = true;
|
||||
state->filterUpdateAxis = state->updateAxis;
|
||||
|
||||
//Switch to the next axis
|
||||
state->updateAxis = (state->updateAxis + 1) % XYZ_AXIS_COUNT;
|
||||
|
||||
|
|
|
@ -31,6 +31,11 @@
|
|||
*/
|
||||
#define FFT_WINDOW_SIZE 64
|
||||
|
||||
typedef struct peak_s {
|
||||
int bin;
|
||||
float value;
|
||||
} peak_t;
|
||||
|
||||
typedef struct gyroAnalyseState_s {
|
||||
// accumulator for oversampled data => no aliasing and less noise
|
||||
float currentSample[XYZ_AXIS_COUNT];
|
||||
|
@ -40,7 +45,6 @@ typedef struct gyroAnalyseState_s {
|
|||
float downsampledGyroData[XYZ_AXIS_COUNT][FFT_WINDOW_SIZE];
|
||||
|
||||
// update state machine step information
|
||||
uint8_t updateTicks;
|
||||
uint8_t updateStep;
|
||||
uint8_t updateAxis;
|
||||
|
||||
|
@ -48,12 +52,15 @@ typedef struct gyroAnalyseState_s {
|
|||
float fftData[FFT_WINDOW_SIZE];
|
||||
float rfftData[FFT_WINDOW_SIZE];
|
||||
|
||||
biquadFilter_t detectedFrequencyFilter[XYZ_AXIS_COUNT];
|
||||
uint16_t centerFreq[XYZ_AXIS_COUNT];
|
||||
uint16_t prevCenterFreq[XYZ_AXIS_COUNT];
|
||||
pt1Filter_t detectedFrequencyFilter[XYZ_AXIS_COUNT][DYN_NOTCH_PEAK_COUNT];
|
||||
float centerFrequency[XYZ_AXIS_COUNT][DYN_NOTCH_PEAK_COUNT];
|
||||
|
||||
peak_t peaks[DYN_NOTCH_PEAK_COUNT];
|
||||
|
||||
bool filterUpdateExecute;
|
||||
uint8_t filterUpdateAxis;
|
||||
uint16_t filterUpdateFrequency;
|
||||
|
||||
uint16_t fftSamplingRateHz;
|
||||
uint8_t fftStartBin;
|
||||
float fftResolution;
|
||||
|
|
|
@ -739,7 +739,7 @@ static float dTermProcess(pidState_t *pidState, float dT) {
|
|||
newDTerm = 0;
|
||||
} else {
|
||||
float delta = pidState->previousRateGyro - pidState->gyroRate;
|
||||
|
||||
|
||||
delta = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, delta);
|
||||
delta = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, delta);
|
||||
|
||||
|
@ -892,7 +892,6 @@ static uint8_t getHeadingHoldState(void)
|
|||
return HEADING_HOLD_DISABLED;
|
||||
}
|
||||
|
||||
#if defined(USE_NAV)
|
||||
int navHeadingState = navigationGetHeadingControlState();
|
||||
// NAV will prevent MAG_MODE from activating, but require heading control
|
||||
if (navHeadingState != NAV_HEADING_CONTROL_NONE) {
|
||||
|
@ -901,9 +900,7 @@ static uint8_t getHeadingHoldState(void)
|
|||
return HEADING_HOLD_ENABLED;
|
||||
}
|
||||
}
|
||||
else
|
||||
#endif
|
||||
if (ABS(rcCommand[YAW]) == 0 && FLIGHT_MODE(HEADING_MODE)) {
|
||||
else if (ABS(rcCommand[YAW]) == 0 && FLIGHT_MODE(HEADING_MODE)) {
|
||||
return HEADING_HOLD_ENABLED;
|
||||
} else {
|
||||
return HEADING_HOLD_UPDATE_HEADING;
|
||||
|
@ -1209,7 +1206,7 @@ void pidInit(void)
|
|||
for (uint8_t axis = FD_ROLL; axis <= FD_YAW; axis++) {
|
||||
|
||||
#ifdef USE_D_BOOST
|
||||
// Rate * 10 * 10. First 10 is to convert stick to DPS. Second 10 is to convert target to acceleration.
|
||||
// Rate * 10 * 10. First 10 is to convert stick to DPS. Second 10 is to convert target to acceleration.
|
||||
// We assume, max acceleration is when pilot deflects the stick fully in 100ms
|
||||
pidState[axis].dBoostTargetAcceleration = currentControlRateProfile->stabilized.rates[axis] * 10 * 10;
|
||||
#endif
|
||||
|
|
|
@ -264,11 +264,9 @@ static void updateFailsafeStatus(void)
|
|||
case FAILSAFE_RX_LOSS_IDLE:
|
||||
failsafeIndicator = 'I';
|
||||
break;
|
||||
#if defined(USE_NAV)
|
||||
case FAILSAFE_RETURN_TO_HOME:
|
||||
failsafeIndicator = 'H';
|
||||
break;
|
||||
#endif
|
||||
case FAILSAFE_LANDING:
|
||||
failsafeIndicator = 'l';
|
||||
break;
|
||||
|
|
|
@ -485,11 +485,11 @@ static void applyLedFixedLayers(void)
|
|||
}
|
||||
}
|
||||
|
||||
static void applyLedHsv(uint32_t mask, const hsvColor_t *color)
|
||||
static void applyLedHsv(uint32_t mask, uint32_t ledOperation, const hsvColor_t *color)
|
||||
{
|
||||
for (int ledIndex = 0; ledIndex < ledCounts.count; ledIndex++) {
|
||||
const ledConfig_t *ledConfig = &ledStripConfig()->ledConfigs[ledIndex];
|
||||
if ((*ledConfig & mask) == mask)
|
||||
if ((*ledConfig & mask) == ledOperation)
|
||||
setLedHsv(ledIndex, color);
|
||||
}
|
||||
}
|
||||
|
@ -548,7 +548,7 @@ static void applyLedWarningLayer(bool updateNow, timeUs_t *timer)
|
|||
}
|
||||
}
|
||||
if (warningColor)
|
||||
applyLedHsv(LED_MOV_OVERLAY(LED_FLAG_OVERLAY(LED_OVERLAY_WARNING)), warningColor);
|
||||
applyLedHsv(LED_OVERLAY_MASK, LED_MOV_OVERLAY(LED_FLAG_OVERLAY(LED_OVERLAY_WARNING)), warningColor);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -582,7 +582,7 @@ static void applyLedBatteryLayer(bool updateNow, timeUs_t *timer)
|
|||
|
||||
if (!flash) {
|
||||
const hsvColor_t *bgc = getSC(LED_SCOLOR_BACKGROUND);
|
||||
applyLedHsv(LED_MOV_FUNCTION(LED_FUNCTION_BATTERY), bgc);
|
||||
applyLedHsv(LED_FUNCTION_MASK, LED_MOV_FUNCTION(LED_FUNCTION_BATTERY), bgc);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -612,7 +612,7 @@ static void applyLedRssiLayer(bool updateNow, timeUs_t *timer)
|
|||
|
||||
if (!flash) {
|
||||
const hsvColor_t *bgc = getSC(LED_SCOLOR_BACKGROUND);
|
||||
applyLedHsv(LED_MOV_FUNCTION(LED_FUNCTION_RSSI), bgc);
|
||||
applyLedHsv(LED_FUNCTION_MASK, LED_MOV_FUNCTION(LED_FUNCTION_RSSI), bgc);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -649,7 +649,7 @@ static void applyLedGpsLayer(bool updateNow, timeUs_t *timer)
|
|||
}
|
||||
}
|
||||
|
||||
applyLedHsv(LED_MOV_FUNCTION(LED_FUNCTION_GPS), gpsColor);
|
||||
applyLedHsv(LED_FUNCTION_MASK, LED_MOV_FUNCTION(LED_FUNCTION_GPS), gpsColor);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -196,7 +196,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, 4);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 5);
|
||||
PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0);
|
||||
|
||||
static int digitCount(int32_t value)
|
||||
|
@ -757,7 +757,6 @@ static const char * osdArmingDisabledReasonMessage(void)
|
|||
case ARMING_DISABLED_SYSTEM_OVERLOADED:
|
||||
return OSD_MESSAGE_STR(OSD_MSG_SYS_OVERLOADED);
|
||||
case ARMING_DISABLED_NAVIGATION_UNSAFE:
|
||||
#if defined(USE_NAV)
|
||||
// Check the exact reason
|
||||
switch (navigationIsBlockingArming(NULL)) {
|
||||
char buf[6];
|
||||
|
@ -774,7 +773,6 @@ static const char * osdArmingDisabledReasonMessage(void)
|
|||
case NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR:
|
||||
return OSD_MESSAGE_STR(OSD_MSG_JUMP_WP_MISCONFIG);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case ARMING_DISABLED_COMPASS_NOT_CALIBRATED:
|
||||
return OSD_MESSAGE_STR(OSD_MSG_MAG_NOT_CAL);
|
||||
|
@ -850,11 +848,9 @@ static const char * osdFailsafePhaseMessage(void)
|
|||
{
|
||||
// See failsafe.h for each phase explanation
|
||||
switch (failsafePhase()) {
|
||||
#ifdef USE_NAV
|
||||
case FAILSAFE_RETURN_TO_HOME:
|
||||
// XXX: Keep this in sync with OSD_FLYMODE.
|
||||
return OSD_MESSAGE_STR(OSD_MSG_RTH_FS);
|
||||
#endif
|
||||
case FAILSAFE_LANDING:
|
||||
// This should be considered an emergengy landing
|
||||
return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING_FS);
|
||||
|
@ -1074,24 +1070,12 @@ static void osdFormatRpm(char *buff, uint32_t rpm)
|
|||
|
||||
int32_t osdGetAltitude(void)
|
||||
{
|
||||
#if defined(USE_NAV)
|
||||
return getEstimatedActualPosition(Z);
|
||||
#elif defined(USE_BARO)
|
||||
return baro.alt;
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
static inline int32_t osdGetAltitudeMsl(void)
|
||||
{
|
||||
#if defined(USE_NAV)
|
||||
return getEstimatedActualPosition(Z)+GPS_home.alt;
|
||||
#elif defined(USE_BARO)
|
||||
return baro.alt+GPS_home.alt;
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
static bool osdIsHeadingValid(void)
|
||||
|
@ -1994,7 +1978,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
|
||||
case OSD_THROTTLE_POS:
|
||||
{
|
||||
osdFormatThrottlePosition(buff, false, NULL);
|
||||
osdFormatThrottlePosition(buff, false, &elemAttr);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -2155,13 +2139,6 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (osdConfig()->hud_radar_nearest > 0) { // Display extra datas for 1 POI closer than a set distance
|
||||
int poi_id = radarGetNearestPOI();
|
||||
if (poi_id >= 0 && radar_pois[poi_id].distance <= osdConfig()->hud_radar_nearest) {
|
||||
osdHudDrawExtras(poi_id);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// -------- POI : Next waypoints from navigation
|
||||
|
@ -2982,7 +2959,6 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CTL S", 0, navConfig()->fw.control_smoothness, 1, 0, ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS);
|
||||
return true;
|
||||
|
||||
#if defined(USE_NAV)
|
||||
case OSD_MISSION:
|
||||
{
|
||||
if (IS_RC_MODE_ACTIVE(BOXPLANWPMISSION)) {
|
||||
|
@ -3003,7 +2979,9 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
tfp_sprintf(buff, "%s>%2uWP", buf, posControl.wpPlannerActiveWPIndex);
|
||||
} else if (posControl.wpPlannerActiveWPIndex){
|
||||
tfp_sprintf(buff, "PLAN>%2uWP", posControl.waypointCount); // mission planner mision active
|
||||
} else {
|
||||
}
|
||||
#ifdef USE_MULTI_MISSION
|
||||
else {
|
||||
if (ARMING_FLAG(ARMED)){
|
||||
// Limit field size when Armed, only show selected mission
|
||||
tfp_sprintf(buff, "M%u ", posControl.loadedMultiMissionIndex);
|
||||
|
@ -3023,10 +3001,10 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
tfp_sprintf(buff, "WP CNT>%2u", posControl.waypointCount);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
displayWrite(osdDisplayPort, elemPosX, elemPosY, buff);
|
||||
return true;
|
||||
}
|
||||
#endif // USE_NAV
|
||||
|
||||
#ifdef USE_POWER_LIMITS
|
||||
case OSD_PLIMIT_REMAINING_BURST_TIME:
|
||||
|
@ -3189,6 +3167,8 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
|
|||
.crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT,
|
||||
.link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT,
|
||||
.rssi_dbm_alarm = SETTING_OSD_RSSI_DBM_ALARM_DEFAULT,
|
||||
.rssi_dbm_max = SETTING_OSD_RSSI_DBM_MAX_DEFAULT,
|
||||
.rssi_dbm_min = SETTING_OSD_RSSI_DBM_MIN_DEFAULT,
|
||||
#endif
|
||||
#ifdef USE_TEMPERATURE_SENSOR
|
||||
.temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT,
|
||||
|
@ -3216,7 +3196,6 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
|
|||
.hud_radar_disp = SETTING_OSD_HUD_RADAR_DISP_DEFAULT,
|
||||
.hud_radar_range_min = SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT,
|
||||
.hud_radar_range_max = SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT,
|
||||
.hud_radar_nearest = SETTING_OSD_HUD_RADAR_NEAREST_DEFAULT,
|
||||
.hud_wp_disp = SETTING_OSD_HUD_WP_DISP_DEFAULT,
|
||||
.left_sidebar_scroll = SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT,
|
||||
.right_sidebar_scroll = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT,
|
||||
|
@ -3875,12 +3854,14 @@ static void osdShowArmed(void)
|
|||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig() -> name)) / 2, y, craftNameBuf );
|
||||
y += 1;
|
||||
}
|
||||
#if defined(USE_NAV)
|
||||
if (posControl.waypointListValid && posControl.waypointCount > 0) {
|
||||
#ifdef USE_MULTI_MISSION
|
||||
tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount);
|
||||
displayWrite(osdDisplayPort, 6, y, buf);
|
||||
}
|
||||
#else
|
||||
displayWrite(osdDisplayPort, 7, y, "*MISSION LOADED*");
|
||||
#endif
|
||||
}
|
||||
y += 1;
|
||||
|
||||
#if defined(USE_GPS)
|
||||
|
@ -4273,11 +4254,9 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
|
|||
if (FLIGHT_MODE(SOARING_MODE)) {
|
||||
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_NAV_SOARING);
|
||||
}
|
||||
#if defined(USE_NAV)
|
||||
if (posControl.flags.wpMissionPlannerActive) {
|
||||
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_MISSION_PLANNER);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
} else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) {
|
||||
|
|
|
@ -323,6 +323,8 @@ typedef struct osdConfig_s {
|
|||
int8_t snr_alarm; //CRSF SNR alarm in dB
|
||||
int8_t link_quality_alarm;
|
||||
int16_t rssi_dbm_alarm; // in dBm
|
||||
int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100%
|
||||
int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0%
|
||||
#endif
|
||||
#ifdef USE_BARO
|
||||
int16_t baro_temp_alarm_min;
|
||||
|
@ -356,7 +358,6 @@ typedef struct osdConfig_s {
|
|||
uint8_t hud_radar_disp;
|
||||
uint16_t hud_radar_range_min;
|
||||
uint16_t hud_radar_range_max;
|
||||
uint16_t hud_radar_nearest;
|
||||
uint8_t hud_wp_disp;
|
||||
|
||||
uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e
|
||||
|
|
|
@ -1475,10 +1475,6 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms
|
|||
pidBankMutable()->pid[djiPidIndexMap[i]].D = sbufReadU8(src);
|
||||
}
|
||||
schedulePidGainsUpdate();
|
||||
#if defined(USE_NAV)
|
||||
// This is currently unnecessary, DJI HD doesn't set any NAV PIDs
|
||||
//navigationUsePIDs();
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
reply->result = MSP_RESULT_ERROR;
|
||||
|
|
|
@ -128,6 +128,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu
|
|||
uint8_t center_y;
|
||||
bool poi_is_oos = 0;
|
||||
char buff[3];
|
||||
int altc = 0;
|
||||
|
||||
uint8_t minX = osdConfig()->hud_margin_h + 2;
|
||||
uint8_t maxX = osdGetDisplayPort()->cols - osdConfig()->hud_margin_h - 3;
|
||||
|
@ -176,11 +177,11 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu
|
|||
}
|
||||
|
||||
if (error_x > 0 ) {
|
||||
d = SYM_HUD_ARROWS_R3 - constrain ((180 - error_x) / 45, 0, 2);
|
||||
d = SYM_HUD_ARROWS_R3 - constrain((180 - error_x) / 45, 0, 2);
|
||||
osdHudWrite(poi_x + 2, poi_y, d, 1);
|
||||
}
|
||||
else {
|
||||
d = SYM_HUD_ARROWS_L3 - constrain ((180 + error_x) / 45, 0, 2);
|
||||
d = SYM_HUD_ARROWS_L3 - constrain((180 + error_x) / 45, 0, 2);
|
||||
osdHudWrite(poi_x - 2, poi_y, d, 1);
|
||||
}
|
||||
}
|
||||
|
@ -201,11 +202,18 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu
|
|||
|
||||
// Distance
|
||||
|
||||
if ((osd_unit_e)osdConfig()->units == OSD_UNIT_IMPERIAL) {
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3);
|
||||
if (((millis() / 1000) % 6 == 0) && poiType > 0) { // For Radar and WPs, display the difference in altitude
|
||||
altc = ((osd_unit_e)osdConfig()->units == OSD_UNIT_IMPERIAL) ? constrain(CENTIMETERS_TO_FEET(poiAltitude * 100), -99, 99) : constrain(poiAltitude, -99 , 99);
|
||||
tfp_sprintf(buff, "%3d", altc);
|
||||
buff[0] = (poiAltitude >= 0) ? SYM_VARIO_UP_2A : SYM_VARIO_DOWN_2A;
|
||||
}
|
||||
else {
|
||||
osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3);
|
||||
else { // Display the distance by default
|
||||
if ((osd_unit_e)osdConfig()->units == OSD_UNIT_IMPERIAL) {
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3);
|
||||
}
|
||||
else {
|
||||
osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3);
|
||||
}
|
||||
}
|
||||
|
||||
osdHudWrite(poi_x - 1, poi_y + 1, buff[0], 1);
|
||||
|
@ -325,38 +333,4 @@ void osdHudDrawHoming(uint8_t px, uint8_t py)
|
|||
displayWriteChar(osdGetDisplayPort(), px, py + 1, crh_d);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Draw extra datas for a radar POI
|
||||
*/
|
||||
void osdHudDrawExtras(uint8_t poi_id)
|
||||
{
|
||||
char buftmp[6];
|
||||
|
||||
uint8_t minX = osdConfig()->hud_margin_h + 1;
|
||||
uint8_t maxX = osdGetDisplayPort()->cols - osdConfig()->hud_margin_h - 2;
|
||||
uint8_t lineY = osdGetDisplayPort()->rows - osdConfig()->hud_margin_v - 1;
|
||||
|
||||
displayWriteChar(osdGetDisplayPort(), minX + 1, lineY, 65 + poi_id);
|
||||
displayWriteChar(osdGetDisplayPort(), minX + 2, lineY, SYM_HUD_SIGNAL_0 + radar_pois[poi_id].lq);
|
||||
|
||||
if (radar_pois[poi_id].altitude < 0) {
|
||||
osdFormatAltitudeSymbol(buftmp, -radar_pois[poi_id].altitude * 100);
|
||||
displayWriteChar(osdGetDisplayPort(), minX + 8, lineY, SYM_HUD_ARROWS_D2);
|
||||
}
|
||||
else {
|
||||
osdFormatAltitudeSymbol(buftmp, radar_pois[poi_id].altitude * 100);
|
||||
displayWriteChar(osdGetDisplayPort(), minX + 8, lineY, SYM_HUD_ARROWS_U2);
|
||||
}
|
||||
|
||||
displayWrite(osdGetDisplayPort(), minX + 4, lineY, buftmp);
|
||||
|
||||
osdFormatVelocityStr(buftmp, radar_pois[poi_id].speed, false, false);
|
||||
displayWrite(osdGetDisplayPort(), maxX - 9, lineY, buftmp);
|
||||
|
||||
tfp_sprintf(buftmp, "%3d%c", radar_pois[poi_id].heading, SYM_HEADING);
|
||||
displayWrite(osdGetDisplayPort(), maxX - 4, lineY, buftmp);
|
||||
|
||||
}
|
||||
|
||||
#endif // USE_OSD
|
||||
|
|
|
@ -18,6 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include "drivers/osd_symbols.h"
|
||||
|
||||
typedef struct displayCanvas_s displayCanvas_t;
|
||||
|
||||
|
@ -26,6 +27,4 @@ void osdHudClear(void);
|
|||
void osdHudDrawCrosshair(displayCanvas_t *canvas, uint8_t px, uint8_t py);
|
||||
void osdHudDrawHoming(uint8_t px, uint8_t py);
|
||||
void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitude, uint8_t poiType, uint16_t poiSymbol, int16_t poiP1, int16_t poiP2);
|
||||
void osdHudDrawExtras(uint8_t poi_id);
|
||||
int8_t radarGetNearestPOI(void);
|
||||
|
||||
|
|
|
@ -45,6 +45,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 3);
|
|||
PG_RESET_TEMPLATE(vtxConfig_t, vtxConfig,
|
||||
.halfDuplex = SETTING_VTX_HALFDUPLEX_DEFAULT,
|
||||
.smartAudioEarlyAkkWorkaroundEnable = SETTING_VTX_SMARTAUDIO_EARLY_AKK_WORKAROUND_DEFAULT,
|
||||
.smartAudioAltSoftSerialMethod = SETTING_VTX_SMARTAUDIO_ALTERNATE_SOFTSERIAL_METHOD_DEFAULT,
|
||||
);
|
||||
|
||||
static uint8_t locked = 0;
|
||||
|
|
|
@ -32,6 +32,7 @@ typedef struct vtxConfig_s {
|
|||
vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
|
||||
uint8_t halfDuplex;
|
||||
uint8_t smartAudioEarlyAkkWorkaroundEnable;
|
||||
bool smartAudioAltSoftSerialMethod;
|
||||
} vtxConfig_t;
|
||||
|
||||
PG_DECLARE(vtxConfig_t, vtxConfig);
|
||||
|
|
|
@ -492,9 +492,13 @@ static void saReceiveFramer(uint8_t c)
|
|||
|
||||
static void saSendFrame(uint8_t *buf, int len)
|
||||
{
|
||||
// TBS SA definition requires that the line is low before frame is sent
|
||||
// (for both soft and hard serial). It can be done by sending first 0x00
|
||||
serialWrite(smartAudioSerialPort, 0x00);
|
||||
if ( (vtxConfig()->smartAudioAltSoftSerialMethod &&
|
||||
(smartAudioSerialPort->identifier == SERIAL_PORT_SOFTSERIAL1 || smartAudioSerialPort->identifier == SERIAL_PORT_SOFTSERIAL2))
|
||||
== false) {
|
||||
// TBS SA definition requires that the line is low before frame is sent
|
||||
// (for both soft and hard serial). It can be done by sending first 0x00
|
||||
serialWrite(smartAudioSerialPort, 0x00);
|
||||
}
|
||||
|
||||
for (int i = 0 ; i < len ; i++) {
|
||||
serialWrite(smartAudioSerialPort, buf[i]);
|
||||
|
|
|
@ -39,7 +39,9 @@
|
|||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_modes.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#ifdef USE_MULTI_MISSION
|
||||
#include "fc/cli.h"
|
||||
#endif
|
||||
#include "fc/settings.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
|
@ -88,8 +90,6 @@ PG_REGISTER_ARRAY(navSafeHome_t, MAX_SAFE_HOMES, safeHomeConfig, PG_SAFE_HOME_CO
|
|||
|
||||
#endif
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
// waypoint 254, 255 are special waypoints
|
||||
STATIC_ASSERT(NAV_MAX_WAYPOINTS < 254, NAV_MAX_WAYPOINTS_exceeded_allowable_range);
|
||||
|
||||
|
@ -125,7 +125,9 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
|||
.pos_failure_timeout = SETTING_NAV_POSITION_TIMEOUT_DEFAULT, // 5 sec
|
||||
.waypoint_radius = SETTING_NAV_WP_RADIUS_DEFAULT, // 2m diameter
|
||||
.waypoint_safe_distance = SETTING_NAV_WP_SAFE_DISTANCE_DEFAULT, // centimeters - first waypoint should be closer than this
|
||||
#ifdef USE_MULTI_MISSION
|
||||
.waypoint_multi_mission_index = SETTING_NAV_WP_MULTI_MISSION_INDEX_DEFAULT, // mission index selected from multi mission WP entry
|
||||
#endif
|
||||
.waypoint_load_on_boot = SETTING_NAV_WP_LOAD_ON_BOOT_DEFAULT, // load waypoints automatically during boot
|
||||
.auto_speed = SETTING_NAV_AUTO_SPEED_DEFAULT, // speed in autonomous modes (3 m/s = 10.8 km/h)
|
||||
.max_auto_speed = SETTING_NAV_MAX_AUTO_SPEED_DEFAULT, // max allowed speed autonomous modes
|
||||
|
@ -1642,11 +1644,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_NEXT(navigatio
|
|||
{
|
||||
UNUSED(previousState);
|
||||
|
||||
const bool isLastWaypoint = (posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST) ||
|
||||
(posControl.activeWaypointIndex >= (posControl.waypointCount - 1));
|
||||
|
||||
if (isLastWaypoint) {
|
||||
// Last waypoint reached
|
||||
if (isLastMissionWaypoint()) { // Last waypoint reached
|
||||
return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED;
|
||||
}
|
||||
else {
|
||||
|
@ -2882,9 +2880,11 @@ void resetWaypointList(void)
|
|||
posControl.waypointCount = 0;
|
||||
posControl.waypointListValid = false;
|
||||
posControl.geoWaypointCount = 0;
|
||||
#ifdef USE_MULTI_MISSION
|
||||
posControl.loadedMultiMissionIndex = 0;
|
||||
posControl.loadedMultiMissionStartWP = 0;
|
||||
posControl.loadedMultiMissionWPCount = 0;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2897,7 +2897,7 @@ int getWaypointCount(void)
|
|||
{
|
||||
return posControl.waypointCount;
|
||||
}
|
||||
|
||||
#ifdef USE_MULTI_MISSION
|
||||
void selectMultiMissionIndex(int8_t increment)
|
||||
{
|
||||
if (posControl.multiMissionCount > 1) { // stick selection only active when multi mission loaded
|
||||
|
@ -2934,13 +2934,17 @@ bool checkMissionCount(int8_t waypoint)
|
|||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // multi mission
|
||||
#ifdef NAV_NON_VOLATILE_WAYPOINT_STORAGE
|
||||
bool loadNonVolatileWaypointList(bool clearIfLoaded)
|
||||
{
|
||||
#ifdef USE_MULTI_MISSION
|
||||
/* multi_mission_index 0 only used for non NVM missions - don't load.
|
||||
* Don't load if mission planner WP count > 0 */
|
||||
if (ARMING_FLAG(ARMED) || !navConfig()->general.waypoint_multi_mission_index || posControl.wpPlannerActiveWPIndex) {
|
||||
#else
|
||||
if (ARMING_FLAG(ARMED) || posControl.wpPlannerActiveWPIndex) {
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -2949,7 +2953,7 @@ bool loadNonVolatileWaypointList(bool clearIfLoaded)
|
|||
resetWaypointList();
|
||||
return false;
|
||||
}
|
||||
|
||||
#ifdef USE_MULTI_MISSION
|
||||
/* Reset multi mission index to 1 if exceeds number of available missions */
|
||||
if (navConfig()->general.waypoint_multi_mission_index > posControl.multiMissionCount) {
|
||||
navConfigMutable()->general.waypoint_multi_mission_index = 1;
|
||||
|
@ -2957,10 +2961,10 @@ bool loadNonVolatileWaypointList(bool clearIfLoaded)
|
|||
posControl.multiMissionCount = 0;
|
||||
posControl.loadedMultiMissionWPCount = 0;
|
||||
int8_t loadedMultiMissionGeoWPCount;
|
||||
|
||||
#endif
|
||||
for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) {
|
||||
setWaypoint(i + 1, nonVolatileWaypointList(i));
|
||||
|
||||
#ifdef USE_MULTI_MISSION
|
||||
/* store details of selected mission */
|
||||
if ((posControl.multiMissionCount + 1 == navConfig()->general.waypoint_multi_mission_index)) {
|
||||
// mission start WP
|
||||
|
@ -2988,6 +2992,15 @@ bool loadNonVolatileWaypointList(bool clearIfLoaded)
|
|||
/* Mission sanity check failed - reset the list
|
||||
* Also reset if no selected mission loaded (shouldn't happen) */
|
||||
if (!posControl.waypointListValid || !posControl.loadedMultiMissionWPCount) {
|
||||
#else
|
||||
// check this is the last waypoint
|
||||
if (nonVolatileWaypointList(i)->flag == NAV_WP_FLAG_LAST) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
// Mission sanity check failed - reset the list
|
||||
if (!posControl.waypointListValid) {
|
||||
#endif
|
||||
resetWaypointList();
|
||||
}
|
||||
|
||||
|
@ -3002,8 +3015,9 @@ bool saveNonVolatileWaypointList(void)
|
|||
for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) {
|
||||
getWaypoint(i + 1, nonVolatileWaypointListMutable(i));
|
||||
}
|
||||
|
||||
#ifdef USE_MULTI_MISSION
|
||||
navConfigMutable()->general.waypoint_multi_mission_index = 1; // reset selected mission to 1 when new entries saved
|
||||
#endif
|
||||
saveConfigAndNotify();
|
||||
|
||||
return true;
|
||||
|
@ -3059,37 +3073,21 @@ static void calculateAndSetActiveWaypoint(const navWaypoint_t * waypoint)
|
|||
calculateAndSetActiveWaypointToLocalPosition(&localPos);
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns TRUE if we are in WP mode and executing last waypoint on the list, or in RTH mode, or in PH mode
|
||||
* In RTH mode our only and last waypoint is home
|
||||
* In PH mode our waypoint is hold position */
|
||||
bool isApproachingLastWaypoint(void)
|
||||
/* Checks if active waypoint is last in mission */
|
||||
bool isLastMissionWaypoint(void)
|
||||
{
|
||||
if (navGetStateFlags(posControl.navState) & NAV_AUTO_WP) {
|
||||
if (posControl.waypointCount == 0) {
|
||||
/* No waypoints */
|
||||
return true;
|
||||
}
|
||||
else if ((posControl.activeWaypointIndex == (posControl.waypointCount - 1)) ||
|
||||
(posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST)) {
|
||||
return true;
|
||||
}
|
||||
else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else if (navGetStateFlags(posControl.navState) & NAV_CTL_POS) {
|
||||
// If POS controller is active we are in Poshold or RTH mode - assume last waypoint
|
||||
return true;
|
||||
}
|
||||
else {
|
||||
return false;
|
||||
}
|
||||
return FLIGHT_MODE(NAV_WP_MODE) && (posControl.activeWaypointIndex >= (posControl.waypointCount - 1) ||
|
||||
(posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST));
|
||||
}
|
||||
|
||||
bool isWaypointWait(void)
|
||||
/* Checks if Nav hold position is active */
|
||||
bool isNavHoldPositionActive(void)
|
||||
{
|
||||
return NAV_Status.state == MW_NAV_STATE_HOLD_TIMED;
|
||||
if (FLIGHT_MODE(NAV_WP_MODE)) { // WP mode last WP hold and Timed hold positions
|
||||
return isLastMissionWaypoint() || NAV_Status.state == MW_NAV_STATE_HOLD_TIMED;
|
||||
}
|
||||
// RTH spiral climb and Home positions and POSHOLD position
|
||||
return FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_POSHOLD_MODE);
|
||||
}
|
||||
|
||||
float getActiveWaypointSpeed(void)
|
||||
|
@ -3189,8 +3187,8 @@ void applyWaypointNavigationAndAltitudeHold(void)
|
|||
}
|
||||
|
||||
/* Reset flags */
|
||||
posControl.flags.horizontalPositionDataConsumed = 0;
|
||||
posControl.flags.verticalPositionDataConsumed = 0;
|
||||
posControl.flags.horizontalPositionDataConsumed = false;
|
||||
posControl.flags.verticalPositionDataConsumed = false;
|
||||
|
||||
/* Process controllers */
|
||||
navigationFSMStateFlags_t navStateFlags = navGetStateFlags(posControl.navState);
|
||||
|
@ -3472,7 +3470,11 @@ bool navigationTerrainFollowingEnabled(void)
|
|||
uint32_t distanceToFirstWP(void)
|
||||
{
|
||||
fpVector3_t startingWaypointPos;
|
||||
#ifdef USE_MULTI_MISSION
|
||||
mapWaypointToLocalPosition(&startingWaypointPos, &posControl.waypointList[posControl.loadedMultiMissionStartWP], GEO_ALT_RELATIVE);
|
||||
#else
|
||||
mapWaypointToLocalPosition(&startingWaypointPos, &posControl.waypointList[0], GEO_ALT_RELATIVE);
|
||||
#endif
|
||||
return calculateDistanceToDestination(&startingWaypointPos);
|
||||
}
|
||||
|
||||
|
@ -3519,10 +3521,13 @@ navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass)
|
|||
* Can't jump to immediately adjacent WPs (pointless)
|
||||
* Can't jump beyond WP list
|
||||
* Only jump to geo-referenced WP types
|
||||
*
|
||||
* Only perform check when mission loaded at start of posControl.waypointList
|
||||
*/
|
||||
#ifdef USE_MULTI_MISSION
|
||||
// Only perform check when mission loaded at start of posControl.waypointList
|
||||
if (posControl.waypointCount && !posControl.loadedMultiMissionStartWP) {
|
||||
#else
|
||||
if (posControl.waypointCount) {
|
||||
#endif
|
||||
for (uint8_t wp = 0; wp < posControl.waypointCount; wp++){
|
||||
if (posControl.waypointList[wp].action == NAV_WP_ACTION_JUMP){
|
||||
if((wp == 0) || ((posControl.waypointList[wp].p1 > (wp-2)) && (posControl.waypointList[wp].p1 < (wp+2)) ) || (posControl.waypointList[wp].p1 >= posControl.waypointCount) || (posControl.waypointList[wp].p2 < -1)) {
|
||||
|
@ -3772,16 +3777,17 @@ void navigationInit(void)
|
|||
posControl.flags.estHeadingStatus = EST_NONE;
|
||||
posControl.flags.estAglStatus = EST_NONE;
|
||||
|
||||
posControl.flags.forcedRTHActivated = 0;
|
||||
posControl.flags.forcedRTHActivated = false;
|
||||
posControl.flags.forcedEmergLandingActivated = false;
|
||||
posControl.waypointCount = 0;
|
||||
posControl.activeWaypointIndex = 0;
|
||||
posControl.waypointListValid = false;
|
||||
posControl.wpPlannerActiveWPIndex = 0;
|
||||
posControl.flags.wpMissionPlannerActive = false;
|
||||
#ifdef USE_MULTI_MISSION
|
||||
posControl.multiMissionCount = 0;
|
||||
posControl.loadedMultiMissionStartWP = 0;
|
||||
|
||||
#endif
|
||||
/* Set initial surface invalid */
|
||||
posControl.actualState.surfaceMin = -1.0f;
|
||||
|
||||
|
@ -3802,6 +3808,7 @@ void navigationInit(void)
|
|||
}
|
||||
#if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE)
|
||||
/* configure WP missions at boot */
|
||||
#ifdef USE_MULTI_MISSION
|
||||
for (int8_t i = 0; i < NAV_MAX_WAYPOINTS; i++) { // check number missions in NVM
|
||||
if (checkMissionCount(i)) {
|
||||
break;
|
||||
|
@ -3811,6 +3818,7 @@ void navigationInit(void)
|
|||
if (navConfig()->general.waypoint_multi_mission_index > posControl.multiMissionCount) {
|
||||
navConfigMutable()->general.waypoint_multi_mission_index = 1;
|
||||
}
|
||||
#endif
|
||||
/* load mission on boot */
|
||||
if (navConfig()->general.waypoint_load_on_boot) {
|
||||
loadNonVolatileWaypointList(false);
|
||||
|
@ -3977,70 +3985,3 @@ bool isAdjustingHeading(void) {
|
|||
int32_t getCruiseHeadingAdjustment(void) {
|
||||
return wrap_18000(posControl.cruise.yaw - posControl.cruise.previousYaw);
|
||||
}
|
||||
|
||||
#else // NAV
|
||||
|
||||
#ifdef USE_GPS
|
||||
/* Fallback if navigation is not compiled in - handle GPS home coordinates */
|
||||
static float GPS_scaleLonDown;
|
||||
static float GPS_totalTravelDistance = 0;
|
||||
|
||||
static void GPS_distance_cm_bearing(int32_t currentLat1, int32_t currentLon1, int32_t destinationLat2, int32_t destinationLon2, uint32_t *dist, int32_t *bearing)
|
||||
{
|
||||
const float dLat = destinationLat2 - currentLat1; // difference of latitude in 1/10 000 000 degrees
|
||||
const float dLon = (float)(destinationLon2 - currentLon1) * GPS_scaleLonDown;
|
||||
|
||||
*dist = fast_fsqrtf(sq(dLat) + sq(dLon)) * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR;
|
||||
|
||||
*bearing = 9000.0f + RADIANS_TO_CENTIDEGREES(atan2_approx(-dLat, dLon)); // Convert the output radians to 100xdeg
|
||||
|
||||
if (*bearing < 0)
|
||||
*bearing += 36000;
|
||||
}
|
||||
|
||||
void onNewGPSData(void)
|
||||
{
|
||||
static timeMs_t previousTimeMs = 0;
|
||||
const timeMs_t currentTimeMs = millis();
|
||||
const timeDelta_t timeDeltaMs = currentTimeMs - previousTimeMs;
|
||||
previousTimeMs = currentTimeMs;
|
||||
|
||||
if (!(sensors(SENSOR_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5))
|
||||
return;
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
/* Update home distance and direction */
|
||||
if (STATE(GPS_FIX_HOME)) {
|
||||
uint32_t dist;
|
||||
int32_t dir;
|
||||
GPS_distance_cm_bearing(gpsSol.llh.lat, gpsSol.llh.lon, GPS_home.lat, GPS_home.lon, &dist, &dir);
|
||||
GPS_distanceToHome = dist / 100;
|
||||
GPS_directionToHome = lrintf(dir / 100.0f);
|
||||
} else {
|
||||
GPS_distanceToHome = 0;
|
||||
GPS_directionToHome = 0;
|
||||
}
|
||||
|
||||
/* Update trip distance */
|
||||
GPS_totalTravelDistance += gpsSol.groundSpeed * MS2S(timeDeltaMs);
|
||||
}
|
||||
else {
|
||||
// Set home position to current GPS coordinates
|
||||
ENABLE_STATE(GPS_FIX_HOME);
|
||||
GPS_home.lat = gpsSol.llh.lat;
|
||||
GPS_home.lon = gpsSol.llh.lon;
|
||||
GPS_home.alt = gpsSol.llh.alt;
|
||||
GPS_distanceToHome = 0;
|
||||
GPS_directionToHome = 0;
|
||||
GPS_scaleLonDown = cos_approx((fabsf((float)gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f);
|
||||
}
|
||||
}
|
||||
|
||||
int32_t getTotalTravelDistance(void)
|
||||
{
|
||||
return lrintf(GPS_totalTravelDistance);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif // NAV
|
||||
|
|
|
@ -68,8 +68,6 @@ bool findNearestSafeHome(void); // Find nearest safehome
|
|||
|
||||
#endif // defined(USE_SAFE_HOME)
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#ifndef NAV_MAX_WAYPOINTS
|
||||
#define NAV_MAX_WAYPOINTS 15
|
||||
#endif
|
||||
|
@ -229,7 +227,9 @@ typedef struct navConfig_s {
|
|||
uint8_t pos_failure_timeout; // Time to wait before switching to emergency landing (0 - disable)
|
||||
uint16_t waypoint_radius; // if we are within this distance to a waypoint then we consider it reached (distance is in cm)
|
||||
uint16_t waypoint_safe_distance; // Waypoint mission sanity check distance
|
||||
#ifdef USE_MULTI_MISSION
|
||||
uint8_t waypoint_multi_mission_index; // Index of mission to be loaded in multi mission entry
|
||||
#endif
|
||||
bool waypoint_load_on_boot; // load waypoints automatically during boot
|
||||
uint16_t auto_speed; // autonomous navigation speed cm/sec
|
||||
uint16_t max_auto_speed; // maximum allowed autonomous navigation speed cm/sec
|
||||
|
@ -492,9 +492,10 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData);
|
|||
void resetWaypointList(void);
|
||||
bool loadNonVolatileWaypointList(bool clearIfLoaded);
|
||||
bool saveNonVolatileWaypointList(void);
|
||||
#ifdef USE_MULTI_MISSION
|
||||
void selectMultiMissionIndex(int8_t increment);
|
||||
void setMultiMissionOnArm(void);
|
||||
|
||||
#endif
|
||||
float getFinalRTHAltitude(void);
|
||||
int16_t fixedWingPitchToThrottleCorrection(int16_t pitch, timeUs_t currentTimeUs);
|
||||
|
||||
|
@ -598,15 +599,3 @@ extern uint16_t navFlags;
|
|||
extern uint16_t navEPH;
|
||||
extern uint16_t navEPV;
|
||||
extern int16_t navAccNEU[3];
|
||||
|
||||
#else
|
||||
|
||||
#define navigationRequiresAngleMode() (0)
|
||||
#define navigationGetHeadingControlState() (0)
|
||||
#define navigationRequiresThrottleTiltCompensation() (0)
|
||||
#define getEstimatedActualVelocity(axis) (0)
|
||||
#define navigationIsControllingThrottle() (0)
|
||||
#define navigationRTHAllowsLanding() (0)
|
||||
#define navigationGetHomeHeading() (0)
|
||||
|
||||
#endif
|
||||
|
|
|
@ -21,8 +21,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
@ -188,7 +186,7 @@ void applyFixedWingAltitudeAndThrottleController(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
// Indicate that information is no longer usable
|
||||
posControl.flags.verticalPositionDataConsumed = 1;
|
||||
posControl.flags.verticalPositionDataConsumed = true;
|
||||
}
|
||||
|
||||
isPitchAdjustmentValid = true;
|
||||
|
@ -277,10 +275,9 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod)
|
|||
|
||||
// If angular visibility of a waypoint is less than 30deg, don't calculate circular loiter, go straight to the target
|
||||
#define TAN_15DEG 0.26795f
|
||||
bool needToCalculateCircularLoiter = (isApproachingLastWaypoint() || isWaypointWait())
|
||||
&& (distanceToActualTarget <= (navLoiterRadius / TAN_15DEG))
|
||||
&& (distanceToActualTarget > 50.0f)
|
||||
&& !FLIGHT_MODE(NAV_COURSE_HOLD_MODE);
|
||||
bool needToCalculateCircularLoiter = isNavHoldPositionActive() &&
|
||||
(distanceToActualTarget <= (navLoiterRadius / TAN_15DEG)) &&
|
||||
(distanceToActualTarget > 50.0f);
|
||||
|
||||
// Calculate virtual position for straight movement
|
||||
if (needToCalculateCircularLoiter) {
|
||||
|
@ -440,7 +437,7 @@ void applyFixedWingPositionController(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
// Indicate that information is no longer usable
|
||||
posControl.flags.horizontalPositionDataConsumed = 1;
|
||||
posControl.flags.horizontalPositionDataConsumed = true;
|
||||
}
|
||||
|
||||
isRollAdjustmentValid = true;
|
||||
|
@ -480,7 +477,7 @@ int16_t applyFixedWingMinSpeedController(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
// Indicate that information is no longer usable
|
||||
posControl.flags.horizontalPositionDataConsumed = 1;
|
||||
posControl.flags.horizontalPositionDataConsumed = true;
|
||||
}
|
||||
}
|
||||
else {
|
||||
|
@ -700,5 +697,3 @@ int32_t navigationGetHeadingError(void)
|
|||
{
|
||||
return navHeadingError;
|
||||
}
|
||||
|
||||
#endif // NAV
|
||||
|
|
|
@ -22,8 +22,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
@ -540,5 +538,3 @@ const char * fixedWingLaunchStateMessage(void)
|
|||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -21,8 +21,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
@ -169,6 +167,3 @@ bool geoConvertLocalToGeodetic(gpsLocation_t *llh, const gpsOrigin_t * origin, c
|
|||
llh->alt += lrintf(pos->z);
|
||||
return origin->valid;
|
||||
}
|
||||
|
||||
|
||||
#endif // NAV
|
||||
|
|
|
@ -21,8 +21,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
@ -235,7 +233,7 @@ static void applyMulticopterAltitudeController(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
// Indicate that information is no longer usable
|
||||
posControl.flags.verticalPositionDataConsumed = 1;
|
||||
posControl.flags.verticalPositionDataConsumed = true;
|
||||
}
|
||||
|
||||
// Update throttle controller
|
||||
|
@ -446,7 +444,7 @@ static void updatePositionVelocityController_MC(const float maxSpeed)
|
|||
*/
|
||||
if (
|
||||
(navGetCurrentStateFlags() & NAV_AUTO_WP &&
|
||||
!isApproachingLastWaypoint() &&
|
||||
!isNavHoldPositionActive() &&
|
||||
newVelTotal < maxSpeed &&
|
||||
!navConfig()->mc.slowDownForTurning
|
||||
) || newVelTotal > maxSpeed
|
||||
|
@ -654,7 +652,7 @@ static void applyMulticopterPositionController(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
// Indicate that information is no longer usable
|
||||
posControl.flags.horizontalPositionDataConsumed = 1;
|
||||
posControl.flags.horizontalPositionDataConsumed = true;
|
||||
}
|
||||
}
|
||||
else {
|
||||
|
@ -774,7 +772,7 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
// Indicate that information is no longer usable
|
||||
posControl.flags.verticalPositionDataConsumed = 1;
|
||||
posControl.flags.verticalPositionDataConsumed = true;
|
||||
}
|
||||
|
||||
// Update throttle controller
|
||||
|
@ -819,4 +817,3 @@ void applyMulticopterNavigationController(navigationFSMStateFlags_t navStateFlag
|
|||
applyMulticopterHeadingController();
|
||||
}
|
||||
}
|
||||
#endif // NAV
|
||||
|
|
|
@ -22,8 +22,6 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
|
@ -216,7 +214,7 @@ void onNewGPSData(void)
|
|||
if(STATE(GPS_FIX_HOME)){
|
||||
static bool magDeclinationSet = false;
|
||||
if (positionEstimationConfig()->automatic_mag_declination && !magDeclinationSet) {
|
||||
const float declination = geoCalculateMagDeclination(&newLLH);
|
||||
const float declination = geoCalculateMagDeclination(&newLLH);
|
||||
imuSetMagneticDeclination(declination);
|
||||
#ifdef USE_SECONDARY_IMU
|
||||
secondaryImuSetMagneticDeclination(declination);
|
||||
|
@ -861,5 +859,3 @@ bool navIsCalibrationComplete(void)
|
|||
{
|
||||
return gravityCalibrationComplete();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -32,8 +32,6 @@
|
|||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
#include "navigation/navigation_pos_estimator_private.h"
|
||||
|
@ -202,5 +200,3 @@ void estimationCalculateAGL(estimationContext_t * ctx)
|
|||
posEstimator.est.aglQual = SURFACE_QUAL_LOW;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // NAV
|
||||
|
|
|
@ -32,8 +32,6 @@
|
|||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
#include "navigation/navigation_pos_estimator_private.h"
|
||||
|
@ -123,6 +121,3 @@ bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx)
|
|||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#endif // NAV
|
||||
|
|
|
@ -19,8 +19,6 @@
|
|||
|
||||
#define DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR 1.113195f // MagicEarthNumber from APM
|
||||
|
||||
#if defined(USE_NAV)
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
|
@ -366,13 +364,13 @@ typedef struct {
|
|||
/* WP Mission planner */
|
||||
int8_t wpMissionPlannerStatus; // WP save status for setting in flight WP mission planner
|
||||
int8_t wpPlannerActiveWPIndex;
|
||||
|
||||
#ifdef USE_MULTI_MISSION
|
||||
/* Multi Missions */
|
||||
int8_t multiMissionCount; // number of missions in multi mission entry
|
||||
int8_t loadedMultiMissionIndex; // index of selected multi mission
|
||||
int8_t loadedMultiMissionStartWP; // selected multi mission start WP
|
||||
int8_t loadedMultiMissionWPCount; // number of WPs in selected multi mission
|
||||
|
||||
#endif
|
||||
navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation
|
||||
int8_t activeWaypointIndex;
|
||||
float wpInitialAltitude; // Altitude at start of WP
|
||||
|
@ -418,8 +416,8 @@ void updateClimbRateToAltitudeController(float desiredClimbRate, climbRateToAlti
|
|||
|
||||
bool isWaypointReached(const navWaypointPosition_t * waypoint, const bool isWaypointHome);
|
||||
bool isWaypointMissed(const navWaypointPosition_t * waypoint);
|
||||
bool isWaypointWait(void);
|
||||
bool isApproachingLastWaypoint(void);
|
||||
bool isNavHoldPositionActive(void);
|
||||
bool isLastMissionWaypoint(void);
|
||||
float getActiveWaypointSpeed(void);
|
||||
|
||||
void updateActualHeading(bool headingValid, int32_t newHeading);
|
||||
|
@ -479,5 +477,3 @@ void applyFixedWingLaunchController(timeUs_t currentTimeUs);
|
|||
* Rover specific functions
|
||||
*/
|
||||
void applyRoverBoatNavigationController(navigationFSMStateFlags_t navStateFlags, timeUs_t currentTimeUs);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -26,8 +26,6 @@
|
|||
|
||||
FILE_COMPILE_FOR_SIZE
|
||||
|
||||
#ifdef USE_NAV
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
@ -102,7 +100,7 @@ void applyRoverBoatPositionController(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
// Indicate that information is no longer usable
|
||||
posControl.flags.horizontalPositionDataConsumed = 1;
|
||||
posControl.flags.horizontalPositionDataConsumed = true;
|
||||
}
|
||||
|
||||
isYawAdjustmentValid = true;
|
||||
|
@ -148,5 +146,3 @@ void applyRoverBoatNavigationController(navigationFSMStateFlags_t navStateFlags,
|
|||
applyRoverBoatPitchRollThrottleController(navStateFlags, currentTimeUs);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -36,6 +36,7 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "drivers/serial_uart.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/osd.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/crsf.h"
|
||||
|
@ -241,8 +242,15 @@ STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
rxLinkStatistics.uplinkTXPower = crsfPowerStates[linkStats->uplinkTXPower];
|
||||
rxLinkStatistics.activeAnt = linkStats->activeAntenna;
|
||||
|
||||
if (rxLinkStatistics.uplinkLQ > 0)
|
||||
lqTrackerSet(rxRuntimeConfig->lqTracker, scaleRange(constrain(rxLinkStatistics.uplinkRSSI, -120, -30), -120, -30, 0, RSSI_MAX_VALUE));
|
||||
if (rxLinkStatistics.uplinkLQ > 0) {
|
||||
int16_t uplinkStrength; // RSSI dBm converted to %
|
||||
uplinkStrength = constrain((100 * sq((osdConfig()->rssi_dbm_max - osdConfig()->rssi_dbm_min)) - (100 * sq((osdConfig()->rssi_dbm_max - rxLinkStatistics.uplinkRSSI)))) / sq((osdConfig()->rssi_dbm_max - osdConfig()->rssi_dbm_min)),0,100);
|
||||
if (rxLinkStatistics.uplinkRSSI >= osdConfig()->rssi_dbm_max )
|
||||
uplinkStrength = 99;
|
||||
else if (rxLinkStatistics.uplinkRSSI < osdConfig()->rssi_dbm_min)
|
||||
uplinkStrength = 0;
|
||||
lqTrackerSet(rxRuntimeConfig->lqTracker, scaleRange(uplinkStrength, 0, 99, 0, RSSI_MAX_VALUE));
|
||||
}
|
||||
else
|
||||
lqTrackerSet(rxRuntimeConfig->lqTracker, 0);
|
||||
|
||||
|
|
|
@ -349,11 +349,7 @@ static void telemetryRX(void)
|
|||
if (sensors(SENSOR_GPS)) {
|
||||
uint16_t gpsspeed = (gpsSol.groundSpeed*9L)/250L;
|
||||
int16_t course = (gpsSol.groundCourse/10 + 360)%360;
|
||||
#ifdef USE_NAV
|
||||
int32_t alt = getEstimatedActualPosition(Z);
|
||||
#else
|
||||
int32_t alt = baro.BaroAlt;
|
||||
#endif
|
||||
uint16_t tim = 0;
|
||||
|
||||
rfTxBuffer[0] = 0x47;
|
||||
|
|
|
@ -38,14 +38,11 @@ FILE_COMPILE_FOR_SPEED
|
|||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
#include "drivers/accgyro/accgyro_mpu3050.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6000.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6050.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6500.h"
|
||||
#include "drivers/accgyro/accgyro_mpu9250.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro_lsm303dlhc.h"
|
||||
#include "drivers/accgyro/accgyro_l3gd20.h"
|
||||
#include "drivers/accgyro/accgyro_bmi088.h"
|
||||
#include "drivers/accgyro/accgyro_bmi160.h"
|
||||
#include "drivers/accgyro/accgyro_bmi270.h"
|
||||
|
@ -87,7 +84,7 @@ static EXTENDED_FASTRAM pt1Filter_t accVibeFilter[XYZ_AXIS_COUNT];
|
|||
static EXTENDED_FASTRAM filterApplyFnPtr accNotchFilterApplyFn;
|
||||
static EXTENDED_FASTRAM void *accNotchFilter[XYZ_AXIS_COUNT];
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 3);
|
||||
PG_REGISTER_WITH_RESET_FN(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 4);
|
||||
|
||||
void pgResetFn_accelerometerConfig(accelerometerConfig_t *instance)
|
||||
{
|
||||
|
@ -123,19 +120,6 @@ static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse)
|
|||
case ACC_AUTODETECT:
|
||||
FALLTHROUGH;
|
||||
|
||||
#ifdef USE_IMU_LSM303DLHC
|
||||
case ACC_LSM303DLHC:
|
||||
if (lsm303dlhcAccDetect(dev)) {
|
||||
accHardware = ACC_LSM303DLHC;
|
||||
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_MPU6050
|
||||
case ACC_MPU6050: // MPU6050
|
||||
if (mpu6050AccDetect(dev)) {
|
||||
|
|
|
@ -33,18 +33,17 @@
|
|||
|
||||
// Type of accelerometer used/detected
|
||||
typedef enum {
|
||||
ACC_NONE = 0,
|
||||
ACC_AUTODETECT = 1,
|
||||
ACC_MPU6050 = 2,
|
||||
ACC_LSM303DLHC = 3,
|
||||
ACC_MPU6000 = 4,
|
||||
ACC_MPU6500 = 5,
|
||||
ACC_MPU9250 = 6,
|
||||
ACC_BMI160 = 7,
|
||||
ACC_ICM20689 = 8,
|
||||
ACC_BMI088 = 9,
|
||||
ACC_ICM42605 = 10,
|
||||
ACC_BMI270 = 11,
|
||||
ACC_NONE = 0,
|
||||
ACC_AUTODETECT,
|
||||
ACC_MPU6050,
|
||||
ACC_MPU6000,
|
||||
ACC_MPU6500,
|
||||
ACC_MPU9250,
|
||||
ACC_BMI160,
|
||||
ACC_ICM20689,
|
||||
ACC_BMI088,
|
||||
ACC_ICM42605,
|
||||
ACC_BMI270,
|
||||
ACC_FAKE,
|
||||
ACC_MAX = ACC_FAKE
|
||||
} accelerationSensor_e;
|
||||
|
|
|
@ -40,14 +40,11 @@ FILE_COMPILE_FOR_SPEED
|
|||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
#include "drivers/accgyro/accgyro_mpu3050.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6000.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6050.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6500.h"
|
||||
#include "drivers/accgyro/accgyro_mpu9250.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro_lsm303dlhc.h"
|
||||
#include "drivers/accgyro/accgyro_l3gd20.h"
|
||||
#include "drivers/accgyro/accgyro_bmi088.h"
|
||||
#include "drivers/accgyro/accgyro_bmi160.h"
|
||||
#include "drivers/accgyro/accgyro_bmi270.h"
|
||||
|
@ -100,7 +97,7 @@ EXTENDED_FASTRAM dynamicGyroNotchState_t dynamicGyroNotchState;
|
|||
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 1);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 2);
|
||||
|
||||
PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
|
||||
.gyro_lpf = SETTING_GYRO_HARDWARE_LPF_DEFAULT,
|
||||
|
@ -146,24 +143,6 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard
|
|||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#ifdef USE_IMU_MPU3050
|
||||
case GYRO_MPU3050:
|
||||
if (mpu3050Detect(dev)) {
|
||||
gyroHardware = GYRO_MPU3050;
|
||||
break;
|
||||
}
|
||||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#ifdef USE_IMU_L3GD20
|
||||
case GYRO_L3GD20:
|
||||
if (l3gd20Detect(dev)) {
|
||||
gyroHardware = GYRO_L3GD20;
|
||||
break;
|
||||
}
|
||||
FALLTHROUGH;
|
||||
#endif
|
||||
|
||||
#ifdef USE_IMU_MPU6000
|
||||
case GYRO_MPU6000:
|
||||
if (mpu6000GyroDetect(dev)) {
|
||||
|
@ -479,8 +458,8 @@ void FAST_CODE NOINLINE gyroFilter()
|
|||
if (gyroAnalyseState.filterUpdateExecute) {
|
||||
dynamicGyroNotchFiltersUpdate(
|
||||
&dynamicGyroNotchState,
|
||||
gyroAnalyseState.filterUpdateAxis,
|
||||
gyroAnalyseState.filterUpdateFrequency
|
||||
gyroAnalyseState.filterUpdateAxis,
|
||||
gyroAnalyseState.centerFrequency[gyroAnalyseState.filterUpdateAxis]
|
||||
);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -24,12 +24,15 @@
|
|||
#include "config/parameter_group.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
/*
|
||||
* Number of peaks to detect with Dynamic Notch Filter aka Matrixc Filter. This is equal to the number of dynamic notch filters
|
||||
*/
|
||||
#define DYN_NOTCH_PEAK_COUNT 3
|
||||
|
||||
typedef enum {
|
||||
GYRO_NONE = 0,
|
||||
GYRO_AUTODETECT,
|
||||
GYRO_MPU6050,
|
||||
GYRO_MPU3050,
|
||||
GYRO_L3GD20,
|
||||
GYRO_MPU6000,
|
||||
GYRO_MPU6500,
|
||||
GYRO_MPU9250,
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
|
||||
#define IRLOCK_TIMEOUT 100
|
||||
|
||||
#if defined(USE_NAV) && defined(USE_IRLOCK)
|
||||
#if defined(USE_IRLOCK)
|
||||
|
||||
enum {
|
||||
DEBUG_IRLOCK_DETECTED,
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#if defined(USE_NAV) && defined(USE_IRLOCK)
|
||||
#if defined(USE_IRLOCK)
|
||||
|
||||
void irlockInit(void);
|
||||
bool irlockHasBeenDetected(void);
|
||||
|
|
|
@ -141,7 +141,6 @@
|
|||
|
||||
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
|
||||
|
||||
#define USE_NAV
|
||||
#define NAV_GPS_GLITCH_DETECTION
|
||||
|
||||
#define USE_ADC
|
||||
|
|
|
@ -1 +0,0 @@
|
|||
target_stm32f303xc(CHEBUZZF3 SKIP_RELEASES)
|
|
@ -1,48 +0,0 @@
|
|||
/*
|
||||
* 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 "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
// INPUTS CH1-8
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0), // PWM1 - PA8
|
||||
DEF_TIM(TIM16, CH1, PB8, TIM_USE_PWM, 0), // PWM2 - PB8
|
||||
DEF_TIM(TIM17, CH1, PB9, TIM_USE_PWM, 0), // PWM3 - PB9
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0), // PWM4 - PC6
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0), // PWM5 - PC7
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0), // PWM6 - PC8
|
||||
DEF_TIM(TIM15, CH1, PF9, TIM_USE_PWM, 0), // PWM7 - PF9
|
||||
DEF_TIM(TIM15, CH2, PF10, TIM_USE_PWM, 0), // PWM8 - PF10
|
||||
|
||||
DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM9 - PD12
|
||||
DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM10 - PD13
|
||||
DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM11 - PD14
|
||||
DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM12 - PD15
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM13 - PA1
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM14 - PA2
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_ANY, 0), // PWM15 - PA3
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0), // PWM16 - PB0
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0), // PWM17 - PB1
|
||||
DEF_TIM(TIM3, CH2, PA4, TIM_USE_ANY, 0), // PWM18 - PA4
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
|
@ -1,86 +0,0 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "CHF3" // Chebuzz F3
|
||||
|
||||
#define LED0 PE8 // Blue LEDs - PE8/PE12
|
||||
#define LED0_INVERTED
|
||||
#define LED1 PE10 // Orange LEDs - PE10/PE14
|
||||
#define LED1_INVERTED
|
||||
|
||||
#define BEEPER PE9 // Red LEDs - PE9/PE13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define USE_IMU_L3GD20
|
||||
#define USE_IMU_MPU6050
|
||||
#define USE_IMU_LSM303DLHC
|
||||
|
||||
#define MPU6050_I2C_BUS BUS_I2C1
|
||||
#define LSM303DLHC_I2C_BUS BUS_I2C1
|
||||
#define L3GD20_SPI_BUS BUS_SPI1
|
||||
#define L3GD20_CS_PIN PE3
|
||||
|
||||
#define IMU_L3GD20_ALIGN CW270_DEG
|
||||
#define IMU_LSM303DLHC_ALIGN CW0_DEG
|
||||
#define IMU_MPU6050_ALIGN CW0_DEG
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_MS5611
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#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
|
||||
|
||||
// Number of available PWM outputs
|
||||
#define MAX_PWM_OUTPUT_PORTS 10
|
||||
|
||||
// IO - assuming 303 in 64pin package, TODO
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2)|BIT(5)|BIT(6)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10))
|
|
@ -150,7 +150,6 @@
|
|||
// #define USE_RANGEFINDER_SRF10
|
||||
|
||||
// *************** NAV *****************************
|
||||
#define USE_NAV
|
||||
#define NAV_GPS_GLITCH_DETECTION
|
||||
#define NAV_MAX_WAYPOINTS 60
|
||||
|
||||
|
|
2
src/main/target/IFLIGHT_BLITZ_F722/CMakeLists.txt
Normal file
2
src/main/target/IFLIGHT_BLITZ_F722/CMakeLists.txt
Normal file
|
@ -0,0 +1,2 @@
|
|||
target_stm32f722xe(IFLIGHT_BLITZ_F722)
|
||||
|
|
@ -15,7 +15,15 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
#include <stdint.h>
|
||||
#include "platform.h"
|
||||
|
||||
bool lsm303dlhcAccDetect(accDev_t *acc);
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
|
||||
}
|
41
src/main/target/IFLIGHT_BLITZ_F722/target.c
Normal file
41
src/main/target/IFLIGHT_BLITZ_F722/target.c
Normal file
|
@ -0,0 +1,41 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
#include "platform.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 DMA1_S2_CH5
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 DMA1_S7_CH5
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 DMA2_S4_CH7
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 DMA2_S7_CH7
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 DMA1_S0_CH2
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 DMA1_S3_CH2
|
||||
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 DMA1_S1_CH3
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S8 DMA1_S6_CH3
|
||||
|
||||
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_LED, 0, 0), // WS2812B DMA2_S6_CH0
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
158
src/main/target/IFLIGHT_BLITZ_F722/target.h
Normal file
158
src/main/target/IFLIGHT_BLITZ_F722/target.h
Normal file
|
@ -0,0 +1,158 @@
|
|||
/*
|
||||
* 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 "IFF722"
|
||||
#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_F722"
|
||||
|
||||
#define LED0 PC15
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// *************** 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_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define GYRO_INT_EXTI PC4
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW0_DEG
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
// *************** I2C /Baro/Mag *********************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** SPI2 OSD***********************
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
// *************** SPI3 Flash ***********************
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PA15
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
#define USB_DETECT_PIN PB2
|
||||
#define USE_USB_DETECT
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PC11
|
||||
#define UART3_TX_PIN PC10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PA1
|
||||
#define UART4_TX_PIN PA0
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_RX_PIN PD2
|
||||
#define UART5_TX_PIN PC12
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define SERIAL_PORT_COUNT 7
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
|
||||
#define ADC_CHANNEL_1_PIN PC2
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
|
||||
// *************** LEDSTRIP ************************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA8
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL)
|
||||
#define CURRENT_METER_SCALE 200
|
||||
|
||||
#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 0xffff
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 10
|
||||
#define USE_OSD
|
||||
#define USE_DSHOT
|
||||
#define USE_SERIALSHOT
|
||||
#define USE_ESC_SENSOR
|
1
src/main/target/KAKUTEH7/CMakeLists.txt
Normal file
1
src/main/target/KAKUTEH7/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32h743xi(KAKUTEH7)
|
40
src/main/target/KAKUTEH7/config.c
Normal file
40
src/main/target/KAKUTEH7/config.c
Normal file
|
@ -0,0 +1,40 @@
|
|||
/*
|
||||
* 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 "fc/fc_msp_box.h"
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "io/piniobox.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
|
||||
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_MSP;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].msp_baudrateIndex = BAUD_115200;
|
||||
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_MSP;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].msp_baudrateIndex = BAUD_115200;
|
||||
|
||||
|
||||
}
|
44
src/main/target/KAKUTEH7/target.c
Normal file
44
src/main/target/KAKUTEH7/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 <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pinio.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4
|
||||
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S1
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S3
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S4
|
||||
|
||||
DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 8), // LED_2812
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
165
src/main/target/KAKUTEH7/target.h
Normal file
165
src/main/target/KAKUTEH7/target.h
Normal file
|
@ -0,0 +1,165 @@
|
|||
/*
|
||||
* 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 "KTH7"
|
||||
#define USBD_PRODUCT_STRING "KAKUTEH7"
|
||||
|
||||
#define USE_TARGET_CONFIG
|
||||
|
||||
#define LED0 PC2
|
||||
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// *************** IMU generic ***********************
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
|
||||
// *************** SPI1 ****************
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
// *************** SPI2 ***********************
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
// *************** SPI4 ***************
|
||||
#define USE_SPI_DEVICE_4
|
||||
#define SPI4_SCK_PIN PE2
|
||||
#define SPI4_MISO_PIN PE5
|
||||
#define SPI4_MOSI_PIN PE6
|
||||
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW270_DEG
|
||||
#define MPU6000_SPI_BUS BUS_SPI4
|
||||
#define MPU6000_CS_PIN PE4
|
||||
#define MPU6000_EXTI_PIN PE1
|
||||
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
// *************** I2C /Baro/Mag *********************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB6
|
||||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_VCM5883
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_TX_PIN PD5
|
||||
#define UART2_RX_PIN PD6
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_TX_PIN PD8
|
||||
#define UART3_RX_PIN PD9
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PD1
|
||||
#define UART4_RX_PIN PD0
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
#define USE_UART7
|
||||
#define UART7_RX_PIN PE7
|
||||
|
||||
#define SERIAL_PORT_COUNT 7
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
#define ADC_CHANNEL_2_PIN PC5
|
||||
#define ADC_CHANNEL_3_PIN PC1
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_2
|
||||
|
||||
// *************** PINIO ***************************
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PE13
|
||||
|
||||
// *************** LEDSTRIP ************************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PD12
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL)
|
||||
#define CURRENT_METER_SCALE 250
|
||||
|
||||
#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 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
1
src/main/target/MAMBAH743/CMakeLists.txt
Normal file
1
src/main/target/MAMBAH743/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32h743xi(MAMBAH743)
|
|
@ -15,6 +15,16 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
#include <stdint.h>
|
||||
|
||||
bool mpu3050Detect(gyroDev_t *gyro);
|
||||
#include "platform.h"
|
||||
|
||||
#include "fc/fc_msp_box.h"
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "io/piniobox.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
|
||||
}
|
47
src/main/target/MAMBAH743/target.c
Normal file
47
src/main/target/MAMBAH743/target.c
Normal file
|
@ -0,0 +1,47 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pinio.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S5
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S6
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 6), // S7
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 7), // S8
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 8), // LED_2812
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
186
src/main/target/MAMBAH743/target.h
Normal file
186
src/main/target/MAMBAH743/target.h
Normal file
|
@ -0,0 +1,186 @@
|
|||
/*
|
||||
* 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 "M743"
|
||||
#define USBD_PRODUCT_STRING "MAMBAH743"
|
||||
|
||||
#define USE_TARGET_CONFIG
|
||||
|
||||
#define LED0 PE5
|
||||
#define LED1 PE4
|
||||
|
||||
#define BEEPER PE3
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// *************** IMU generic ***********************
|
||||
#define USE_DUAL_GYRO
|
||||
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
// *************** SPI1 IMU0 MPU6000 ****************
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
// SPI4 is used on the second MPU6000 gyro, we do not use it at the moment
|
||||
// #define USE_SPI_DEVICE_4
|
||||
// #define SPI4_SCK_PIN PE12
|
||||
// #define SPI4_MISO_PIN PE13
|
||||
// #define SPI4_MOSI_PIN PE14
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW180_DEG
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_EXTI_PIN PC4
|
||||
|
||||
#define USE_IMU_BMI270
|
||||
#define IMU_BMI270_ALIGN CW180_DEG
|
||||
#define BMI270_SPI_BUS BUS_SPI1
|
||||
#define BMI270_CS_PIN PA4
|
||||
#define BMI270_EXTI_PIN PC4
|
||||
|
||||
// *************** SPI2 OSD ***********************
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
// *************** I2C /Baro/Mag *********************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB6
|
||||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C2_SCL PB10
|
||||
#define I2C2_SDA PB11
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define USE_MAG_VCM5883
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_TX_PIN PD5
|
||||
#define UART2_RX_PIN PD6
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_TX_PIN PD8
|
||||
#define UART3_RX_PIN PD9
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PD1
|
||||
#define UART4_RX_PIN PD0
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_TX_PIN PC12
|
||||
#define UART5_RX_PIN PD2
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
#define USE_UART7
|
||||
#define UART7_TX_PIN PE8
|
||||
#define UART7_RX_PIN PE7
|
||||
|
||||
#define USE_UART8
|
||||
#define UART8_TX_PIN PE1
|
||||
#define UART8_RX_PIN PE0
|
||||
|
||||
#define SERIAL_PORT_COUNT 9
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART6
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
|
||||
#define ADC_CHANNEL_1_PIN PC1
|
||||
#define ADC_CHANNEL_2_PIN PC3
|
||||
#define ADC_CHANNEL_3_PIN PC2
|
||||
#define ADC_CHANNEL_4_PIN PC0
|
||||
|
||||
#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
|
||||
|
||||
// *************** PINIO ***************************
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PC5
|
||||
|
||||
// *************** LEDSTRIP ************************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA8
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL)
|
||||
#define CURRENT_METER_SCALE 250
|
||||
|
||||
#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 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
|
@ -147,6 +147,7 @@
|
|||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
|
|
@ -56,6 +56,7 @@
|
|||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -59,6 +59,7 @@
|
|||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
|
|
|
@ -118,6 +118,7 @@
|
|||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -104,6 +104,7 @@
|
|||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -57,6 +57,7 @@
|
|||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -54,6 +54,7 @@
|
|||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -71,6 +71,7 @@
|
|||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -89,6 +89,7 @@
|
|||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
|
|
|
@ -47,7 +47,7 @@ const timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11
|
||||
DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12 DMA_NONE
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED_2812
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 8), // LED_2812
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_BEEPER, 0, 0), // BEEPER PWM
|
||||
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // RX6 PPM
|
||||
|
|
|
@ -109,6 +109,7 @@
|
|||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
|
|
1
src/main/target/SPEEDYBEEF7MINI/CMakeLists.txt
Normal file
1
src/main/target/SPEEDYBEEF7MINI/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32f722xe(SPEEDYBEEF7MINI)
|
|
@ -15,6 +15,19 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
#include <stdint.h>
|
||||
|
||||
bool l3gd20Detect(gyroDev_t *gyro);
|
||||
#include "platform.h"
|
||||
|
||||
#include "fc/fc_msp_box.h"
|
||||
|
||||
#include "io/piniobox.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_MSP;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].msp_baudrateIndex = BAUD_115200;
|
||||
|
||||
pinioBoxConfigMutable()->permanentId[0] = BOXARM;
|
||||
}
|
50
src/main/target/SPEEDYBEEF7MINI/target.c
Normal file
50
src/main/target/SPEEDYBEEF7MINI/target.c
Normal file
|
@ -0,0 +1,50 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pinio.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN);
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5)
|
||||
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(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED D(2, 6, 0)
|
||||
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM, RX1
|
||||
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 & softserial1
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
175
src/main/target/SPEEDYBEEF7MINI/target.h
Normal file
175
src/main/target/SPEEDYBEEF7MINI/target.h
Normal file
|
@ -0,0 +1,175 @@
|
|||
/*
|
||||
* 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 "SBMN"
|
||||
#define USBD_PRODUCT_STRING "SPEEDYBEEF7MINI"
|
||||
|
||||
#define LED0 PA14 //Blue SWCLK
|
||||
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// *************** SPI1 Gyro & ACC *******************
|
||||
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
|
||||
|
||||
#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_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW0_DEG
|
||||
#define MPU6000_CS_PIN PB2
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_EXTI_PIN PC4
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
// *************** I2C /Baro/Mag *********************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** SPI2 OSD ***********************
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
// *************** SPI3 SD BLACKBOX*******************
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_MISO_PIN PC11
|
||||
#define SPI3_MOSI_PIN PC12
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PD2
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
#define USB_DETECT_PIN PC14
|
||||
#define USE_USB_DETECT
|
||||
|
||||
#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 PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PA0
|
||||
#define UART4_RX_PIN PA1
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_TX_PIN PA2
|
||||
#define SOFTSERIAL_1_RX_PIN PA2
|
||||
|
||||
#define SERIAL_PORT_COUNT 7
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
|
||||
#define ADC_CHANNEL_1_PIN PC2
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
#define ADC_CHANNEL_3_PIN PC0
|
||||
#define ADC_CHANNEL_4_PIN PA4
|
||||
|
||||
#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
|
||||
|
||||
// *************** PINIO ***************************
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PC9 // RF Switch
|
||||
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
|
||||
|
||||
// *************** LEDSTRIP ************************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PC8
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
||||
#define CURRENT_METER_SCALE 250
|
||||
#define CURRENT_METER_OFFSET -500
|
||||
|
||||
#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 0xffff
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define USE_DSHOT
|
||||
#define USE_SERIALSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
||||
#define BNO055_I2C_BUS BUS_I2C1
|
||||
|
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