mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-13 19:40:27 +03:00
Merge remote-tracking branch 'upstream/master' into abo_acro_attitude_hold
This commit is contained in:
commit
7547d67eae
235 changed files with 3556 additions and 2022 deletions
1
.gitignore
vendored
1
.gitignore
vendored
|
@ -15,6 +15,7 @@ startup_stm32f10x_md_gcc.s
|
|||
#.vscode/
|
||||
cov-int*
|
||||
/build/
|
||||
/build_SITL/
|
||||
/obj/
|
||||
/patches/
|
||||
/tools/
|
||||
|
|
1
AUTHORS
1
AUTHORS
|
@ -56,6 +56,7 @@ Krzysztof Rosinski
|
|||
Kyle Manna
|
||||
Larry Davis
|
||||
Marc Egli
|
||||
Marcelo Bezerra
|
||||
Mark Williams
|
||||
Martin Budden
|
||||
Matthew Evans
|
||||
|
|
|
@ -44,9 +44,9 @@ The stick positions are combined to activate different functions:
|
|||
| Bypass Nav Arm disable | LOW | HIGH | CENTER | CENTER |
|
||||
| Save setting | LOW | LOW | LOW | HIGH |
|
||||
| Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER |
|
||||
| Enter Camera OSD(RuncamDevice)| RIGHT | CENTER | CENTER | CENTER |
|
||||
| Exit Camera OSD (RuncamDevice)| LEFT | CENTER | CENTER | CENTER |
|
||||
| Confirm - Camera OSD | RIGHT | CENTER | CENTER | CENTER |
|
||||
| Enter Camera OSD(RuncamDevice)| CENTER | HIGH | CENTER | CENTER |
|
||||
| Exit Camera OSD (RuncamDevice)| CENTER | LOW | CENTER | CENTER |
|
||||
| Confirm - Camera OSD | CENTER | HIGH | CENTER | CENTER |
|
||||
| Navigation - Camera OSD | CENTER | CENTER | * | * |
|
||||
|
||||
For graphical stick position in all transmitter modes, check out [this page](https://www.mrd-rc.com/tutorials-tools-and-testing/inav-flight/inav-stick-commands-for-all-transmitter-modes/).
|
||||
|
|
144
docs/MixerProfile.md
Normal file
144
docs/MixerProfile.md
Normal file
|
@ -0,0 +1,144 @@
|
|||
# MixerProfile
|
||||
|
||||
A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings to enable VTOL transitions.
|
||||
|
||||
Currently two profiles are supported on targets other than F411 and F722 (due to resource constraints on these FC). i.e VTOL transition is not available on F411 and F722 targets.
|
||||
|
||||
By default, switching between profiles requires reboot to take affect. However, when all conditions are met, and a suitable [configuration](#configuration) has been applied, `mixer_profile` also allows in-flight profile [switching](#rc-mode-settings) to allow things like VTOL operation. This is the recommended operating mode.
|
||||
|
||||
Please note that this is an emerging / experimental capability that will require some effort by the pilot to implement.
|
||||
|
||||
## Setup for VTOL
|
||||
- A VTOL specific FC target or `timer_output_mode` overrides was required in the early stage of the development, But since unified mapping introduced in INAV 7.0 It is not needed anymore.
|
||||
- ~~For mixer profile switching it is necessary to keep motor and servo PWM mapping consistent between Fixed-Wing (FW) and Multi-rotor (MR) profiles~~
|
||||
- ~~Traditionally, FW and MR have had different enumerations to define the PWM mappings. For VTOL operation it is necessary to set the `timer_output_mode` overrides to allow a consistent enumeration and thus mapping between MR and FW modes.~~
|
||||
- ~~In operation, it is necessary to set the `mixer_profile` and the `pid_profile` separately and to set a [RC mode](#rc-mode-settings) to switch between them.~~
|
||||
## Configuration
|
||||
### Timer overrides
|
||||
Set the timer overrides for the outputs that you are intended to use.
|
||||
For SITL builds, is not necessary to set timer overrides.
|
||||
Please note that there are some display issues on the configurator that will show wrong mapping on the mixer_profile which has less motor/servo compared with the another
|
||||
### Profile Switch
|
||||
|
||||
Setup the FW mode and MR mode separately in two different mixer profiles:
|
||||
|
||||
In this example, FW mode is `mixer_profile` 1 and MR mode is `mixer_profile` 2.
|
||||
|
||||
Currently, the INAV Configurator does not fully support `mixer_profile`, so some of the settings have to be done in CLI.
|
||||
|
||||
Add `set mixer_pid_profile_linking = ON` in order to enable `pid_profile` auto handling. It will change the `pid profile` index according to the `mixer_profile` index on FC boot and allow `mixer_profile` hot switching (this is recommended usage).
|
||||
|
||||
The following 2 `mixer_profile` sections are added in the CLI:
|
||||
|
||||
```
|
||||
#switch to mixer_profile by cli
|
||||
mixer_profile 1
|
||||
|
||||
set platform_type = AIRPLANE
|
||||
set model_preview_type = 26
|
||||
# motor stop feature have been moved to here
|
||||
set motorstop_on_low = ON
|
||||
# enable pid_profile auto handling (recommended).
|
||||
set mixer_pid_profile_linking = ON
|
||||
save
|
||||
```
|
||||
Then finish the aeroplane setting on mixer_profile 1
|
||||
|
||||
```
|
||||
mixer_profile 2
|
||||
|
||||
set platform_type = TRICOPTER
|
||||
set model_preview_type = 1
|
||||
# also enable pid_profile auto handling
|
||||
set mixer_pid_profile_linking = ON
|
||||
save
|
||||
```
|
||||
Then finish the multi-rotor setting on `mixer_profile` 2.
|
||||
|
||||
Note that default profile is profile `1`.
|
||||
|
||||
You can use `MAX` servo input to set a fixed input for the tilting servo. Speed setting for `MAX` input is available in the CLI.
|
||||
|
||||
It is recommended to have some amount of control surface (elevon / elevator) mapped for stabilization even in MR mode to get improved authority when airspeed is high.
|
||||
|
||||
**Double check all settings in CLI with the `diff all` command**; make sure you have set the correct settings. Also check what will change with `mixer_profile`. For example servo output min / max range will not change. But `smix` and `mmix` will change.
|
||||
|
||||
### Mixer Transition input
|
||||
|
||||
Typically, 'transition input' will be useful in MR mode to gain airspeed.
|
||||
Both the servo mixer and motor mixer can accept transition mode as an input.
|
||||
The associated motor or servo will then move accordingly when transition mode is activated.
|
||||
Transition input is disabled when navigation mode is activate
|
||||
|
||||
The use of Transition Mode is recommended to enable further features and future developments like fail-safe support. Mapping motor to servo output, or servo with logic conditions is **not** recommended
|
||||
|
||||
#### Servo
|
||||
|
||||
38 is the input source for transition input; use this to tilt motor to gain airspeed.
|
||||
|
||||
Example: Increase servo 1 output by +45 with speed of 150 when transition mode is activated for tilted motor setup:
|
||||
|
||||
```
|
||||
# rule no; servo index; input source; rate; speed; activate logic function number
|
||||
smix 6 1 38 45 150 -1
|
||||
```
|
||||
Please note there will be a time window that tilting motors is providing up lift but rear motor isn't. Result in a sudden pitch raise on the entering of the mode. More forward tilting servo position on transition input(you can use 'speed' in servo rules to slowly move to this position), A faster tilting servo speed on `MAX` servo input will reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect.
|
||||
|
||||
#### Motor
|
||||
|
||||
The default `mmix` throttle value is 0.0, It will not show in `diff` command when throttle value is 0.0 (unused); this causes the motor to stop.
|
||||
|
||||
- 0.0<throttle<=1.0 : normal mapping
|
||||
- -1.0<throttle<=0.0 : motor stop, default value 0
|
||||
- -2.0<throttle<-1.0 : spin regardless of the radio's throttle position at speed `abs(throttle)-1` when Mixer Transition is activated.
|
||||
|
||||
Example: This will spin motor number 5 (counting from 1) at 20%, in transition mode only, to gain speed for a "4 rotor 1 pusher" setup:
|
||||
|
||||
```
|
||||
# motor number; throttle; roll; pitch; yaw
|
||||
mmix 4 -1.200 0.000 0.000 0.000
|
||||
```
|
||||
|
||||
### RC mode settings
|
||||
|
||||
It is recommend that the pilot uses a RC mode switch to activate modes or switch profiles.
|
||||
Profile files Switching is not available until the runtime sensor calibration is done. Switching is NOT available when navigation mode is activate or position controller is activate, including altitude hold.
|
||||
|
||||
`mixer_profile` 1 will be used as default, `mixer_profile` 2 will be used when the `MIXER PROFILE 2` mode box is activated. Once successfully set, you can see the profiles / model preview etc. will switch accordingly when you view the relevant INAV Configurator tabs. Checking these tabs in the INAV Configurator will help make the setup easier.
|
||||
|
||||
Set `MIXER TRANSITION` accordingly when you want to use `MIXER TRANSITION` input for motors and servos. Here is sample of using the `MIXER TRANSITION` mode:
|
||||
|
||||

|
||||
|
||||
| 1000~1300 | 1300~1700 | 1700~2000 |
|
||||
| :-- | :-- | :-- |
|
||||
| FW(profile1) with transition off | MC(profile2) with transition on | MC(profile2) with transition off |
|
||||
|
||||
It is also possible to set it as 4 state switch by adding FW(profile1) with transition on.
|
||||
|
||||
### Automated Transition
|
||||
This feature is mainly for RTH in a failsafe event. When set properly, model will use the FW mode to fly home efficiently, And land in the MC mode for easier landing.
|
||||
Set `mixer_automated_switch` to `ON` in mixer_profile for MC mode. Set `mixer_switch_trans_timer` in mixer_profile for MC mode for the time required to gain airspeed for your model before entering to FW mode, for example, 50 ds. Finally set `mixer_automated_switch` to `ON` in mixer_profile for FW mode to let the model land in MC mode.
|
||||
```
|
||||
mixer_profile 2
|
||||
set mixer_automated_switch = ON
|
||||
set mixer_switch_trans_timer = 50
|
||||
mixer_profile 1
|
||||
set mixer_automated_switch = ON
|
||||
save
|
||||
```
|
||||
|
||||
`ON` for a mixer_profile\`s `mixer_automated_switch` means to schedule a Automated Transition when RTH head home(applies for MC mixer_profile) or RTH Land(applies for FW mixer_profile) is requested by navigation controller.
|
||||
|
||||
When `mixer_automated_switch`:`OFF` is set for all mixer_profiles(defaults). Model will not perform automated transition at all.
|
||||
|
||||
|
||||
## Happy flying
|
||||
|
||||
Remember that this is currently an emerging capability:
|
||||
|
||||
* Test every thing on bench first.
|
||||
* Remove the props and try `MIXER PROFILE 2`, `MIXER TRANSITION` RC modes while arming.
|
||||
* Then try MR or FW mode separately see if there are any problems.
|
||||
* Try it somewhere you can recover your model in case of fail-safe. Fail-safe behavior is unknown at the current stage of development.
|
||||
* Use the INAV Discord for help and setup questions; use the Github Issues for reporting bugs and unexpected behaviors. For reporting on Github, a CLI `diff all`, a DVR and a Blackbox log of the incident will assist investigation.
|
|
@ -1,17 +1,28 @@
|
|||
# INAV Programming Framework
|
||||
|
||||
INAV Programming Framework (abbr. IPF) is a mechanism that allows to evaluate cenrtain flight parameters (RC channels, switches, altitude, distance, timers, other logic conditions) and use the value of evaluated expression in different places of INAV. Currently, the result of LCs can be used in:
|
||||
INAV Programming Framework (IPF) is a mechanism that allows you to to create
|
||||
custom functionality in INAV. You can choose for certain actions to be done,
|
||||
based on custom conditions you select.
|
||||
|
||||
Logic conditions can be based on things such as RC channel values, switches, altitude,
|
||||
distance, timers, etc. The conditions you create can also make use of other conditions
|
||||
you've entered previously.
|
||||
The results can be used in:
|
||||
|
||||
* [Servo mixer](Mixer.md) to activate/deactivate certain servo mix rulers
|
||||
* To activate/deactivate system overrides
|
||||
|
||||
INAV Programming Framework coinsists of:
|
||||
INAV Programming Framework consists of:
|
||||
|
||||
* Logic Conditions - each Logic Condition can be understood as a single command, a single line of code
|
||||
* Global Variables - variables that can store values from and for LogiC Conditions and servo mixer
|
||||
* Logic Conditions - each Logic Condition can be understood as a single command, a single line of code. Each logic condition consists of:
|
||||
* an operator (action), such as "plus" or "set vtx power"
|
||||
* one or two operands (nouns), which the action acts upon. Operands are often numbers, such as a channel value or the distance to home.
|
||||
* "activator" condition - optional. This condition is only active when another condition is true
|
||||
* Global Variables - variables that can store values from and for Logic Conditions and servo mixer
|
||||
* Programming PID - general purpose, user configurable PID controllers
|
||||
|
||||
IPF can be edited using INAV Configurator user interface, or via CLI
|
||||
IPF can be edited using INAV Configurator user interface, or via CLI. To use COnfigurator, click the tab labeled
|
||||
"Programming". The various options shown in Configurator are described below.
|
||||
|
||||
## Logic Conditions
|
||||
|
||||
|
@ -141,6 +152,9 @@ IPF can be edited using INAV Configurator user interface, or via CLI
|
|||
| 35 | AGL_STATUS | boolean `1` when AGL can be trusted, `0` when AGL estimate can not be trusted |
|
||||
| 36 | AGL | integer Above The Groud Altitude in `cm` |
|
||||
| 37 | RANGEFINDER_RAW | integer raw distance provided by the rangefinder in `cm` |
|
||||
| 38 | ACTIVE_MIXER_PROFILE | Which mixers are currently active (for vtol etc) |
|
||||
| 39 | MIXER_TRANSITION_ACTIVE | Currently switching between mixers (quad to plane etc) |
|
||||
| 40 | ATTITUDE_YAW | current heading (yaw) in `degrees` |
|
||||
|
||||
#### FLIGHT_MODE
|
||||
|
||||
|
@ -310,3 +324,14 @@ Steps:
|
|||
2. Scale range [0:1000] to [0:3]
|
||||
3. Increase range by `1` to have the range of [1:4]
|
||||
4. Assign LC#2 to VTX power function
|
||||
|
||||
## Common issues / questions about IPF
|
||||
|
||||
One common mistake involves setting RC channel values. To override (set) the
|
||||
value of a specific RC channel, choose "Override RC value", then for operand A
|
||||
choose *value* and enter the channel number. Choosing "get RC value" is a common mistake,
|
||||
which does something other than what you probably want.
|
||||
|
||||

|
||||
|
||||
|
||||
|
|
29
docs/Rx.md
29
docs/Rx.md
|
@ -2,10 +2,11 @@
|
|||
|
||||
A receiver is used to receive radio control signals from your transmitter and convert them into signals that the flight controller can understand.
|
||||
|
||||
There are 2 basic types of receivers:
|
||||
There are a number of types of receivers:
|
||||
|
||||
1. PPM Receivers
|
||||
2. Serial Receivers
|
||||
* PPM Receivers (obsolete)
|
||||
* Serial Receivers
|
||||
* MSP RX
|
||||
|
||||
## PPM Receivers
|
||||
|
||||
|
@ -192,9 +193,19 @@ This command will put the receiver into bind mode without the need to reboot the
|
|||
bind_rx
|
||||
```
|
||||
|
||||
## MultiWii serial protocol (MSP)
|
||||
## MultiWii serial protocol (MSP RX)
|
||||
|
||||
Allows you to use MSP commands as the RC input. Only 8 channel support to maintain compatibility with MSP.
|
||||
Allows you to use MSP commands as the RC input. Up to 18 channels are supported.
|
||||
Note:
|
||||
* It is necessary to update `MSP_SET_RAW_RC` at 5Hz or faster.
|
||||
* `MSP_SET_RAW_RC` uses the defined RC channel map
|
||||
* `MSP_RC` returns `AERT` regardless of channel map
|
||||
* You can combine "real" RC radio and MSP RX by compiling custom firmware with `USE_MSP_RC_OVERRIDE` defined. Then use `msp_override_channels` to set the channels to be overridden.
|
||||
* The [wiki Remote Control and Management article](https://github.com/iNavFlight/inav/wiki/INAV-Remote-Management,-Control-and-Telemetry) provides more information, including links to 3rd party projects that exercise `MSP_SET_RAW_RC` and `USE_MSP_RC_OVERRIDE`
|
||||
|
||||
## SIM (SITL) Joystick
|
||||
|
||||
Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL).
|
||||
|
||||
## Configuration
|
||||
|
||||
|
@ -203,7 +214,7 @@ The receiver type can be set from the configurator or CLI.
|
|||
```
|
||||
# get receiver_type
|
||||
receiver_type = NONE
|
||||
Allowed values: NONE, PPM, SERIAL, MSP, SPI, UIB
|
||||
Allowed values: NONE, SERIAL, MSP, SIM (SITL)
|
||||
```
|
||||
|
||||
### RX signal-loss detection
|
||||
|
@ -233,7 +244,7 @@ The highest channel value considered valid. e.g. PWM/PPM pulse length
|
|||
See the Serial chapter for some some RX configuration examples.
|
||||
|
||||
To setup spectrum in the GUI:
|
||||
1. Start on the "Ports" tab make sure that UART2 has serial RX. If not set the checkbox, save and reboot.
|
||||
1. Start on the "Ports" tab make sure that teh required has serial RX. If not set the checkbox, save and reboot.
|
||||
2. Move to the "Configuration" page and in the upper lefthand corner choose Serial RX as the receiver type.
|
||||
3. Below that choose the type of serial receiver that you are using. Save and reboot.
|
||||
|
||||
|
@ -244,11 +255,11 @@ For Serial RX set the `receiver_type` and `serialrx_provider` setting as appropr
|
|||
```
|
||||
# get rec
|
||||
receiver_type = SERIAL
|
||||
Allowed values: NONE, PPM, SERIAL, MSP, SPI, UIB
|
||||
Allowed values: NONE, SERIAL, MSP, SIM (SITL)
|
||||
|
||||
# get serialrx
|
||||
serialrx_provider = SBUS
|
||||
Allowed values: SPEK1024, SPEK2048, SBUS, SUMD, IBUS, JETIEXBUS, CRSF, FPORT, SBUS_FAST, FPORT2, SRXL2
|
||||
Allowed values: SPEK1024, SPEK2048, SBUS, SUMD, IBUS, JETIEXBUS, CRSF, FPORT, SBUS_FAST, FPORT2, SRXL2, GHST, MAVLINK, FBUS
|
||||
|
||||
```
|
||||
|
||||
|
|
BIN
docs/Screenshots/mixer_profile.png
Normal file
BIN
docs/Screenshots/mixer_profile.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 24 KiB |
|
@ -46,11 +46,11 @@ e.g. after configuring a port for GPS enable the GPS feature.
|
|||
* If SoftSerial is used, then all SoftSerial ports must use the same baudrate.
|
||||
* Softserial is limited to 19200 buad.
|
||||
* All telemetry systems except MSP will ignore any attempts to override the baudrate.
|
||||
* MSP/CLI can be shared with EITHER Blackbox OR telemetry. In shared mode blackbox or telemetry will be output only when armed.
|
||||
* MSP/CLI can be shared with EITHER Blackbox OR telemetry (LTM or MAVlink, not RX telemetry). In shared mode blackbox or telemetry will be output only when armed.
|
||||
* Smartport telemetry cannot be shared with MSP.
|
||||
* No other serial port sharing combinations are valid.
|
||||
* You can use as many different telemetry systems as you like at the same time.
|
||||
* You can only use each telemetry system once. e.g. FrSky telemetry cannot be used on two port, but MSP Telemetry + FrSky on different ports is fine.
|
||||
* You can only use each telemetry system once. e.g. FrSky telemetry cannot be used on two port, but LTN Telemetry and FrSky on two different ports is fine.
|
||||
|
||||
### Configuration via CLI
|
||||
|
||||
|
@ -89,4 +89,3 @@ The allowable baud rates are as follows:
|
|||
| 14 | 1500000 |
|
||||
| 15 | 2000000 |
|
||||
| 16 | 2470000 |
|
||||
|
||||
|
|
|
@ -258,7 +258,7 @@ Inertia force compensation method when gps is avaliable, VELNED use the acclerat
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| VELNED | | |
|
||||
| ADAPTIVE | | |
|
||||
|
||||
---
|
||||
|
||||
|
@ -1864,7 +1864,7 @@ Weight of GPS altitude measurements in estimated altitude. Setting is used only
|
|||
|
||||
### inav_w_z_gps_v
|
||||
|
||||
Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero
|
||||
Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
|
@ -2552,6 +2552,36 @@ This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly
|
|||
|
||||
---
|
||||
|
||||
### mixer_automated_switch
|
||||
|
||||
If set to on, This mixer_profile will try to switch to another mixer_profile when 1.RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius on mixer_profile is a MULTIROTOR or TRICOPTER platform_type. 2. RTH landing is requested on this mixer_profile is a AIRPLANE platform_type
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
### mixer_pid_profile_linking
|
||||
|
||||
If enabled, pid profile_index will follow mixer_profile index. Set to OFF(default) if you want to handle PID profile by your self. Recommend to set to ON on all mixer_profiles to let the mixer_profile handle the PID profile switching on a VTOL or mixed platform type setup.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
### mixer_switch_trans_timer
|
||||
|
||||
If switch another mixer_profile is scheduled by mixer_automated_switch or mixer_automated_switch. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 0 | 0 | 200 |
|
||||
|
||||
---
|
||||
|
||||
### mode_range_logic_operator
|
||||
|
||||
Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode.
|
||||
|
@ -2612,6 +2642,16 @@ Output frequency (in Hz) for motor pins. Applies only to brushed motors.
|
|||
|
||||
---
|
||||
|
||||
### motorstop_on_low
|
||||
|
||||
If enabled, motor will stop when throttle is low on this mixer_profile
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
### msp_override_channels
|
||||
|
||||
Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode.
|
||||
|
@ -3398,7 +3438,7 @@ Multicopter hover throttle hint for altitude controller. Should be set to approx
|
|||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 1500 | 1000 | 2000 |
|
||||
| 1300 | 1000 | 2000 |
|
||||
|
||||
---
|
||||
|
||||
|
@ -3972,6 +4012,16 @@ Value above which to make the OSD relative altitude indicator blink (meters)
|
|||
|
||||
---
|
||||
|
||||
### osd_arm_screen_display_time
|
||||
|
||||
Amount of time to display the arm screen [ms]
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 1500 | 1000 | 5000 |
|
||||
|
||||
---
|
||||
|
||||
### osd_baro_temp_alarm_max
|
||||
|
||||
Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)
|
||||
|
@ -4302,6 +4352,16 @@ Temperature under which the IMU temperature OSD element will start blinking (dec
|
|||
|
||||
---
|
||||
|
||||
### osd_inav_to_pilot_logo_spacing
|
||||
|
||||
The space between the INAV and pilot logos, if `osd_use_pilot_logo` is `ON`. This number may be adjusted so that it fits the odd/even col width displays. For example, if using an odd column width display, such as Walksnail, and this is set to 4. 1 will be added so that the logos are equally spaced from the centre of the screen.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 8 | 0 | 20 |
|
||||
|
||||
---
|
||||
|
||||
### osd_left_sidebar_scroll
|
||||
|
||||
_// TODO_
|
||||
|
@ -4722,6 +4782,16 @@ IMPERIAL, METRIC, UK
|
|||
|
||||
---
|
||||
|
||||
### osd_use_pilot_logo
|
||||
|
||||
Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
### osd_video_system
|
||||
|
||||
Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF', 'AVATAR' and `BF43COMPAT`
|
||||
|
|
|
@ -89,23 +89,6 @@ To change for example the configuration of the fourth sensor to label `BATT`, mi
|
|||
|
||||
`temp_sensor 3 2 7d01186838f2ff28 5 450 0 BATT`
|
||||
|
||||
## Building a custom firmware with temperature sensor support (F3 only)
|
||||
|
||||
This needs to be added in the `target.h` file:
|
||||
|
||||
```
|
||||
#define USE_TEMPERATURE_SENSOR
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2Cx // replace x with the index of the I²C bus the temperature sensors will be connected to
|
||||
|
||||
// for LM75 sensors support
|
||||
#define USE_TEMPERATURE_LM75
|
||||
|
||||
// for DS18B20 sensors
|
||||
#define USE_1WIRE
|
||||
#define USE_1WIRE_DS2482
|
||||
#define USE_TEMPERATURE_DS18B20
|
||||
```
|
||||
|
||||
## Configuring the way OSD temperature labels are displayed
|
||||
|
||||
You can use the `osd_temp_label_align` setting to chose how the labels for the temperature sensor's values are displayed. Possible alignment values are `LEFT` and `RIGHT`.
|
||||
|
|
BIN
docs/assets/images/ipf_set_get_rc_channel.png
Normal file
BIN
docs/assets/images/ipf_set_get_rc_channel.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 12 KiB |
|
@ -1,4 +1,4 @@
|
|||
# Software In The Loop (HITL) plugin for X-Plane 11
|
||||
# Hardware In The Loop (HITL) plugin for X-Plane 11/12
|
||||
|
||||
**Hardware-in-the-loop (HITL) simulation**, is a technique that is used in the development and testing of complex real-time embedded systems.
|
||||
|
||||
|
@ -6,6 +6,6 @@
|
|||
|
||||
**INAV-X-Plane-HITL** is plugin for **X-Plane** for testing and developing flight controllers with **INAV flight controller firmware**
|
||||
|
||||
https://github.com/iNavFlight/inav.
|
||||
https://github.com/RomanLut/INAV-X-Plane-HITL
|
||||
|
||||
HITL technique can be used to test features during development. Please check page above for installation instructions.
|
|
@ -16,7 +16,7 @@ Building the pull request manually or using custom/unofficial targets is not the
|
|||
- Make sure the pull request has passed all checks, otherwise you may not have pre-compiled firmware images.
|
||||
- Make a diff all backup of your existing INAV configuration.
|
||||
- Take notes of what INAV target you are using.
|
||||
- You will need a recent version of INAV Configurator from master, or even a specific branch. If you don't need a specific branch, [inav-configurator-next](http://seyrsnys.myzen.co.uk/inav-configurator-next/) usually has recent unofficial pre-built versions of INAV Configurator. If your pull requests refers to an inav-configruator pull request, you are likely to need a specific branch of the configurator. In that case you can try to build it from source by following the build [``Instructions``](https://github.com/iNavFlight/inav-configurator#building-and-running-inav-configurator-locally-for-development) or follow instructions on how to do any needed configuration changes using the CLI.
|
||||
- You will need a recent version of INAV Configurator from master, or even a specific branch. If you don't need a specific branch, [inav-configurator-next](https://seyrsnys-inav-cfg-next.surge.sh/) usually has recent unofficial pre-built versions of INAV Configurator. If your pull requests refers to an inav-configruator pull request, you are likely to need a specific branch of the configurator. In that case you can try to build it from source by following the build [``Instructions``](https://github.com/iNavFlight/inav-configurator#building-and-running-inav-configurator-locally-for-development) or follow instructions on how to do any needed configuration changes using the CLI.
|
||||
|
||||
# Finding the pull request
|
||||
This is easy, but you will need to be logged in to your GitHub account.
|
||||
|
@ -31,18 +31,11 @@ Once you find the one you are looking for, go ahead an open it!
|
|||
|
||||
Click on the ``Checks`` tab
|
||||
|
||||
Click on ``Build firmware``, it should take you to the ``Actions`` tab.
|
||||

|
||||
Click on the down arrow next to the number of artifacts
|
||||

|
||||
|
||||
You should see a summary with a column saying ``Artifacts`` and a number. Click on the number to be taken to the list of artifacts.
|
||||
|
||||

|
||||
|
||||
On the ``Artifacts`` list, there should be an artifact without SITL in its name.
|
||||
|
||||

|
||||
|
||||
Click on it to download the zip file containing pre-compiled firmware images for all INAV official targets. Extract all files and select the firmware for your target using the configurator by clicking on ``Load Firmware [Local]`` button. Don't forget to use the ``Full chip erase`` option, as there are no guarantees the firmware will be compatible with your existing settings.
|
||||
You should see a list of files. The one without SITL in the name, the biggest one, will be a zip file with all official target .hex files. Click on it to download it to your computer.
|
||||
Extract all files and select the firmware for your target using the configurator by clicking on ``Load Firmware [Local]`` button. Don't forget to use the ``Full chip erase`` option, as there are no guarantees the firmware will be compatible with your existing settings.
|
||||
|
||||
# I have flashed the new firmware, what should I do next?
|
||||
|
||||
|
|
Binary file not shown.
Before Width: | Height: | Size: 12 KiB |
Binary file not shown.
Before Width: | Height: | Size: 71 KiB |
BIN
docs/development/assets/pr_testing/artifacts_download.png
Normal file
BIN
docs/development/assets/pr_testing/artifacts_download.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 98 KiB |
Binary file not shown.
Before Width: | Height: | Size: 32 KiB |
|
@ -327,6 +327,8 @@ main_sources(COMMON_SRC
|
|||
flight/rth_estimator.h
|
||||
flight/servos.c
|
||||
flight/servos.h
|
||||
flight/mixer_profile.c
|
||||
flight/mixer_profile.h
|
||||
flight/wind_estimator.c
|
||||
flight/wind_estimator.h
|
||||
flight/gyroanalyse.c
|
||||
|
@ -504,7 +506,6 @@ main_sources(COMMON_SRC
|
|||
io/gps.h
|
||||
io/gps_ublox.c
|
||||
io/gps_ublox_utils.c
|
||||
io/gps_nmea.c
|
||||
io/gps_msp.c
|
||||
io/gps_fake.c
|
||||
io/gps_private.h
|
||||
|
|
|
@ -31,6 +31,7 @@
|
|||
|
||||
#include "build/version.h"
|
||||
|
||||
#include "flight/mixer_profile.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
|
@ -40,6 +41,7 @@
|
|||
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/settings.h"
|
||||
#include "fc/config.h"
|
||||
|
||||
static uint8_t currentMotorMixerIndex = 0;
|
||||
static uint8_t tmpcurrentMotorMixerIndex = 1;
|
||||
|
|
|
@ -114,8 +114,7 @@ typedef union {
|
|||
fp_angles_def angles;
|
||||
} fp_angles_t;
|
||||
|
||||
typedef struct stdev_s
|
||||
{
|
||||
typedef struct stdev_s {
|
||||
float m_oldM, m_newM, m_oldS, m_newS;
|
||||
int m_n;
|
||||
} stdev_t;
|
||||
|
|
|
@ -36,8 +36,8 @@
|
|||
//#define PG_TRANSPONDER_CONFIG 17
|
||||
#define PG_SYSTEM_CONFIG 18
|
||||
#define PG_FEATURE_CONFIG 19
|
||||
#define PG_MIXER_CONFIG 20
|
||||
#define PG_SERVO_MIXER 21
|
||||
#define PG_MIXER_PROFILE 20
|
||||
// #define PG_SERVO_MIXER 21
|
||||
#define PG_IMU_CONFIG 22
|
||||
//#define PG_PROFILE_SELECTION 23
|
||||
#define PG_RX_CONFIG 24
|
||||
|
|
|
@ -159,6 +159,7 @@
|
|||
#define SYM_HEADING_W 0xCB // 203 Heading Graphic west
|
||||
#define SYM_HEADING_DIVIDED_LINE 0xCC // 204 Heading Graphic
|
||||
#define SYM_HEADING_LINE 0xCD // 205 Heading Graphic
|
||||
|
||||
#define SYM_MAX 0xCE // 206 MAX symbol
|
||||
#define SYM_PROFILE 0xCF // 207 Profile symbol
|
||||
#define SYM_SWITCH_INDICATOR_LOW 0xD0 // 208 Switch High
|
||||
|
@ -175,10 +176,10 @@
|
|||
#define SYM_FLIGHT_HOURS_REMAINING 0xDB // 219 Flight time (hours) remaining
|
||||
#define SYM_GROUND_COURSE 0xDC // 220 Ground course
|
||||
#define SYM_ALERT 0xDD // 221 General alert symbol
|
||||
|
||||
#define SYM_TERRAIN_FOLLOWING 0xFB // 251 Terrain following (also Alt adjust)
|
||||
#define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error
|
||||
|
||||
|
||||
#define SYM_LOGO_START 0x101 // 257 to 297, INAV logo
|
||||
#define SYM_LOGO_WIDTH 10
|
||||
#define SYM_LOGO_HEIGHT 4
|
||||
|
@ -228,6 +229,7 @@
|
|||
#define SYM_HOME_DIST 0x165 // 357 DIST
|
||||
#define SYM_AH_CH_CENTER 0x166 // 358 Crossair center
|
||||
#define SYM_FLIGHT_DIST_REMAINING 0x167 // 359 Flight distance reminaing
|
||||
#define SYM_ODOMETER 0x168 // 360 Odometer
|
||||
|
||||
#define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3
|
||||
#define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4
|
||||
|
@ -261,6 +263,11 @@
|
|||
#define SYM_SERVO_PAN_IS_OFFSET_L 0x1C7 // 455 Pan servo is offset left
|
||||
#define SYM_SERVO_PAN_IS_OFFSET_R 0x1C8 // 456 Pan servo is offset right
|
||||
|
||||
#define SYM_PILOT_LOGO_SML_L 0x1D5 // 469 small Pilot logo Left
|
||||
#define SYM_PILOT_LOGO_SML_C 0x1D6 // 470 small Pilot logo Centre
|
||||
#define SYM_PILOT_LOGO_SML_R 0x1D7 // 471 small Pilot logo Right
|
||||
#define SYM_PILOT_LOGO_LRG_START 0x1D8 // 472 to 511, Pilot logo
|
||||
|
||||
#else
|
||||
|
||||
#define TEMP_SENSOR_SYM_COUNT 0
|
||||
|
|
|
@ -38,7 +38,7 @@ uint8_t hardwareMotorType = MOTOR_UNKNOWN;
|
|||
void detectBrushedESC(void)
|
||||
{
|
||||
for (int i = 0; i < timerHardwareCount; i++) {
|
||||
if (timerHardware[i].usageFlags & TIM_USE_MC_MOTOR) {
|
||||
if (timerHardware[i].usageFlags & TIM_USE_MOTOR) {
|
||||
IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag);
|
||||
IOInit(MotorDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0);
|
||||
IOConfigGPIO(MotorDetectPin, IOCFG_IPU);
|
||||
|
|
|
@ -211,18 +211,17 @@ static bool checkPwmTimerConflicts(const timerHardware_t *timHw)
|
|||
}
|
||||
|
||||
static void timerHardwareOverride(timerHardware_t * timer) {
|
||||
|
||||
switch (timerOverrides(timer2id(timer->tim))->outputMode) {
|
||||
case OUTPUT_MODE_MOTORS:
|
||||
if (timer->usageFlags & (TIM_USE_MC_SERVO | TIM_USE_FW_SERVO)) {
|
||||
timer->usageFlags &= ~(TIM_USE_MC_SERVO | TIM_USE_FW_SERVO);
|
||||
timer->usageFlags |= TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR;
|
||||
if (TIM_IS_SERVO(timer->usageFlags)) {
|
||||
timer->usageFlags &= ~TIM_USE_SERVO;
|
||||
timer->usageFlags |= TIM_USE_MOTOR;
|
||||
}
|
||||
break;
|
||||
case OUTPUT_MODE_SERVOS:
|
||||
if (timer->usageFlags & (TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR)) {
|
||||
timer->usageFlags &= ~(TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR);
|
||||
timer->usageFlags |= TIM_USE_MC_SERVO | TIM_USE_FW_SERVO;
|
||||
if (TIM_IS_MOTOR(timer->usageFlags)) {
|
||||
timer->usageFlags &= ~TIM_USE_MOTOR;
|
||||
timer->usageFlags |= TIM_USE_SERVO;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -266,7 +265,6 @@ uint8_t pwmClaimTimer(HAL_Timer_t *tim, uint32_t usageFlags) {
|
|||
void pwmEnsureEnoughtMotors(uint8_t motorCount)
|
||||
{
|
||||
uint8_t motorOnlyOutputs = 0;
|
||||
uint8_t mcMotorOnlyOutputs = 0;
|
||||
|
||||
for (int idx = 0; idx < timerHardwareCount; idx++) {
|
||||
timerHardware_t *timHw = &timerHardware[idx];
|
||||
|
@ -277,49 +275,28 @@ void pwmEnsureEnoughtMotors(uint8_t motorCount)
|
|||
continue;
|
||||
}
|
||||
|
||||
if (timHw->usageFlags & (TIM_USE_MC_MOTOR) && !(timHw->usageFlags & (TIM_USE_MC_SERVO))) {
|
||||
mcMotorOnlyOutputs++;
|
||||
mcMotorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
}
|
||||
if (timHw->usageFlags & (TIM_USE_FW_MOTOR) && !(timHw->usageFlags & (TIM_USE_FW_SERVO))) {
|
||||
if (TIM_IS_MOTOR_ONLY(timHw->usageFlags)) {
|
||||
motorOnlyOutputs++;
|
||||
motorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
}
|
||||
}
|
||||
|
||||
if (mixerConfig()->platformType == PLATFORM_MULTIROTOR ||
|
||||
mixerConfig()->platformType == PLATFORM_TRICOPTER) {
|
||||
|
||||
for (int idx = 0; mcMotorOnlyOutputs < motorCount && idx < timerHardwareCount; idx++) {
|
||||
for (int idx = 0; idx < timerHardwareCount; idx++) {
|
||||
timerHardware_t *timHw = &timerHardware[idx];
|
||||
|
||||
if (checkPwmTimerConflicts(timHw)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
uint32_t mcFlags = timHw->usageFlags & (TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO);
|
||||
|
||||
if (mcFlags && mcFlags != TIM_USE_MC_MOTOR) {
|
||||
timHw->usageFlags &= ~TIM_USE_MC_SERVO;
|
||||
timHw->usageFlags |= TIM_USE_MC_MOTOR;
|
||||
mcMotorOnlyOutputs++;
|
||||
mcMotorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
}
|
||||
}
|
||||
if (TIM_IS_MOTOR(timHw->usageFlags) && !TIM_IS_MOTOR_ONLY(timHw->usageFlags)) {
|
||||
if (motorOnlyOutputs < motorCount) {
|
||||
timHw->usageFlags &= ~TIM_USE_SERVO;
|
||||
timHw->usageFlags |= TIM_USE_MOTOR;
|
||||
motorOnlyOutputs++;
|
||||
motorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
} else {
|
||||
for (int idx = 0; motorOnlyOutputs < motorCount && idx < timerHardwareCount; idx++) {
|
||||
timerHardware_t *timHw = &timerHardware[idx];
|
||||
|
||||
if (checkPwmTimerConflicts(timHw)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
uint32_t fwFlags = timHw->usageFlags & (TIM_USE_FW_MOTOR | TIM_USE_FW_SERVO);
|
||||
if (fwFlags && fwFlags != TIM_USE_FW_MOTOR) {
|
||||
timHw->usageFlags &= ~TIM_USE_FW_SERVO;
|
||||
timHw->usageFlags |= TIM_USE_FW_MOTOR;
|
||||
motorOnlyOutputs++;
|
||||
motorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
timHw->usageFlags &= ~TIM_USE_MOTOR;
|
||||
pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -327,6 +304,7 @@ void pwmEnsureEnoughtMotors(uint8_t motorCount)
|
|||
|
||||
void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos)
|
||||
{
|
||||
UNUSED(isMixerUsingServos);
|
||||
timOutputs->maxTimMotorCount = 0;
|
||||
timOutputs->maxTimServoCount = 0;
|
||||
|
||||
|
@ -338,8 +316,6 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU
|
|||
for (int idx = 0; idx < timerHardwareCount; idx++) {
|
||||
timerHardware_t *timHw = &timerHardware[idx];
|
||||
|
||||
timerHardwareOverride(timHw);
|
||||
|
||||
int type = MAP_TO_NONE;
|
||||
|
||||
// Check for known conflicts (i.e. UART, LEDSTRIP, Rangefinder and ADC)
|
||||
|
@ -348,47 +324,27 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU
|
|||
continue;
|
||||
}
|
||||
|
||||
// Determine if timer belongs to motor/servo
|
||||
if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) {
|
||||
// Multicopter
|
||||
|
||||
// Make sure first motorCount outputs get assigned to motor
|
||||
if ((timHw->usageFlags & TIM_USE_MC_MOTOR) && (motorIdx < motorCount)) {
|
||||
timHw->usageFlags = timHw->usageFlags & ~TIM_USE_MC_SERVO;
|
||||
pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
motorIdx += 1;
|
||||
}
|
||||
|
||||
// We enable mapping to servos if mixer is actually using them and it does not conflict with used motors
|
||||
if (isMixerUsingServos && timHw->usageFlags & TIM_USE_MC_SERVO && !pwmHasMotorOnTimer(timOutputs, timHw->tim)) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
} else if (timHw->usageFlags & TIM_USE_MC_MOTOR && !pwmHasServoOnTimer(timOutputs, timHw->tim)) {
|
||||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
}
|
||||
} else {
|
||||
// Make sure first motorCount motor outputs get assigned to motor
|
||||
if ((timHw->usageFlags & TIM_USE_FW_MOTOR) && (motorIdx < motorCount)) {
|
||||
timHw->usageFlags = timHw->usageFlags & ~TIM_USE_FW_SERVO;
|
||||
if (TIM_IS_MOTOR(timHw->usageFlags) && (motorIdx < motorCount)) {
|
||||
timHw->usageFlags &= ~TIM_USE_SERVO;
|
||||
pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
motorIdx += 1;
|
||||
}
|
||||
|
||||
// Fixed wing or HELI (one/two motors and a lot of servos
|
||||
if (timHw->usageFlags & TIM_USE_FW_SERVO && !pwmHasMotorOnTimer(timOutputs, timHw->tim)) {
|
||||
if (TIM_IS_SERVO(timHw->usageFlags) && !pwmHasMotorOnTimer(timOutputs, timHw->tim)) {
|
||||
type = MAP_TO_SERVO_OUTPUT;
|
||||
} else if (timHw->usageFlags & TIM_USE_FW_MOTOR && !pwmHasServoOnTimer(timOutputs, timHw->tim)) {
|
||||
} else if (TIM_IS_MOTOR(timHw->usageFlags) && !pwmHasServoOnTimer(timOutputs, timHw->tim)) {
|
||||
type = MAP_TO_MOTOR_OUTPUT;
|
||||
}
|
||||
}
|
||||
|
||||
switch(type) {
|
||||
case MAP_TO_MOTOR_OUTPUT:
|
||||
timHw->usageFlags &= (TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR);
|
||||
timHw->usageFlags &= TIM_USE_MOTOR;
|
||||
timOutputs->timMotors[timOutputs->maxTimMotorCount++] = timHw;
|
||||
pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
break;
|
||||
case MAP_TO_SERVO_OUTPUT:
|
||||
timHw->usageFlags &= (TIM_USE_MC_SERVO | TIM_USE_FW_SERVO);
|
||||
timHw->usageFlags &= TIM_USE_SERVO;
|
||||
timOutputs->timServos[timOutputs->maxTimServoCount++] = timHw;
|
||||
pwmClaimTimer(timHw->tim, timHw->usageFlags);
|
||||
break;
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
|
||||
#include "drivers/io_types.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#if defined(TARGET_MOTOR_COUNT)
|
||||
|
|
|
@ -119,6 +119,7 @@ static bool pwmMotorsEnabled = true;
|
|||
static timeUs_t digitalMotorUpdateIntervalUs = 0;
|
||||
static timeUs_t digitalMotorLastUpdateUs;
|
||||
static timeUs_t lastCommandSent = 0;
|
||||
static timeUs_t commandPostDelay = 0;
|
||||
|
||||
static circularBuffer_t commandsCircularBuffer;
|
||||
static uint8_t commandsBuff[DHSOT_COMMAND_QUEUE_SIZE];
|
||||
|
@ -419,7 +420,7 @@ static int getDShotCommandRepeats(dshotCommands_e cmd) {
|
|||
return repeats;
|
||||
}
|
||||
|
||||
static void executeDShotCommands(void){
|
||||
static bool executeDShotCommands(void){
|
||||
|
||||
timeUs_t tNow = micros();
|
||||
|
||||
|
@ -431,17 +432,29 @@ static void executeDShotCommands(void){
|
|||
circularBufferPopHead(&commandsCircularBuffer, (uint8_t *) &cmd);
|
||||
currentExecutingCommand.cmd = cmd;
|
||||
currentExecutingCommand.remainingRepeats = getDShotCommandRepeats(cmd);
|
||||
commandPostDelay = DSHOT_COMMAND_INTERVAL_US;
|
||||
} else {
|
||||
return;
|
||||
if (commandPostDelay) {
|
||||
if (tNow - lastCommandSent < commandPostDelay) {
|
||||
return false;
|
||||
}
|
||||
commandPostDelay = 0;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
delayMicroseconds(DSHOT_COMMAND_DELAY_US);
|
||||
for (uint8_t i = 0; i < getMotorCount(); i++) {
|
||||
motors[i].requestTelemetry = true;
|
||||
motors[i].value = currentExecutingCommand.cmd;
|
||||
}
|
||||
if (tNow - lastCommandSent >= DSHOT_COMMAND_DELAY_US) {
|
||||
currentExecutingCommand.remainingRepeats--;
|
||||
lastCommandSent = tNow;
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -464,7 +477,9 @@ void pwmCompleteMotorUpdate(void) {
|
|||
#ifdef USE_DSHOT
|
||||
if (isMotorProtocolDshot()) {
|
||||
|
||||
executeDShotCommands();
|
||||
if (!executeDShotCommands()) {
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
for (int index = 0; index < motorCount; index++) {
|
||||
|
|
|
@ -110,16 +110,22 @@ typedef enum {
|
|||
TIM_USE_ANY = 0,
|
||||
TIM_USE_PPM = (1 << 0),
|
||||
TIM_USE_PWM = (1 << 1),
|
||||
TIM_USE_MC_MOTOR = (1 << 2), // Multicopter motor output
|
||||
TIM_USE_MC_SERVO = (1 << 3), // Multicopter servo output (i.e. TRI)
|
||||
TIM_USE_MOTOR = (1 << 2), // Motor output
|
||||
TIM_USE_SERVO = (1 << 3), // Servo output
|
||||
TIM_USE_MC_CHNFW = (1 << 4), // Deprecated and not used after removal of CHANNEL_FORWARDING feature
|
||||
TIM_USE_FW_MOTOR = (1 << 5),
|
||||
TIM_USE_FW_SERVO = (1 << 6),
|
||||
//TIM_USE_FW_MOTOR = (1 << 5), // We no longer differentiate mc from fw on pwm allocation
|
||||
//TIM_USE_FW_SERVO = (1 << 6),
|
||||
TIM_USE_LED = (1 << 24),
|
||||
TIM_USE_BEEPER = (1 << 25),
|
||||
} timerUsageFlag_e;
|
||||
|
||||
#define TIM_USE_OUTPUT_AUTO (TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR | TIM_USE_FW_SERVO)
|
||||
#define TIM_USE_OUTPUT_AUTO (TIM_USE_MOTOR | TIM_USE_SERVO)
|
||||
|
||||
#define TIM_IS_MOTOR(flags) ((flags) & TIM_USE_MOTOR)
|
||||
#define TIM_IS_SERVO(flags) ((flags) & TIM_USE_SERVO)
|
||||
|
||||
#define TIM_IS_MOTOR_ONLY(flags) (TIM_IS_MOTOR(flags) && !TIM_IS_SERVO(flags))
|
||||
#define TIM_IS_SERVO_ONLY(flags) (!TIM_IS_MOTOR(flags) && TIM_IS_SERVO(flags))
|
||||
|
||||
enum {
|
||||
TIMER_OUTPUT_NONE = 0x00,
|
||||
|
|
|
@ -301,7 +301,12 @@ bool impl_timerPWMConfigChannelDMA(TCH_t * tch, void * dmaBuffer, uint8_t dmaBuf
|
|||
TIM_CtrlPWMOutputs(timer, ENABLE);
|
||||
TIM_ARRPreloadConfig(timer, ENABLE);
|
||||
|
||||
if (tch->timHw->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||
TIM_CCxNCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCxN_Enable);
|
||||
} else {
|
||||
TIM_CCxCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCx_Enable);
|
||||
}
|
||||
|
||||
TIM_Cmd(timer, ENABLE);
|
||||
|
||||
dmaInit(tch->dma, OWNER_TIMER, 0);
|
||||
|
@ -382,7 +387,12 @@ bool impl_timerPWMConfigDMABurst(burstDmaTimer_t *burstDmaTimer, TCH_t * tch, vo
|
|||
TIM_CtrlPWMOutputs(timer, ENABLE);
|
||||
TIM_ARRPreloadConfig(timer, ENABLE);
|
||||
|
||||
if (tch->timHw->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||
TIM_CCxNCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCxN_Enable);
|
||||
} else {
|
||||
TIM_CCxCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCx_Enable);
|
||||
}
|
||||
|
||||
TIM_Cmd(timer, ENABLE);
|
||||
|
||||
if (!tch->timCtx->dmaBurstRef) {
|
||||
|
|
|
@ -81,7 +81,7 @@ bool cliMode = false;
|
|||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
|
@ -289,7 +289,7 @@ typedef enum {
|
|||
DUMP_MASTER = (1 << 0),
|
||||
DUMP_PROFILE = (1 << 1),
|
||||
DUMP_BATTERY_PROFILE = (1 << 2),
|
||||
DUMP_RATES = (1 << 3),
|
||||
DUMP_MIXER_PROFILE = (1 << 3),
|
||||
DUMP_ALL = (1 << 4),
|
||||
DO_DIFF = (1 << 5),
|
||||
SHOW_DEFAULTS = (1 << 6),
|
||||
|
@ -1869,7 +1869,7 @@ static void cliServoMix(char *cmdline)
|
|||
printServoMix(DUMP_MASTER, customServoMixers(0), NULL);
|
||||
} else if (sl_strncasecmp(cmdline, "reset", 5) == 0) {
|
||||
// erase custom mixer
|
||||
pgResetCopy(customServoMixersMutable(0), PG_SERVO_MIXER);
|
||||
Reset_servoMixers(customServoMixersMutable(0));
|
||||
} else {
|
||||
enum {RULE = 0, TARGET, INPUT, RATE, SPEED, CONDITION, ARGS_COUNT};
|
||||
char *ptr = strtok_r(cmdline, " ", &saveptr);
|
||||
|
@ -3132,6 +3132,39 @@ static void cliDumpBatteryProfile(uint8_t profileIndex, uint8_t dumpMask)
|
|||
dumpAllValues(BATTERY_CONFIG_VALUE, dumpMask);
|
||||
}
|
||||
|
||||
static void cliMixerProfile(char *cmdline)
|
||||
{
|
||||
// CLI profile index is 1-based
|
||||
if (isEmpty(cmdline)) {
|
||||
cliPrintLinef("mixer_profile %d", getConfigMixerProfile() + 1);
|
||||
return;
|
||||
} else {
|
||||
const int i = fastA2I(cmdline) - 1;
|
||||
if (i >= 0 && i < MAX_MIXER_PROFILE_COUNT) {
|
||||
setConfigMixerProfileAndWriteEEPROM(i);
|
||||
cliMixerProfile("");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void cliDumpMixerProfile(uint8_t profileIndex, uint8_t dumpMask)
|
||||
{
|
||||
if (profileIndex >= MAX_MIXER_PROFILE_COUNT) {
|
||||
// Faulty values
|
||||
return;
|
||||
}
|
||||
setConfigMixerProfile(profileIndex);
|
||||
cliPrintHashLine("mixer_profile");
|
||||
cliPrintLinef("mixer_profile %d\r\n", getConfigMixerProfile() + 1);
|
||||
dumpAllValues(MIXER_CONFIG_VALUE, dumpMask);
|
||||
cliPrintHashLine("Mixer: motor mixer");
|
||||
cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray()[0].throttle == 0.0f, "\r\nmmix reset\r\n");
|
||||
printMotorMix(dumpMask, primaryMotorMixer_CopyArray(), primaryMotorMixer(0));
|
||||
cliPrintHashLine("Mixer: servo mixer");
|
||||
cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray()[0].rate == 0, "smix reset\r\n");
|
||||
printServoMix(dumpMask, customServoMixers_CopyArray(), customServoMixers(0));
|
||||
}
|
||||
|
||||
#ifdef USE_CLI_BATCH
|
||||
static void cliPrintCommandBatchWarning(const char *warning)
|
||||
{
|
||||
|
@ -3687,6 +3720,8 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
dumpMask = DUMP_PROFILE; // only
|
||||
} else if ((options = checkCommand(cmdline, "battery_profile"))) {
|
||||
dumpMask = DUMP_BATTERY_PROFILE; // only
|
||||
} else if ((options = checkCommand(cmdline, "mixer_profile"))) {
|
||||
dumpMask = DUMP_MIXER_PROFILE; // only
|
||||
} else if ((options = checkCommand(cmdline, "all"))) {
|
||||
dumpMask = DUMP_ALL; // all profiles and rates
|
||||
} else {
|
||||
|
@ -3699,12 +3734,14 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
|
||||
const int currentProfileIndexSave = getConfigProfile();
|
||||
const int currentBatteryProfileIndexSave = getConfigBatteryProfile();
|
||||
const int currentMixerProfileIndexSave = getConfigMixerProfile();
|
||||
backupConfigs();
|
||||
// reset all configs to defaults to do differencing
|
||||
resetConfigs();
|
||||
// restore the profile indices, since they should not be reset for proper comparison
|
||||
setConfigProfile(currentProfileIndexSave);
|
||||
setConfigBatteryProfile(currentBatteryProfileIndexSave);
|
||||
setConfigMixerProfile(currentMixerProfileIndexSave);
|
||||
|
||||
if (checkCommand(options, "showdefaults")) {
|
||||
dumpMask = dumpMask | SHOW_DEFAULTS; // add default values as comments for changed values
|
||||
|
@ -3738,16 +3775,6 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
cliPrintHashLine("Timer overrides");
|
||||
printTimerOutputModes(dumpMask, timerOverrides_CopyArray, timerOverrides(0), -1);
|
||||
|
||||
cliPrintHashLine("Mixer: motor mixer");
|
||||
cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray[0].throttle == 0.0f, "\r\nmmix reset\r\n");
|
||||
|
||||
printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0));
|
||||
|
||||
// print custom servo mixer if exists
|
||||
cliPrintHashLine("Mixer: servo mixer");
|
||||
cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n");
|
||||
printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0));
|
||||
|
||||
// print servo parameters
|
||||
cliPrintHashLine("Outputs [servo]");
|
||||
printServo(dumpMask, servoParams_CopyArray, servoParams(0));
|
||||
|
@ -3829,6 +3856,10 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
// dump all profiles
|
||||
const int currentProfileIndexSave = getConfigProfile();
|
||||
const int currentBatteryProfileIndexSave = getConfigBatteryProfile();
|
||||
const int currentMixerProfileIndexSave = getConfigMixerProfile();
|
||||
for (int ii = 0; ii < MAX_MIXER_PROFILE_COUNT; ++ii) {
|
||||
cliDumpMixerProfile(ii, dumpMask);
|
||||
}
|
||||
for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) {
|
||||
cliDumpProfile(ii, dumpMask);
|
||||
}
|
||||
|
@ -3837,8 +3868,10 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
}
|
||||
setConfigProfile(currentProfileIndexSave);
|
||||
setConfigBatteryProfile(currentBatteryProfileIndexSave);
|
||||
setConfigMixerProfile(currentMixerProfileIndexSave);
|
||||
|
||||
cliPrintHashLine("restore original profile selection");
|
||||
cliPrintLinef("mixer_profile %d", currentMixerProfileIndexSave + 1);
|
||||
cliPrintLinef("profile %d", currentProfileIndexSave + 1);
|
||||
cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1);
|
||||
|
||||
|
@ -3847,10 +3880,14 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
#endif
|
||||
} else {
|
||||
// dump just the current profiles
|
||||
cliDumpMixerProfile(getConfigMixerProfile(), dumpMask);
|
||||
cliDumpProfile(getConfigProfile(), dumpMask);
|
||||
cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask);
|
||||
}
|
||||
}
|
||||
if (dumpMask & DUMP_MIXER_PROFILE) {
|
||||
cliDumpMixerProfile(getConfigMixerProfile(), dumpMask);
|
||||
}
|
||||
|
||||
if (dumpMask & DUMP_PROFILE) {
|
||||
cliDumpProfile(getConfigProfile(), dumpMask);
|
||||
|
@ -4011,6 +4048,8 @@ const clicmd_t cmdTable[] = {
|
|||
"[<index>]", cliProfile),
|
||||
CLI_COMMAND_DEF("battery_profile", "change battery profile",
|
||||
"[<index>]", cliBatteryProfile),
|
||||
CLI_COMMAND_DEF("mixer_profile", "change mixer profile",
|
||||
"[<index>]", cliMixerProfile),
|
||||
CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
|
||||
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
|
||||
#if defined(USE_SAFE_HOME)
|
||||
|
|
|
@ -107,6 +107,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG,
|
|||
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
|
||||
.current_profile_index = 0,
|
||||
.current_battery_profile_index = 0,
|
||||
.current_mixer_profile_index = 0,
|
||||
.debug_mode = SETTING_DEBUG_MODE_DEFAULT,
|
||||
#ifdef USE_DEV_TOOLS
|
||||
.groundTestMode = SETTING_GROUND_TEST_MODE_DEFAULT, // disables motors, set heading trusted for FW (for dev use)
|
||||
|
@ -304,6 +305,7 @@ static void activateConfig(void)
|
|||
{
|
||||
activateControlRateConfig();
|
||||
activateBatteryProfile();
|
||||
activateMixerConfig();
|
||||
|
||||
resetAdjustmentStates();
|
||||
|
||||
|
@ -330,6 +332,7 @@ void readEEPROM(void)
|
|||
|
||||
setConfigProfile(getConfigProfile());
|
||||
setConfigBatteryProfile(getConfigBatteryProfile());
|
||||
setConfigMixerProfile(getConfigMixerProfile());
|
||||
|
||||
validateAndFixConfig();
|
||||
activateConfig();
|
||||
|
@ -469,6 +472,36 @@ void setConfigBatteryProfileAndWriteEEPROM(uint8_t profileIndex)
|
|||
beeperConfirmationBeeps(profileIndex + 1);
|
||||
}
|
||||
|
||||
uint8_t getConfigMixerProfile(void)
|
||||
{
|
||||
return systemConfig()->current_mixer_profile_index;
|
||||
}
|
||||
|
||||
bool setConfigMixerProfile(uint8_t profileIndex)
|
||||
{
|
||||
bool ret = true; // return true if current_mixer_profile_index has changed
|
||||
if (systemConfig()->current_mixer_profile_index == profileIndex) {
|
||||
ret = false;
|
||||
}
|
||||
if (profileIndex >= MAX_MIXER_PROFILE_COUNT) {// sanity check
|
||||
profileIndex = 0;
|
||||
}
|
||||
systemConfigMutable()->current_mixer_profile_index = profileIndex;
|
||||
return ret;
|
||||
}
|
||||
|
||||
void setConfigMixerProfileAndWriteEEPROM(uint8_t profileIndex)
|
||||
{
|
||||
if (setConfigMixerProfile(profileIndex)) {
|
||||
// profile has changed, so ensure current values saved before new profile is loaded
|
||||
suspendRxSignal();
|
||||
writeEEPROM();
|
||||
readEEPROM();
|
||||
resumeRxSignal();
|
||||
}
|
||||
beeperConfirmationBeeps(profileIndex + 1);
|
||||
}
|
||||
|
||||
void setGyroCalibration(float getGyroZero[XYZ_AXIS_COUNT])
|
||||
{
|
||||
gyroConfigMutable()->gyro_zero_cal[X] = (int16_t) getGyroZero[X];
|
||||
|
|
|
@ -36,7 +36,7 @@ typedef enum {
|
|||
FEATURE_VBAT = 1 << 1,
|
||||
FEATURE_TX_PROF_SEL = 1 << 2, // Profile selection by TX stick command
|
||||
FEATURE_BAT_PROFILE_AUTOSWITCH = 1 << 3,
|
||||
FEATURE_MOTOR_STOP = 1 << 4,
|
||||
FEATURE_UNUSED_12 = 1 << 4, //was FEATURE_MOTOR_STOP
|
||||
FEATURE_UNUSED_1 = 1 << 5, // was FEATURE_SERVO_TILT was FEATURE_DYNAMIC_FILTERS
|
||||
FEATURE_SOFTSERIAL = 1 << 6,
|
||||
FEATURE_GPS = 1 << 7,
|
||||
|
@ -69,6 +69,7 @@ typedef enum {
|
|||
typedef struct systemConfig_s {
|
||||
uint8_t current_profile_index;
|
||||
uint8_t current_battery_profile_index;
|
||||
uint8_t current_mixer_profile_index;
|
||||
uint8_t debug_mode;
|
||||
#ifdef USE_DEV_TOOLS
|
||||
bool groundTestMode; // Disables motor ouput, sets heading trusted on FW (for dev use)
|
||||
|
@ -138,6 +139,10 @@ uint8_t getConfigBatteryProfile(void);
|
|||
bool setConfigBatteryProfile(uint8_t profileIndex);
|
||||
void setConfigBatteryProfileAndWriteEEPROM(uint8_t profileIndex);
|
||||
|
||||
uint8_t getConfigMixerProfile(void);
|
||||
bool setConfigMixerProfile(uint8_t profileIndex);
|
||||
void setConfigMixerProfileAndWriteEEPROM(uint8_t profileIndex);
|
||||
|
||||
void setGyroCalibration(float getGyroZero[XYZ_AXIS_COUNT]);
|
||||
void setGravityCalibration(float getGravity);
|
||||
|
||||
|
|
17
src/main/fc/fc_core.c
Executable file → Normal file
17
src/main/fc/fc_core.c
Executable file → Normal file
|
@ -81,6 +81,7 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer_profile.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
|
@ -618,7 +619,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
const bool throttleIsLow = throttleStickIsLow();
|
||||
|
||||
// When armed and motors aren't spinning, do beeps periodically
|
||||
if (ARMING_FLAG(ARMED) && feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY)) {
|
||||
if (ARMING_FLAG(ARMED) && ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY)) {
|
||||
static bool armedBeeperOn = false;
|
||||
|
||||
if (throttleIsLow) {
|
||||
|
@ -692,12 +693,12 @@ void processRx(timeUs_t currentTimeUs)
|
|||
|
||||
#if defined(USE_MAG)
|
||||
if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXHEADFREE)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXHEADFREE) && STATE(MULTIROTOR)) {
|
||||
ENABLE_FLIGHT_MODE(HEADFREE_MODE);
|
||||
} else {
|
||||
DISABLE_FLIGHT_MODE(HEADFREE_MODE);
|
||||
}
|
||||
if (IS_RC_MODE_ACTIVE(BOXHEADADJ)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXHEADADJ) && STATE(MULTIROTOR)) {
|
||||
headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); // acquire new heading
|
||||
}
|
||||
}
|
||||
|
@ -711,6 +712,8 @@ void processRx(timeUs_t currentTimeUs)
|
|||
} else {
|
||||
DISABLE_FLIGHT_MODE(MANUAL_MODE);
|
||||
}
|
||||
}else{
|
||||
DISABLE_FLIGHT_MODE(MANUAL_MODE);
|
||||
}
|
||||
|
||||
/* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered.
|
||||
|
@ -730,8 +733,8 @@ void processRx(timeUs_t currentTimeUs)
|
|||
}
|
||||
else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) {
|
||||
if (throttleIsLow) {
|
||||
if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) {
|
||||
if ((rollPitchStatus == CENTERED) || (feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY))) {
|
||||
if (STATE(AIRMODE_ACTIVE)) {
|
||||
if ((rollPitchStatus == CENTERED) || (ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY))) {
|
||||
ENABLE_STATE(ANTI_WINDUP);
|
||||
}
|
||||
else {
|
||||
|
@ -749,7 +752,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
}
|
||||
else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE) {
|
||||
if (throttleIsLow) {
|
||||
if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) {
|
||||
if (STATE(AIRMODE_ACTIVE)) {
|
||||
if ((rollPitchStatus == CENTERED) && !STATE(ANTI_WINDUP_DEACTIVATED)) {
|
||||
ENABLE_STATE(ANTI_WINDUP);
|
||||
}
|
||||
|
@ -777,7 +780,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
}
|
||||
}
|
||||
//---------------------------------------------------------
|
||||
if (mixerConfig()->platformType == PLATFORM_AIRPLANE) {
|
||||
if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) {
|
||||
DISABLE_FLIGHT_MODE(HEADFREE_MODE);
|
||||
}
|
||||
|
||||
|
|
|
@ -304,9 +304,7 @@ void init(void)
|
|||
|
||||
// Initialize servo and motor mixers
|
||||
// This needs to be called early to set up platform type correctly and count required motors & servos
|
||||
servosInit();
|
||||
mixerUpdateStateFlags();
|
||||
mixerInit();
|
||||
mixerConfigInit();
|
||||
|
||||
// Some sanity checking
|
||||
if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
||||
|
|
|
@ -74,6 +74,7 @@
|
|||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
@ -1465,7 +1466,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
|
||||
case MSP2_INAV_MIXER:
|
||||
sbufWriteU8(dst, mixerConfig()->motorDirectionInverted);
|
||||
sbufWriteU16(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, mixerConfig()->motorstopOnLow);
|
||||
sbufWriteU8(dst, mixerConfig()->platformType);
|
||||
sbufWriteU8(dst, mixerConfig()->hasFlaps);
|
||||
sbufWriteU16(dst, mixerConfig()->appliedMixerPreset);
|
||||
|
@ -1580,6 +1582,21 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
break;
|
||||
#endif
|
||||
|
||||
#ifdef USE_RATE_DYNAMICS
|
||||
|
||||
case MSP2_INAV_RATE_DYNAMICS:
|
||||
{
|
||||
sbufWriteU8(dst, currentControlRateProfile->rateDynamics.sensitivityCenter);
|
||||
sbufWriteU8(dst, currentControlRateProfile->rateDynamics.sensitivityEnd);
|
||||
sbufWriteU8(dst, currentControlRateProfile->rateDynamics.correctionCenter);
|
||||
sbufWriteU8(dst, currentControlRateProfile->rateDynamics.correctionEnd);
|
||||
sbufWriteU8(dst, currentControlRateProfile->rateDynamics.weightCenter);
|
||||
sbufWriteU8(dst, currentControlRateProfile->rateDynamics.weightEnd);
|
||||
}
|
||||
break;
|
||||
|
||||
#endif
|
||||
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
@ -2866,7 +2883,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
case MSP2_INAV_SET_MIXER:
|
||||
if (dataSize == 9) {
|
||||
mixerConfigMutable()->motorDirectionInverted = sbufReadU8(src);
|
||||
sbufReadU16(src); // Was yaw_jump_prevention_limit
|
||||
sbufReadU8(src); // Was yaw_jump_prevention_limit
|
||||
mixerConfigMutable()->motorstopOnLow = sbufReadU8(src);
|
||||
mixerConfigMutable()->platformType = sbufReadU8(src);
|
||||
mixerConfigMutable()->hasFlaps = sbufReadU8(src);
|
||||
mixerConfigMutable()->appliedMixerPreset = sbufReadU16(src);
|
||||
|
@ -3037,6 +3055,27 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#ifdef USE_RATE_DYNAMICS
|
||||
|
||||
case MSP2_INAV_SET_RATE_DYNAMICS:
|
||||
|
||||
if (dataSize == 6) {
|
||||
((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.sensitivityCenter = sbufReadU8(src);
|
||||
((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.sensitivityEnd = sbufReadU8(src);
|
||||
((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.correctionCenter = sbufReadU8(src);
|
||||
((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.correctionEnd = sbufReadU8(src);
|
||||
((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.weightCenter = sbufReadU8(src);
|
||||
((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.weightEnd = sbufReadU8(src);
|
||||
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
default:
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
@ -3230,6 +3269,10 @@ static bool mspSettingInfoCommand(sbuf_t *dst, sbuf_t *src)
|
|||
sbufWriteU8(dst, getConfigBatteryProfile());
|
||||
sbufWriteU8(dst, MAX_BATTERY_PROFILE_COUNT);
|
||||
break;
|
||||
case MIXER_CONFIG_VALUE:
|
||||
sbufWriteU8(dst, getConfigMixerProfile());
|
||||
sbufWriteU8(dst, MAX_MIXER_PROFILE_COUNT);
|
||||
break;
|
||||
}
|
||||
|
||||
// If the setting uses a table, send each possible string (null terminated)
|
||||
|
|
|
@ -30,6 +30,7 @@
|
|||
#include "fc/fc_msp_box.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
|
||||
#include "io/osd.h"
|
||||
|
||||
|
@ -99,7 +100,9 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
|
|||
{ .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 59 },
|
||||
{ .boxId = BOXBEEPERMUTE, .boxName = "BEEPER MUTE", .permanentId = 60 },
|
||||
{ .boxId = BOXMULTIFUNCTION, .boxName = "MULTI FUNCTION", .permanentId = 61 },
|
||||
{ .boxId = BOXATTIHOLD, .boxName = "ATTITUDE HOLD", .permanentId = 62 },
|
||||
{ .boxId = BOXMIXERPROFILE, .boxName = "MIXER PROFILE 2", .permanentId = 62 },
|
||||
{ .boxId = BOXMIXERTRANSITION, .boxName = "MIXER TRANSITION", .permanentId = 63 },
|
||||
{ .boxId = BOXATTIHOLD, .boxName = "ATTITUDE HOLD", .permanentId = 64 },
|
||||
{ .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF }
|
||||
};
|
||||
|
||||
|
@ -200,7 +203,7 @@ void initActiveBoxIds(void)
|
|||
//Camstab mode is enabled always
|
||||
ADD_ACTIVE_BOX(BOXCAMSTAB);
|
||||
|
||||
if (STATE(MULTIROTOR)) {
|
||||
if (STATE(MULTIROTOR) || platformTypeConfigured(PLATFORM_MULTIROTOR) || platformTypeConfigured(PLATFORM_TRICOPTER)) {
|
||||
if ((sensors(SENSOR_ACC) || sensors(SENSOR_MAG))) {
|
||||
ADD_ACTIVE_BOX(BOXHEADFREE);
|
||||
ADD_ACTIVE_BOX(BOXHEADADJ);
|
||||
|
@ -242,13 +245,13 @@ void initActiveBoxIds(void)
|
|||
#endif
|
||||
}
|
||||
|
||||
if (STATE(AIRPLANE)) {
|
||||
if (STATE(AIRPLANE) || platformTypeConfigured(PLATFORM_AIRPLANE)) {
|
||||
ADD_ACTIVE_BOX(BOXSOARING);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_MR_BRAKING_MODE
|
||||
if (mixerConfig()->platformType == PLATFORM_MULTIROTOR) {
|
||||
if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || platformTypeConfigured(PLATFORM_MULTIROTOR)) {
|
||||
ADD_ACTIVE_BOX(BOXBRAKING);
|
||||
}
|
||||
#endif
|
||||
|
@ -257,11 +260,12 @@ void initActiveBoxIds(void)
|
|||
ADD_ACTIVE_BOX(BOXNAVALTHOLD);
|
||||
}
|
||||
|
||||
if (STATE(AIRPLANE) || STATE(ROVER) || STATE(BOAT)) {
|
||||
if (STATE(AIRPLANE) || STATE(ROVER) || STATE(BOAT) ||
|
||||
platformTypeConfigured(PLATFORM_AIRPLANE) || platformTypeConfigured(PLATFORM_ROVER) || platformTypeConfigured(PLATFORM_BOAT)) {
|
||||
ADD_ACTIVE_BOX(BOXMANUAL);
|
||||
}
|
||||
|
||||
if (STATE(AIRPLANE)) {
|
||||
if (STATE(AIRPLANE) || platformTypeConfigured(PLATFORM_AIRPLANE)) {
|
||||
if (!feature(FEATURE_FW_LAUNCH)) {
|
||||
ADD_ACTIVE_BOX(BOXNAVLAUNCH);
|
||||
}
|
||||
|
@ -354,6 +358,11 @@ void initActiveBoxIds(void)
|
|||
ADD_ACTIVE_BOX(BOXTURTLE);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if (MAX_MIXER_PROFILE_COUNT > 1)
|
||||
ADD_ACTIVE_BOX(BOXMIXERPROFILE);
|
||||
ADD_ACTIVE_BOX(BOXMIXERTRANSITION);
|
||||
#endif
|
||||
}
|
||||
|
||||
#define IS_ENABLED(mask) ((mask) == 0 ? 0 : 1)
|
||||
|
@ -422,6 +431,10 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags)
|
|||
#endif
|
||||
#ifdef USE_MULTI_FUNCTIONS
|
||||
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMULTIFUNCTION)), BOXMULTIFUNCTION);
|
||||
#endif
|
||||
#if (MAX_MIXER_PROFILE_COUNT > 1)
|
||||
CHECK_ACTIVE_BOX(IS_ENABLED(currentMixerProfileIndex), BOXMIXERPROFILE);
|
||||
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION)), BOXMIXERTRANSITION);
|
||||
#endif
|
||||
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXATTIHOLD)), BOXATTIHOLD);
|
||||
memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t));
|
||||
|
|
|
@ -51,6 +51,7 @@
|
|||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/beeper.h"
|
||||
|
@ -213,7 +214,7 @@ void processRcStickPositions(bool isThrottleLow)
|
|||
// perform actions
|
||||
bool armingSwitchIsActive = IS_RC_MODE_ACTIVE(BOXARM);
|
||||
|
||||
if (STATE(AIRPLANE) && feature(FEATURE_MOTOR_STOP) && armingConfig()->fixed_wing_auto_arm) {
|
||||
if (STATE(AIRPLANE) && ifMotorstopFeatureEnabled() && armingConfig()->fixed_wing_auto_arm) {
|
||||
// Auto arm on throttle when using fixedwing and motorstop
|
||||
if (!isThrottleLow) {
|
||||
tryArm();
|
||||
|
|
|
@ -79,7 +79,9 @@ typedef enum {
|
|||
BOXCHANGEMISSION = 50,
|
||||
BOXBEEPERMUTE = 51,
|
||||
BOXMULTIFUNCTION = 52,
|
||||
BOXATTIHOLD = 53,
|
||||
BOXMIXERPROFILE = 53,
|
||||
BOXMIXERTRANSITION = 54,
|
||||
BOXATTIHOLD = 55,
|
||||
CHECKBOX_ITEM_COUNT
|
||||
} boxId_e;
|
||||
|
||||
|
|
|
@ -239,6 +239,8 @@ static uint16_t getValueOffset(const setting_t *value)
|
|||
return value->offset + sizeof(controlRateConfig_t) * getConfigProfile();
|
||||
case BATTERY_CONFIG_VALUE:
|
||||
return value->offset + sizeof(batteryProfile_t) * getConfigBatteryProfile();
|
||||
case MIXER_CONFIG_VALUE:
|
||||
return value->offset + sizeof(mixerProfile_t) * getConfigMixerProfile();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -14,11 +14,11 @@ typedef struct lookupTableEntry_s {
|
|||
} lookupTableEntry_t;
|
||||
|
||||
#define SETTING_TYPE_OFFSET 0
|
||||
#define SETTING_SECTION_OFFSET 4
|
||||
#define SETTING_SECTION_OFFSET 3
|
||||
#define SETTING_MODE_OFFSET 6
|
||||
|
||||
typedef enum {
|
||||
// value type, bits 0-3
|
||||
// value type, bits 0-2
|
||||
VAR_UINT8 = (0 << SETTING_TYPE_OFFSET),
|
||||
VAR_INT8 = (1 << SETTING_TYPE_OFFSET),
|
||||
VAR_UINT16 = (2 << SETTING_TYPE_OFFSET),
|
||||
|
@ -29,11 +29,12 @@ typedef enum {
|
|||
} setting_type_e;
|
||||
|
||||
typedef enum {
|
||||
// value section, bits 4-5
|
||||
// value section, bits 3-5
|
||||
MASTER_VALUE = (0 << SETTING_SECTION_OFFSET),
|
||||
PROFILE_VALUE = (1 << SETTING_SECTION_OFFSET),
|
||||
CONTROL_RATE_VALUE = (2 << SETTING_SECTION_OFFSET), // 0x20
|
||||
CONTROL_RATE_VALUE = (2 << SETTING_SECTION_OFFSET),
|
||||
BATTERY_CONFIG_VALUE = (3 << SETTING_SECTION_OFFSET),
|
||||
MIXER_CONFIG_VALUE = (4 << SETTING_SECTION_OFFSET),
|
||||
} setting_section_e;
|
||||
|
||||
typedef enum {
|
||||
|
@ -42,8 +43,9 @@ typedef enum {
|
|||
MODE_LOOKUP = (1 << SETTING_MODE_OFFSET), // 0x40
|
||||
} setting_mode_e;
|
||||
|
||||
#define SETTING_TYPE_MASK (0x0F)
|
||||
#define SETTING_SECTION_MASK (0x30)
|
||||
|
||||
#define SETTING_TYPE_MASK (0x07)
|
||||
#define SETTING_SECTION_MASK (0x38)
|
||||
#define SETTING_MODE_MASK (0xC0)
|
||||
|
||||
typedef struct settingMinMaxConfig_s {
|
||||
|
|
|
@ -44,10 +44,10 @@ tables:
|
|||
values: ["VELNED", "TURNRATE","ADAPTIVE"]
|
||||
enum: imu_inertia_comp_method_e
|
||||
- name: gps_provider
|
||||
values: ["NMEA", "UBLOX", "UBLOX7", "MSP", "FAKE"]
|
||||
values: ["UBLOX", "UBLOX7", "MSP", "FAKE"]
|
||||
enum: gpsProvider_e
|
||||
- name: gps_sbas_mode
|
||||
values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"]
|
||||
values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"]
|
||||
enum: sbasMode_e
|
||||
- name: gps_dyn_model
|
||||
values: ["PEDESTRIAN", "AIR_1G", "AIR_4G"]
|
||||
|
@ -1045,7 +1045,7 @@ groups:
|
|||
max: PWM_RANGE_MAX
|
||||
- name: nav_mc_hover_thr
|
||||
description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering."
|
||||
default_value: 1500
|
||||
default_value: 1300
|
||||
field: nav.mc.hover_throttle
|
||||
min: 1000
|
||||
max: 2000
|
||||
|
@ -1134,31 +1134,56 @@ groups:
|
|||
field: powerLimits.burstPowerFalldownTime
|
||||
max: 3000
|
||||
|
||||
- name: PG_MIXER_CONFIG
|
||||
type: mixerConfig_t
|
||||
- name: PG_MIXER_PROFILE
|
||||
type: mixerProfile_t
|
||||
headers: ["flight/mixer_profile.h"]
|
||||
value_type: MIXER_CONFIG_VALUE
|
||||
members:
|
||||
- name: motor_direction_inverted
|
||||
description: "Use if you need to inverse yaw motor direction."
|
||||
default_value: OFF
|
||||
field: motorDirectionInverted
|
||||
field: mixer_config.motorDirectionInverted
|
||||
type: bool
|
||||
- name: platform_type
|
||||
description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented"
|
||||
default_value: "MULTIROTOR"
|
||||
field: platformType
|
||||
field: mixer_config.platformType
|
||||
type: uint8_t
|
||||
table: platform_type
|
||||
- name: has_flaps
|
||||
description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot"
|
||||
default_value: OFF
|
||||
field: hasFlaps
|
||||
field: mixer_config.hasFlaps
|
||||
type: bool
|
||||
- name: model_preview_type
|
||||
description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons."
|
||||
default_value: -1
|
||||
field: appliedMixerPreset
|
||||
field: mixer_config.appliedMixerPreset
|
||||
min: -1
|
||||
max: INT16_MAX
|
||||
- name: motorstop_on_low
|
||||
description: "If enabled, motor will stop when throttle is low on this mixer_profile"
|
||||
default_value: OFF
|
||||
field: mixer_config.motorstopOnLow
|
||||
type: bool
|
||||
- name: mixer_pid_profile_linking
|
||||
description: "If enabled, pid profile_index will follow mixer_profile index. Set to OFF(default) if you want to handle PID profile by your self. Recommend to set to ON on all mixer_profiles to let the mixer_profile handle the PID profile switching on a VTOL or mixed platform type setup."
|
||||
default_value: OFF
|
||||
field: mixer_config.PIDProfileLinking
|
||||
type: bool
|
||||
- name: mixer_automated_switch
|
||||
description: "If set to on, This mixer_profile will try to switch to another mixer_profile when 1.RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius on mixer_profile is a MULTIROTOR or TRICOPTER platform_type. 2. RTH landing is requested on this mixer_profile is a AIRPLANE platform_type"
|
||||
default_value: OFF
|
||||
field: mixer_config.automated_switch
|
||||
type: bool
|
||||
- name: mixer_switch_trans_timer
|
||||
description: "If switch another mixer_profile is scheduled by mixer_automated_switch or mixer_automated_switch. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch."
|
||||
default_value: 0
|
||||
field: mixer_config.switchTransitionTimer
|
||||
min: 0
|
||||
max: 200
|
||||
|
||||
|
||||
|
||||
- name: PG_REVERSIBLE_MOTORS_CONFIG
|
||||
type: reversibleMotorsConfig_t
|
||||
|
@ -1427,7 +1452,7 @@ groups:
|
|||
type: bool
|
||||
- name: ahrs_inertia_comp_method
|
||||
description: "Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop"
|
||||
default_value: VELNED
|
||||
default_value: ADAPTIVE
|
||||
field: inertia_comp_method
|
||||
table: imu_inertia_comp_method
|
||||
|
||||
|
@ -2242,7 +2267,7 @@ groups:
|
|||
max: 10
|
||||
default_value: 0.2
|
||||
- name: inav_w_z_gps_v
|
||||
description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero"
|
||||
description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors."
|
||||
field: w_z_gps_v
|
||||
min: 0
|
||||
max: 10
|
||||
|
@ -3475,59 +3500,88 @@ groups:
|
|||
max: 6
|
||||
default_value: 4
|
||||
|
||||
- name: osd_use_pilot_logo
|
||||
description: Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511
|
||||
field: use_pilot_logo
|
||||
type: bool
|
||||
default_value: OFF
|
||||
|
||||
- name: osd_inav_to_pilot_logo_spacing
|
||||
description: The space between the INAV and pilot logos, if `osd_use_pilot_logo` is `ON`. This number may be adjusted so that it fits the odd/even col width displays. For example, if using an odd column width display, such as Walksnail, and this is set to 4. 1 will be added so that the logos are equally spaced from the centre of the screen.
|
||||
field: inav_to_pilot_logo_spacing
|
||||
min: 0
|
||||
max: 20
|
||||
default_value: 8
|
||||
|
||||
- name: osd_arm_screen_display_time
|
||||
description: Amount of time to display the arm screen [ms]
|
||||
field: arm_screen_display_time
|
||||
min: 1000
|
||||
max: 5000
|
||||
default_value: 1500
|
||||
|
||||
- name: osd_switch_indicator_zero_name
|
||||
description: "Character to use for OSD switch incicator 0."
|
||||
field: osd_switch_indicator0_name
|
||||
type: string
|
||||
max: 5
|
||||
default_value: "FLAP"
|
||||
|
||||
- name: osd_switch_indicator_one_name
|
||||
description: "Character to use for OSD switch incicator 1."
|
||||
field: osd_switch_indicator1_name
|
||||
type: string
|
||||
max: 5
|
||||
default_value: "GEAR"
|
||||
|
||||
- name: osd_switch_indicator_two_name
|
||||
description: "Character to use for OSD switch incicator 2."
|
||||
field: osd_switch_indicator2_name
|
||||
type: string
|
||||
max: 5
|
||||
default_value: "CAM"
|
||||
|
||||
- name: osd_switch_indicator_three_name
|
||||
description: "Character to use for OSD switch incicator 3."
|
||||
field: osd_switch_indicator3_name
|
||||
type: string
|
||||
max: 5
|
||||
default_value: "LIGT"
|
||||
|
||||
- name: osd_switch_indicator_zero_channel
|
||||
description: "RC Channel to use for OSD switch indicator 0."
|
||||
field: osd_switch_indicator0_channel
|
||||
min: 5
|
||||
max: MAX_SUPPORTED_RC_CHANNEL_COUNT
|
||||
default_value: 5
|
||||
|
||||
- name: osd_switch_indicator_one_channel
|
||||
description: "RC Channel to use for OSD switch indicator 1."
|
||||
field: osd_switch_indicator1_channel
|
||||
min: 5
|
||||
max: MAX_SUPPORTED_RC_CHANNEL_COUNT
|
||||
default_value: 5
|
||||
|
||||
- name: osd_switch_indicator_two_channel
|
||||
description: "RC Channel to use for OSD switch indicator 2."
|
||||
field: osd_switch_indicator2_channel
|
||||
min: 5
|
||||
max: MAX_SUPPORTED_RC_CHANNEL_COUNT
|
||||
default_value: 5
|
||||
|
||||
- name: osd_switch_indicator_three_channel
|
||||
description: "RC Channel to use for OSD switch indicator 3."
|
||||
field: osd_switch_indicator3_channel
|
||||
min: 5
|
||||
max: MAX_SUPPORTED_RC_CHANNEL_COUNT
|
||||
default_value: 5
|
||||
|
||||
- name: osd_switch_indicators_align_left
|
||||
description: "Align text to left of switch indicators"
|
||||
field: osd_switch_indicators_align_left
|
||||
type: bool
|
||||
default_value: ON
|
||||
|
||||
- name: osd_system_msg_display_time
|
||||
description: System message display cycle time for multiple messages (milliseconds).
|
||||
field: system_msg_display_time
|
||||
|
|
|
@ -3,8 +3,8 @@
|
|||
#ifdef USE_STATS
|
||||
|
||||
typedef struct statsConfig_s {
|
||||
uint32_t stats_total_time; // [s]
|
||||
uint32_t stats_total_dist; // [m]
|
||||
uint32_t stats_total_time; // [Seconds]
|
||||
uint32_t stats_total_dist; // [Metres]
|
||||
#ifdef USE_ADC
|
||||
uint32_t stats_total_energy; // deciWatt hour (x0.1Wh)
|
||||
#endif
|
||||
|
|
|
@ -719,28 +719,25 @@ static void imuCalculateEstimatedAttitude(float dT)
|
|||
}
|
||||
if (imuConfig()->inertia_comp_method == COMPMETHOD_ADAPTIVE && isGPSTrustworthy() && STATE(AIRPLANE))
|
||||
{
|
||||
//pick the best centrifugal acceleration between velned and turnrate
|
||||
fpVector3_t compansatedGravityBF_velned;
|
||||
vectorAdd(&compansatedGravityBF_velned, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_velned);
|
||||
float velned_magnitude = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_velned)) - GRAVITY_CMSS);
|
||||
float velned_error = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_velned)) - GRAVITY_CMSS);
|
||||
|
||||
fpVector3_t compansatedGravityBF_turnrate;
|
||||
vectorAdd(&compansatedGravityBF_turnrate, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_turnrate);
|
||||
float turnrate_magnitude = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_turnrate)) - GRAVITY_CMSS);
|
||||
if (velned_magnitude > turnrate_magnitude)
|
||||
{
|
||||
compansatedGravityBF = compansatedGravityBF_turnrate;
|
||||
float turnrate_error = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_turnrate)) - GRAVITY_CMSS);
|
||||
|
||||
compansatedGravityBF = velned_error > turnrate_error? compansatedGravityBF_turnrate:compansatedGravityBF_velned;
|
||||
}
|
||||
else
|
||||
{
|
||||
compansatedGravityBF = compansatedGravityBF_velned;
|
||||
}
|
||||
}
|
||||
else if (imuConfig()->inertia_comp_method == COMPMETHOD_VELNED && isGPSTrustworthy())
|
||||
else if (((imuConfig()->inertia_comp_method == COMPMETHOD_VELNED) || (imuConfig()->inertia_comp_method == COMPMETHOD_ADAPTIVE)) && isGPSTrustworthy())
|
||||
{
|
||||
//velned centrifugal force compensation, quad will use this method
|
||||
vectorAdd(&compansatedGravityBF, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_velned);
|
||||
}
|
||||
else if (STATE(AIRPLANE))
|
||||
{
|
||||
//turnrate centrifugal force compensation
|
||||
vectorAdd(&compansatedGravityBF, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_turnrate);
|
||||
}
|
||||
else
|
||||
|
|
|
@ -32,6 +32,7 @@
|
|||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "config/config_reset.h"
|
||||
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
@ -82,15 +83,6 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig,
|
|||
.neutral = SETTING_3D_NEUTRAL_DEFAULT
|
||||
);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 5);
|
||||
|
||||
PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
|
||||
.motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT,
|
||||
.platformType = SETTING_PLATFORM_TYPE_DEFAULT,
|
||||
.hasFlaps = SETTING_HAS_FLAPS_DEFAULT,
|
||||
.appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only
|
||||
);
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 10);
|
||||
|
||||
PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
|
||||
|
@ -100,9 +92,6 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
|
|||
.mincommand = SETTING_MIN_COMMAND_DEFAULT,
|
||||
.motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles
|
||||
);
|
||||
|
||||
PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0);
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(timerOverride_t, HARDWARE_TIMER_DEFINITION_COUNT, timerOverrides, PG_TIMER_OVERRIDE_CONFIG, 0);
|
||||
|
||||
#define CRASH_OVER_AFTER_CRASH_FLIP_STICK_MIN 0.15f
|
||||
|
@ -125,14 +114,29 @@ int getThrottleIdleValue(void)
|
|||
|
||||
static void computeMotorCount(void)
|
||||
{
|
||||
static bool firstRun = true;
|
||||
if (!firstRun) {
|
||||
return;
|
||||
}
|
||||
motorCount = 0;
|
||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
bool isMotorUsed = false;
|
||||
for(int j = 0; j< MAX_MIXER_PROFILE_COUNT; j++){
|
||||
if (mixerMotorMixersByIndex(j)[i].throttle != 0.0f) {
|
||||
isMotorUsed = true;
|
||||
}
|
||||
}
|
||||
// check if done
|
||||
if (primaryMotorMixer(i)->throttle == 0.0f) {
|
||||
if (!isMotorUsed) {
|
||||
break;
|
||||
}
|
||||
motorCount++;
|
||||
}
|
||||
firstRun = false;
|
||||
}
|
||||
|
||||
bool ifMotorstopFeatureEnabled(void){
|
||||
return currentMixerConfig.motorstopOnLow;
|
||||
}
|
||||
|
||||
uint8_t getMotorCount(void) {
|
||||
|
@ -158,35 +162,44 @@ void mixerUpdateStateFlags(void)
|
|||
DISABLE_STATE(AIRPLANE);
|
||||
DISABLE_STATE(MOVE_FORWARD_ONLY);
|
||||
|
||||
if (mixerConfig()->platformType == PLATFORM_AIRPLANE) {
|
||||
if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) {
|
||||
ENABLE_STATE(FIXED_WING_LEGACY);
|
||||
ENABLE_STATE(AIRPLANE);
|
||||
ENABLE_STATE(ALTITUDE_CONTROL);
|
||||
ENABLE_STATE(MOVE_FORWARD_ONLY);
|
||||
} if (mixerConfig()->platformType == PLATFORM_ROVER) {
|
||||
} if (currentMixerConfig.platformType == PLATFORM_ROVER) {
|
||||
ENABLE_STATE(ROVER);
|
||||
ENABLE_STATE(FIXED_WING_LEGACY);
|
||||
ENABLE_STATE(MOVE_FORWARD_ONLY);
|
||||
} if (mixerConfig()->platformType == PLATFORM_BOAT) {
|
||||
} if (currentMixerConfig.platformType == PLATFORM_BOAT) {
|
||||
ENABLE_STATE(BOAT);
|
||||
ENABLE_STATE(FIXED_WING_LEGACY);
|
||||
ENABLE_STATE(MOVE_FORWARD_ONLY);
|
||||
} else if (mixerConfig()->platformType == PLATFORM_MULTIROTOR) {
|
||||
} else if (currentMixerConfig.platformType == PLATFORM_MULTIROTOR) {
|
||||
ENABLE_STATE(MULTIROTOR);
|
||||
ENABLE_STATE(ALTITUDE_CONTROL);
|
||||
} else if (mixerConfig()->platformType == PLATFORM_TRICOPTER) {
|
||||
} else if (currentMixerConfig.platformType == PLATFORM_TRICOPTER) {
|
||||
ENABLE_STATE(MULTIROTOR);
|
||||
ENABLE_STATE(ALTITUDE_CONTROL);
|
||||
} else if (mixerConfig()->platformType == PLATFORM_HELICOPTER) {
|
||||
} else if (currentMixerConfig.platformType == PLATFORM_HELICOPTER) {
|
||||
ENABLE_STATE(MULTIROTOR);
|
||||
ENABLE_STATE(ALTITUDE_CONTROL);
|
||||
}
|
||||
|
||||
if (mixerConfig()->hasFlaps) {
|
||||
if (currentMixerConfig.hasFlaps) {
|
||||
ENABLE_STATE(FLAPERON_AVAILABLE);
|
||||
} else {
|
||||
DISABLE_STATE(FLAPERON_AVAILABLE);
|
||||
}
|
||||
if (
|
||||
currentMixerConfig.platformType == PLATFORM_BOAT ||
|
||||
currentMixerConfig.platformType == PLATFORM_ROVER ||
|
||||
navConfig()->fw.useFwNavYawControl
|
||||
) {
|
||||
ENABLE_STATE(FW_HEADING_USE_YAW);
|
||||
} else {
|
||||
DISABLE_STATE(FW_HEADING_USE_YAW);
|
||||
}
|
||||
}
|
||||
|
||||
void nullMotorRateLimiting(const float dT)
|
||||
|
@ -208,7 +221,7 @@ void mixerInit(void)
|
|||
|
||||
mixerResetDisarmedMotors();
|
||||
|
||||
if (mixerConfig()->motorDirectionInverted) {
|
||||
if (currentMixerConfig.motorDirectionInverted) {
|
||||
motorYawMultiplier = -1;
|
||||
} else {
|
||||
motorYawMultiplier = 1;
|
||||
|
@ -231,7 +244,7 @@ void mixerResetDisarmedMotors(void)
|
|||
|
||||
reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD;
|
||||
|
||||
if (feature(FEATURE_MOTOR_STOP)) {
|
||||
if (ifMotorstopFeatureEnabled()) {
|
||||
motorValueWhenStopped = motorZeroCommand;
|
||||
} else {
|
||||
motorValueWhenStopped = throttleIdleValue;
|
||||
|
@ -289,7 +302,7 @@ static void applyTurtleModeToMotors(void) {
|
|||
|
||||
float signPitch = rcCommand[PITCH] < 0 ? 1 : -1;
|
||||
float signRoll = rcCommand[ROLL] < 0 ? 1 : -1;
|
||||
float signYaw = (float)((rcCommand[YAW] < 0 ? 1 : -1) * (mixerConfig()->motorDirectionInverted ? 1 : -1));
|
||||
float signYaw = (float)((rcCommand[YAW] < 0 ? 1 : -1) * (currentMixerConfig.motorDirectionInverted ? 1 : -1));
|
||||
|
||||
float stickDeflectionLength = calc_length_pythagorean_2D(stickDeflectionPitchAbs, stickDeflectionRollAbs);
|
||||
float stickDeflectionExpoLength = calc_length_pythagorean_2D(stickDeflectionPitchExpo, stickDeflectionRollExpo);
|
||||
|
@ -468,7 +481,7 @@ static int getReversibleMotorsThrottleDeadband(void)
|
|||
directionValue = reversibleMotorsConfig()->deadband_high;
|
||||
}
|
||||
|
||||
return feature(FEATURE_MOTOR_STOP) ? reversibleMotorsConfig()->neutral : directionValue;
|
||||
return ifMotorstopFeatureEnabled() ? reversibleMotorsConfig()->neutral : directionValue;
|
||||
}
|
||||
|
||||
void FAST_CODE mixTable(void)
|
||||
|
@ -614,6 +627,16 @@ void FAST_CODE mixTable(void)
|
|||
} else {
|
||||
motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax);
|
||||
}
|
||||
|
||||
//stop motors
|
||||
if (currentMixer[i].throttle <= 0.0f) {
|
||||
motor[i] = motorZeroCommand;
|
||||
}
|
||||
//spin stopped motors only in mixer transition mode
|
||||
if (isMixerTransitionMixing && currentMixer[i].throttle <= -1.05f && currentMixer[i].throttle >= -2.0f && (!feature(FEATURE_REVERSIBLE_MOTORS))) {
|
||||
motor[i] = -currentMixer[i].throttle * 1000;
|
||||
motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -64,7 +64,6 @@ typedef struct motorMixer_s {
|
|||
float yaw;
|
||||
} motorMixer_t;
|
||||
|
||||
PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer);
|
||||
|
||||
typedef struct timerOverride_s {
|
||||
uint8_t outputMode;
|
||||
|
@ -72,15 +71,6 @@ typedef struct timerOverride_s {
|
|||
|
||||
PG_DECLARE_ARRAY(timerOverride_t, HARDWARE_TIMER_DEFINITION_COUNT, timerOverrides);
|
||||
|
||||
typedef struct mixerConfig_s {
|
||||
int8_t motorDirectionInverted;
|
||||
uint8_t platformType;
|
||||
bool hasFlaps;
|
||||
int16_t appliedMixerPreset;
|
||||
} mixerConfig_t;
|
||||
|
||||
PG_DECLARE(mixerConfig_t, mixerConfig);
|
||||
|
||||
typedef struct reversibleMotorsConfig_s {
|
||||
uint16_t deadband_low; // min 3d value
|
||||
uint16_t deadband_high; // max 3d value
|
||||
|
@ -117,6 +107,7 @@ extern int16_t motor[MAX_SUPPORTED_MOTORS];
|
|||
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
extern int mixerThrottleCommand;
|
||||
|
||||
bool ifMotorstopFeatureEnabled(void);
|
||||
int getThrottleIdleValue(void);
|
||||
int16_t getThrottlePercent(bool);
|
||||
uint16_t setDesiredThrottle(uint16_t throttle, bool allowMotorStop);
|
||||
|
@ -135,6 +126,7 @@ void processServoAutotrim(const float dT);
|
|||
void processServoAutotrimMode(void);
|
||||
void processContinuousServoAutotrim(const float dT);
|
||||
void stopMotors(void);
|
||||
void stopMotorsNoDelay(void);
|
||||
void stopPwmAllMotors(void);
|
||||
|
||||
void loadPrimaryMotorMixer(void);
|
||||
|
|
253
src/main/flight/mixer_profile.c
Normal file
253
src/main/flight/mixer_profile.c
Normal file
|
@ -0,0 +1,253 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "config/config_reset.h"
|
||||
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/time.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "common/axis.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "navigation/navigation.h"
|
||||
#include "navigation/navigation_private.h"
|
||||
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/settings.h"
|
||||
#include "fc/rc_modes.h"
|
||||
#include "fc/cli.h"
|
||||
|
||||
#include "programming/logic_condition.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
#include "common/log.h"
|
||||
|
||||
mixerConfig_t currentMixerConfig;
|
||||
int currentMixerProfileIndex;
|
||||
bool isMixerTransitionMixing;
|
||||
bool isMixerTransitionMixing_requested;
|
||||
mixerProfileAT_t mixerProfileAT;
|
||||
int nextProfileIndex;
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1);
|
||||
|
||||
void pgResetFn_mixerProfiles(mixerProfile_t *instance)
|
||||
{
|
||||
for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++)
|
||||
{
|
||||
RESET_CONFIG(mixerProfile_t, &instance[i],
|
||||
.mixer_config = {
|
||||
.motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT,
|
||||
.platformType = SETTING_PLATFORM_TYPE_DEFAULT,
|
||||
.hasFlaps = SETTING_HAS_FLAPS_DEFAULT,
|
||||
.appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, // This flag is not available in CLI and used by Configurator only
|
||||
.motorstopOnLow = SETTING_MOTORSTOP_ON_LOW_DEFAULT,
|
||||
.PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT,
|
||||
.automated_switch = SETTING_MIXER_AUTOMATED_SWITCH_DEFAULT,
|
||||
.switchTransitionTimer = SETTING_MIXER_SWITCH_TRANS_TIMER_DEFAULT,
|
||||
});
|
||||
for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++)
|
||||
{
|
||||
RESET_CONFIG(motorMixer_t, &instance[i].MotorMixers[j],
|
||||
.throttle = 0,
|
||||
.roll = 0,
|
||||
.pitch = 0,
|
||||
.yaw = 0);
|
||||
}
|
||||
for (int j = 0; j < MAX_SERVO_RULES; j++)
|
||||
{
|
||||
RESET_CONFIG(servoMixer_t, &instance[i].ServoMixers[j],
|
||||
.targetChannel = 0,
|
||||
.inputSource = 0,
|
||||
.rate = 0,
|
||||
.speed = 0
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
,
|
||||
.conditionId = -1,
|
||||
#endif
|
||||
);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void activateMixerConfig(){
|
||||
currentMixerProfileIndex = getConfigMixerProfile();
|
||||
currentMixerConfig = *mixerConfig();
|
||||
nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT;
|
||||
}
|
||||
|
||||
void mixerConfigInit(void)
|
||||
{
|
||||
activateMixerConfig();
|
||||
servosInit();
|
||||
mixerUpdateStateFlags();
|
||||
mixerInit();
|
||||
if (currentMixerConfig.PIDProfileLinking)
|
||||
{
|
||||
// LOG_INFO(PWM, "mixer switch pidInit");
|
||||
setConfigProfile(getConfigMixerProfile());
|
||||
pidInit();
|
||||
pidInitFilters();
|
||||
pidResetErrorAccumulators(); //should be safer to reset error accumulators
|
||||
schedulePidGainsUpdate();
|
||||
navigationUsePIDs(); // set navigation pid gains
|
||||
}
|
||||
}
|
||||
|
||||
void setMixerProfileAT(void)
|
||||
{
|
||||
mixerProfileAT.transitionStartTime = millis();
|
||||
mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStartTime + (timeMs_t)currentMixerConfig.switchTransitionTimer * 100;
|
||||
}
|
||||
|
||||
bool platformTypeConfigured(flyingPlatformType_e platformType)
|
||||
{
|
||||
if (!isModeActivationConditionPresent(BOXMIXERPROFILE)){
|
||||
return false;
|
||||
}
|
||||
return mixerConfigByIndex(nextProfileIndex)->platformType == platformType;
|
||||
}
|
||||
|
||||
bool checkMixerATRequired(mixerProfileATRequest_e required_action)
|
||||
{
|
||||
//return false if mixerAT condition is not required or setting is not valid
|
||||
if ((!STATE(AIRPLANE)) && (!STATE(MULTIROTOR)))
|
||||
{
|
||||
return false;
|
||||
}
|
||||
if (!isModeActivationConditionPresent(BOXMIXERPROFILE))
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
if(currentMixerConfig.automated_switch){
|
||||
if ((required_action == MIXERAT_REQUEST_RTH) && STATE(MULTIROTOR))
|
||||
{
|
||||
return true;
|
||||
}
|
||||
if ((required_action == MIXERAT_REQUEST_LAND) && STATE(AIRPLANE))
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool mixerATUpdateState(mixerProfileATRequest_e required_action)
|
||||
{
|
||||
//return true if mixerAT is done or not required
|
||||
bool reprocessState;
|
||||
do
|
||||
{
|
||||
reprocessState=false;
|
||||
if (required_action==MIXERAT_REQUEST_ABORT){
|
||||
isMixerTransitionMixing_requested = false;
|
||||
mixerProfileAT.phase = MIXERAT_PHASE_IDLE;
|
||||
return true;
|
||||
}
|
||||
switch (mixerProfileAT.phase){
|
||||
case MIXERAT_PHASE_IDLE:
|
||||
//check if mixerAT is required
|
||||
if (checkMixerATRequired(required_action)){
|
||||
mixerProfileAT.phase=MIXERAT_PHASE_TRANSITION_INITIALIZE;
|
||||
reprocessState = true;
|
||||
}
|
||||
break;
|
||||
case MIXERAT_PHASE_TRANSITION_INITIALIZE:
|
||||
// LOG_INFO(PWM, "MIXERAT_PHASE_IDLE");
|
||||
setMixerProfileAT();
|
||||
mixerProfileAT.phase = MIXERAT_PHASE_TRANSITIONING;
|
||||
reprocessState = true;
|
||||
break;
|
||||
case MIXERAT_PHASE_TRANSITIONING:
|
||||
isMixerTransitionMixing_requested = true;
|
||||
if (millis() > mixerProfileAT.transitionTransEndTime){
|
||||
isMixerTransitionMixing_requested = false;
|
||||
outputProfileHotSwitch(nextProfileIndex);
|
||||
mixerProfileAT.phase = MIXERAT_PHASE_IDLE;
|
||||
reprocessState = true;
|
||||
//transition is done
|
||||
}
|
||||
return false;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
while (reprocessState);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool checkMixerProfileHotSwitchAvalibility(void)
|
||||
{
|
||||
if (MAX_MIXER_PROFILE_COUNT != 2)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void outputProfileUpdateTask(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
if(cliMode) return;
|
||||
bool mixerAT_inuse = mixerProfileAT.phase != MIXERAT_PHASE_IDLE;
|
||||
// transition mode input for servo mix and motor mix
|
||||
if (!FLIGHT_MODE(FAILSAFE_MODE) && (!mixerAT_inuse))
|
||||
{
|
||||
if (isModeActivationConditionPresent(BOXMIXERPROFILE)){
|
||||
outputProfileHotSwitch(IS_RC_MODE_ACTIVE(BOXMIXERPROFILE) == 0 ? 0 : 1);
|
||||
}
|
||||
isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION);
|
||||
}
|
||||
isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) || mixerAT_inuse ||(posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS));
|
||||
}
|
||||
|
||||
// switch mixerprofile without reboot
|
||||
bool outputProfileHotSwitch(int profile_index)
|
||||
{
|
||||
static bool allow_hot_switch = true;
|
||||
// LOG_INFO(PWM, "OutputProfileHotSwitch");
|
||||
if (!allow_hot_switch)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
if (currentMixerProfileIndex == profile_index)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
if (profile_index < 0 || profile_index >= MAX_MIXER_PROFILE_COUNT)
|
||||
{ // sanity check
|
||||
// LOG_INFO(PWM, "invalid mixer profile index");
|
||||
return false;
|
||||
}
|
||||
if (areSensorsCalibrating())
|
||||
{ // it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D
|
||||
return false;
|
||||
}
|
||||
if (!checkMixerProfileHotSwitchAvalibility())
|
||||
{
|
||||
// LOG_INFO(PWM, "mixer switch failed, checkMixerProfileHotSwitchAvalibility");
|
||||
return false;
|
||||
}
|
||||
if ((posControl.navState != NAV_STATE_IDLE) && (posControl.navState != NAV_STATE_MIXERAT_IN_PROGRESS))
|
||||
{
|
||||
// LOG_INFO(PWM, "mixer switch failed, navState != NAV_STATE_IDLE");
|
||||
return false;
|
||||
}
|
||||
if (!setConfigMixerProfile(profile_index))
|
||||
{
|
||||
// LOG_INFO(PWM, "mixer switch failed to set config");
|
||||
return false;
|
||||
}
|
||||
mixerConfigInit();
|
||||
return true;
|
||||
}
|
79
src/main/flight/mixer_profile.h
Normal file
79
src/main/flight/mixer_profile.h
Normal file
|
@ -0,0 +1,79 @@
|
|||
#pragma once
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
#ifndef MAX_MIXER_PROFILE_COUNT
|
||||
#define MAX_MIXER_PROFILE_COUNT 2
|
||||
#endif
|
||||
|
||||
typedef struct mixerConfig_s {
|
||||
int8_t motorDirectionInverted;
|
||||
uint8_t platformType;
|
||||
bool hasFlaps;
|
||||
int16_t appliedMixerPreset;
|
||||
bool motorstopOnLow;
|
||||
bool PIDProfileLinking;
|
||||
bool automated_switch;
|
||||
int16_t switchTransitionTimer;
|
||||
} mixerConfig_t;
|
||||
typedef struct mixerProfile_s {
|
||||
mixerConfig_t mixer_config;
|
||||
motorMixer_t MotorMixers[MAX_SUPPORTED_MOTORS];
|
||||
servoMixer_t ServoMixers[MAX_SERVO_RULES];
|
||||
} mixerProfile_t;
|
||||
|
||||
PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles);
|
||||
typedef enum {
|
||||
MIXERAT_REQUEST_NONE, //no request, stats checking only
|
||||
MIXERAT_REQUEST_RTH,
|
||||
MIXERAT_REQUEST_LAND,
|
||||
MIXERAT_REQUEST_ABORT,
|
||||
} mixerProfileATRequest_e;
|
||||
|
||||
//mixerProfile Automated Transition PHASE
|
||||
typedef enum {
|
||||
MIXERAT_PHASE_IDLE,
|
||||
MIXERAT_PHASE_TRANSITION_INITIALIZE,
|
||||
MIXERAT_PHASE_TRANSITIONING,
|
||||
MIXERAT_PHASE_DONE,
|
||||
} mixerProfileATState_e;
|
||||
|
||||
typedef struct mixerProfileAT_s {
|
||||
mixerProfileATState_e phase;
|
||||
bool transitionInputMixing;
|
||||
timeMs_t transitionStartTime;
|
||||
timeMs_t transitionStabEndTime;
|
||||
timeMs_t transitionTransEndTime;
|
||||
} mixerProfileAT_t;
|
||||
extern mixerProfileAT_t mixerProfileAT;
|
||||
bool checkMixerATRequired(mixerProfileATRequest_e required_action);
|
||||
bool mixerATUpdateState(mixerProfileATRequest_e required_action);
|
||||
|
||||
extern mixerConfig_t currentMixerConfig;
|
||||
extern int currentMixerProfileIndex;
|
||||
extern bool isMixerTransitionMixing;
|
||||
#define mixerConfig() (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->mixer_config))
|
||||
#define mixerConfigMutable() ((mixerConfig_t *) mixerConfig())
|
||||
|
||||
#define primaryMotorMixer(_index) (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->MotorMixers)[_index])
|
||||
#define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index))
|
||||
#define customServoMixers(_index) (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->ServoMixers)[_index])
|
||||
#define customServoMixersMutable(_index) ((servoMixer_t *)customServoMixers(_index))
|
||||
|
||||
static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) { return &mixerProfiles_CopyArray[_index]; }
|
||||
#define primaryMotorMixer_CopyArray() (mixerProfiles_CopyArray_by_index(systemConfig()->current_mixer_profile_index)->MotorMixers)
|
||||
#define customServoMixers_CopyArray() (mixerProfiles_CopyArray_by_index(systemConfig()->current_mixer_profile_index)->ServoMixers)
|
||||
|
||||
#define mixerConfigByIndex(index) (&(mixerProfiles(index)->mixer_config))
|
||||
#define mixerMotorMixersByIndex(index) (mixerProfiles(index)->MotorMixers)
|
||||
#define mixerServoMixersByIndex(index) (mixerProfiles(index)->ServoMixers)
|
||||
|
||||
bool platformTypeConfigured(flyingPlatformType_e platformType);
|
||||
bool outputProfileHotSwitch(int profile_index);
|
||||
bool checkMixerProfileHotSwitchAvalibility(void);
|
||||
void activateMixerConfig(void);
|
||||
void mixerConfigInit(void);
|
||||
void outputProfileUpdateTask(timeUs_t currentTimeUs);
|
|
@ -43,6 +43,7 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
#include "flight/kalman.h"
|
||||
#include "flight/smith_predictor.h"
|
||||
|
@ -1065,7 +1066,7 @@ void FAST_CODE pidController(float dT)
|
|||
return;
|
||||
}
|
||||
|
||||
bool canUseFpvCameraMix = true;
|
||||
bool canUseFpvCameraMix = STATE(MULTIROTOR);
|
||||
uint8_t headingHoldState = getHeadingHoldState();
|
||||
|
||||
// In case Yaw override is active, we engage the Heading Hold state
|
||||
|
@ -1161,7 +1162,7 @@ void FAST_CODE pidController(float dT)
|
|||
}
|
||||
|
||||
// Apply FPV camera mix
|
||||
if (canUseFpvCameraMix && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && currentControlRateProfile->misc.fpvCamAngleDegrees) {
|
||||
if (canUseFpvCameraMix && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && currentControlRateProfile->misc.fpvCamAngleDegrees && STATE(MULTIROTOR)) {
|
||||
pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees);
|
||||
}
|
||||
|
||||
|
@ -1245,9 +1246,9 @@ void pidInit(void)
|
|||
|
||||
if (pidProfile()->pidControllerType == PID_TYPE_AUTO) {
|
||||
if (
|
||||
mixerConfig()->platformType == PLATFORM_AIRPLANE ||
|
||||
mixerConfig()->platformType == PLATFORM_BOAT ||
|
||||
mixerConfig()->platformType == PLATFORM_ROVER
|
||||
currentMixerConfig.platformType == PLATFORM_AIRPLANE ||
|
||||
currentMixerConfig.platformType == PLATFORM_BOAT ||
|
||||
currentMixerConfig.platformType == PLATFORM_ROVER
|
||||
) {
|
||||
usedPidControllerType = PID_TYPE_PIFF;
|
||||
} else {
|
||||
|
|
|
@ -130,7 +130,7 @@ void autotuneStart(void)
|
|||
|
||||
void autotuneUpdateState(void)
|
||||
{
|
||||
if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE) && ARMING_FLAG(ARMED)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE) && STATE(AIRPLANE) && ARMING_FLAG(ARMED)) {
|
||||
if (!FLIGHT_MODE(AUTO_TUNE)) {
|
||||
autotuneStart();
|
||||
ENABLE_FLIGHT_MODE(AUTO_TUNE);
|
||||
|
|
|
@ -209,8 +209,8 @@ float calculateRemainingFlightTimeBeforeRTH(bool takeWindIntoAccount) {
|
|||
// returns meters
|
||||
float calculateRemainingDistanceBeforeRTH(bool takeWindIntoAccount) {
|
||||
|
||||
// Fixed wing only for now
|
||||
if (!(STATE(FIXED_WING_LEGACY) || ARMING_FLAG(ARMED))) {
|
||||
// Fixed wing only for now, and must be armed
|
||||
if (!STATE(AIRPLANE) || !ARMING_FLAG(ARMED)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
|
|
@ -70,11 +70,10 @@ PG_RESET_TEMPLATE(servoConfig_t, servoConfig,
|
|||
.servo_autotrim_rotation_limit = SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_DEFAULT
|
||||
);
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(servoMixer_t, MAX_SERVO_RULES, customServoMixers, PG_SERVO_MIXER, 1);
|
||||
|
||||
void pgResetFn_customServoMixers(servoMixer_t *instance)
|
||||
void Reset_servoMixers(servoMixer_t *instance)
|
||||
{
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++){
|
||||
RESET_CONFIG(servoMixer_t, &instance[i],
|
||||
.targetChannel = 0,
|
||||
.inputSource = 0,
|
||||
|
@ -105,6 +104,13 @@ int16_t servo[MAX_SUPPORTED_SERVOS];
|
|||
|
||||
static uint8_t servoRuleCount = 0;
|
||||
static servoMixer_t currentServoMixer[MAX_SERVO_RULES];
|
||||
|
||||
/*
|
||||
//Was used to keep track of servo rules in all mixer_profile, In order to Apply mixer speed limit when rules turn off
|
||||
static servoMixer_t currentServoMixer[MAX_SERVO_RULES*MAX_MIXER_PROFILE_COUNT];
|
||||
static bool currentServoMixerActivative[MAX_SERVO_RULES*MAX_MIXER_PROFILE_COUNT]; // if true, the rule is used by current servo mixer
|
||||
*/
|
||||
|
||||
static bool servoOutputEnabled;
|
||||
|
||||
static bool mixerUsesServos;
|
||||
|
@ -137,6 +143,33 @@ void servoComputeScalingFactors(uint8_t servoIndex) {
|
|||
servoMetadata[servoIndex].scaleMin = (servoParams(servoIndex)->middle - servoParams(servoIndex)->min) / 500.0f;
|
||||
}
|
||||
|
||||
void computeServoCount(void)
|
||||
{
|
||||
static bool firstRun = true;
|
||||
if (!firstRun) {
|
||||
return;
|
||||
}
|
||||
minServoIndex = 255;
|
||||
maxServoIndex = 0;
|
||||
for (int j = 0; j < MAX_MIXER_PROFILE_COUNT; j++) {
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
// check if done
|
||||
if (mixerServoMixersByIndex(j)[i].rate == 0){
|
||||
break;
|
||||
}
|
||||
if (mixerServoMixersByIndex(j)[i].targetChannel < minServoIndex) {
|
||||
minServoIndex = mixerServoMixersByIndex(j)[i].targetChannel;
|
||||
}
|
||||
|
||||
if (mixerServoMixersByIndex(j)[i].targetChannel > maxServoIndex) {
|
||||
maxServoIndex = mixerServoMixersByIndex(j)[i].targetChannel;
|
||||
}
|
||||
mixerUsesServos = true;
|
||||
}
|
||||
}
|
||||
firstRun = false;
|
||||
}
|
||||
|
||||
void servosInit(void)
|
||||
{
|
||||
// give all servos a default command
|
||||
|
@ -147,12 +180,12 @@ void servosInit(void)
|
|||
/*
|
||||
* load mixer
|
||||
*/
|
||||
computeServoCount();
|
||||
loadCustomServoMixer();
|
||||
|
||||
// If there are servo rules after all, update variables
|
||||
if (servoRuleCount > 0) {
|
||||
if (mixerUsesServos) {
|
||||
servoOutputEnabled = true;
|
||||
mixerUsesServos = true;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
|
@ -162,7 +195,7 @@ void servosInit(void)
|
|||
|
||||
int getServoCount(void)
|
||||
{
|
||||
if (servoRuleCount) {
|
||||
if (mixerUsesServos) {
|
||||
return 1 + maxServoIndex - minServoIndex;
|
||||
}
|
||||
else {
|
||||
|
@ -172,27 +205,17 @@ int getServoCount(void)
|
|||
|
||||
void loadCustomServoMixer(void)
|
||||
{
|
||||
// reset settings
|
||||
servoRuleCount = 0;
|
||||
minServoIndex = 255;
|
||||
maxServoIndex = 0;
|
||||
memset(currentServoMixer, 0, sizeof(currentServoMixer));
|
||||
|
||||
// load custom mixer into currentServoMixer
|
||||
for (int i = 0; i < MAX_SERVO_RULES; i++) {
|
||||
// check if done
|
||||
if (customServoMixers(i)->rate == 0)
|
||||
if (customServoMixers(i)->rate == 0){
|
||||
break;
|
||||
|
||||
if (customServoMixers(i)->targetChannel < minServoIndex) {
|
||||
minServoIndex = customServoMixers(i)->targetChannel;
|
||||
}
|
||||
|
||||
if (customServoMixers(i)->targetChannel > maxServoIndex) {
|
||||
maxServoIndex = customServoMixers(i)->targetChannel;
|
||||
}
|
||||
|
||||
memcpy(¤tServoMixer[i], customServoMixers(i), sizeof(servoMixer_t));
|
||||
currentServoMixer[servoRuleCount] = *customServoMixers(i);
|
||||
servoSpeedLimitFilter[servoRuleCount].state = 0;
|
||||
servoRuleCount++;
|
||||
}
|
||||
}
|
||||
|
@ -231,7 +254,7 @@ void writeServos(void)
|
|||
/*
|
||||
* in case of tricopters, there might me a need to zero servo output when unarmed
|
||||
*/
|
||||
if (mixerConfig()->platformType == PLATFORM_TRICOPTER && !ARMING_FLAG(ARMED) && !servoConfig()->tri_unarmed_servo) {
|
||||
if (currentMixerConfig.platformType == PLATFORM_TRICOPTER && !ARMING_FLAG(ARMED) && !servoConfig()->tri_unarmed_servo) {
|
||||
zeroServoValue = true;
|
||||
}
|
||||
|
||||
|
@ -261,7 +284,7 @@ void servoMixer(float dT)
|
|||
|
||||
// Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter
|
||||
if (feature(FEATURE_REVERSIBLE_MOTORS) && (rxGetChannelValue(THROTTLE) < PWM_RANGE_MIDDLE) &&
|
||||
(mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) {
|
||||
(currentMixerConfig.platformType == PLATFORM_MULTIROTOR || currentMixerConfig.platformType == PLATFORM_TRICOPTER)) {
|
||||
input[INPUT_STABILIZED_YAW] *= -1;
|
||||
}
|
||||
}
|
||||
|
@ -297,6 +320,8 @@ void servoMixer(float dT)
|
|||
|
||||
input[INPUT_STABILIZED_THROTTLE] = mixerThrottleCommand - 1000 - 500; // Since it derives from rcCommand or mincommand and must be [-500:+500]
|
||||
|
||||
input[INPUT_MIXER_TRANSITION] = isMixerTransitionMixing * 500; //fixed value
|
||||
|
||||
// center the RC input value around the RC middle value
|
||||
// by subtracting the RC middle value from the RC input value, we get:
|
||||
// data - middle = input
|
||||
|
@ -335,19 +360,19 @@ void servoMixer(float dT)
|
|||
|
||||
// mix servos according to rules
|
||||
for (int i = 0; i < servoRuleCount; i++) {
|
||||
const uint8_t target = currentServoMixer[i].targetChannel;
|
||||
const uint8_t from = currentServoMixer[i].inputSource;
|
||||
|
||||
int16_t inputRaw = input[from];
|
||||
|
||||
/*
|
||||
* Check if conditions for a rule are met, not all conditions apply all the time
|
||||
*/
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
if (!logicConditionGetValue(currentServoMixer[i].conditionId)) {
|
||||
continue;
|
||||
inputRaw = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
const uint8_t target = currentServoMixer[i].targetChannel;
|
||||
const uint8_t from = currentServoMixer[i].inputSource;
|
||||
|
||||
/*
|
||||
* Apply mixer speed limit. 1 [one] speed unit is defined as 10us/s:
|
||||
* 0 = no limiting
|
||||
|
@ -355,13 +380,13 @@ void servoMixer(float dT)
|
|||
* 10 = 100us/s -> full sweep (from 1000 to 2000) is performed in 10s
|
||||
* 100 = 1000us/s -> full sweep in 1s
|
||||
*/
|
||||
int16_t inputLimited = (int16_t) rateLimitFilterApply4(&servoSpeedLimitFilter[i], input[from], currentServoMixer[i].speed * 10, dT);
|
||||
int16_t inputLimited = (int16_t) rateLimitFilterApply4(&servoSpeedLimitFilter[i], inputRaw, currentServoMixer[i].speed * 10, dT);
|
||||
|
||||
servo[target] += ((int32_t)inputLimited * currentServoMixer[i].rate) / 100;
|
||||
}
|
||||
|
||||
/*
|
||||
* When not armed, apply servo low position to all outputs that include a throttle or stabilizet throttle in the mix
|
||||
* When not armed, apply servo low position to all outputs that include a throttle or stabilized throttle in the mix
|
||||
*/
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
for (int i = 0; i < servoRuleCount; i++) {
|
||||
|
@ -430,6 +455,7 @@ void processServoAutotrimMode(void)
|
|||
if (ARMING_FLAG(ARMED)) {
|
||||
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
|
||||
for (int i = 0; i < servoRuleCount; i++) {
|
||||
// Reset servo middle accumulator
|
||||
const uint8_t target = currentServoMixer[i].targetChannel;
|
||||
const uint8_t source = currentServoMixer[i].inputSource;
|
||||
if (source == axis) {
|
||||
|
@ -593,6 +619,10 @@ void processServoAutotrim(const float dT) {
|
|||
return;
|
||||
}
|
||||
#endif
|
||||
if(!STATE(AIRPLANE))
|
||||
{
|
||||
return;
|
||||
}
|
||||
if (feature(FEATURE_FW_AUTOTRIM)) {
|
||||
processContinuousServoAutotrim(dT);
|
||||
} else {
|
||||
|
|
|
@ -62,7 +62,7 @@ typedef enum {
|
|||
INPUT_GVAR_5 = 35,
|
||||
INPUT_GVAR_6 = 36,
|
||||
INPUT_GVAR_7 = 37,
|
||||
|
||||
INPUT_MIXER_TRANSITION = 38,
|
||||
INPUT_SOURCE_COUNT
|
||||
} inputSource_e;
|
||||
|
||||
|
@ -151,6 +151,7 @@ typedef struct servoMetadata_s {
|
|||
|
||||
extern int16_t servo[MAX_SUPPORTED_SERVOS];
|
||||
|
||||
void Reset_servoMixers(servoMixer_t* instance);
|
||||
bool isServoOutputEnabled(void);
|
||||
void setServoOutputEnabled(bool flag);
|
||||
bool isMixerUsingServos(void);
|
||||
|
|
|
@ -77,13 +77,6 @@ gpsSolutionData_t gpsSol;
|
|||
baudRate_e gpsToSerialBaudRate[GPS_BAUDRATE_COUNT] = { BAUD_115200, BAUD_57600, BAUD_38400, BAUD_19200, BAUD_9600, BAUD_230400, BAUD_460800, BAUD_921600 };
|
||||
|
||||
static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = {
|
||||
/* NMEA GPS */
|
||||
#ifdef USE_GPS_PROTO_NMEA
|
||||
{ false, MODE_RX, gpsRestartNMEA, &gpsHandleNMEA },
|
||||
#else
|
||||
{ false, 0, NULL, NULL },
|
||||
#endif
|
||||
|
||||
/* UBLOX binary */
|
||||
#ifdef USE_GPS_PROTO_UBLOX
|
||||
{ false, MODE_RXTX, &gpsRestartUBLOX, &gpsHandleUBLOX },
|
||||
|
@ -113,7 +106,7 @@ static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = {
|
|||
|
||||
};
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 4);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 5);
|
||||
|
||||
PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
|
||||
.provider = SETTING_GPS_PROVIDER_DEFAULT,
|
||||
|
@ -264,7 +257,7 @@ void gpsPreInit(void)
|
|||
{
|
||||
// Make sure gpsProvider is known when gpsMagDetect is called
|
||||
gpsState.gpsConfig = gpsConfig();
|
||||
gpsState.baseTimeoutMs = (gpsState.gpsConfig->provider == GPS_NMEA) ? GPS_TIMEOUT*2 : GPS_TIMEOUT;
|
||||
gpsState.baseTimeoutMs = GPS_TIMEOUT;
|
||||
}
|
||||
|
||||
void gpsInit(void)
|
||||
|
|
|
@ -33,8 +33,7 @@
|
|||
#define GPS_DEGREES_DIVIDER 10000000L
|
||||
|
||||
typedef enum {
|
||||
GPS_NMEA = 0,
|
||||
GPS_UBLOX,
|
||||
GPS_UBLOX = 0,
|
||||
GPS_UBLOX7PLUS,
|
||||
GPS_MSP,
|
||||
GPS_FAKE,
|
||||
|
@ -47,6 +46,7 @@ typedef enum {
|
|||
SBAS_WAAS,
|
||||
SBAS_MSAS,
|
||||
SBAS_GAGAN,
|
||||
SBAS_SPAN,
|
||||
SBAS_NONE
|
||||
} sbasMode_e;
|
||||
|
||||
|
|
|
@ -1,340 +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 <ctype.h>
|
||||
#include <string.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_GPS) && (defined(USE_GPS_PROTO_NMEA))
|
||||
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/gps_conversion.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gps_private.h"
|
||||
|
||||
#include "scheduler/protothreads.h"
|
||||
|
||||
/* This is a light implementation of a GPS frame decoding
|
||||
This should work with most of modern GPS devices configured to output 5 frames.
|
||||
It assumes there are some NMEA GGA frames to decode on the serial bus
|
||||
Now verifies checksum correctly before applying data
|
||||
|
||||
Here we use only the following data :
|
||||
- latitude
|
||||
- longitude
|
||||
- GPS fix is/is not ok
|
||||
- GPS num sat (4 is enough to be +/- reliable)
|
||||
// added by Mis
|
||||
- GPS altitude (for OSD displaying)
|
||||
- GPS speed (for OSD displaying)
|
||||
*/
|
||||
|
||||
#define NO_FRAME 0
|
||||
#define FRAME_GGA 1
|
||||
#define FRAME_RMC 2
|
||||
|
||||
static uint32_t grab_fields(char *src, uint8_t mult)
|
||||
{ // convert string to uint32
|
||||
uint32_t i;
|
||||
uint32_t tmp = 0;
|
||||
for (i = 0; src[i] != 0; i++) {
|
||||
if (src[i] == '.') {
|
||||
i++;
|
||||
if (mult == 0)
|
||||
break;
|
||||
else
|
||||
src[i + mult] = 0;
|
||||
}
|
||||
tmp *= 10;
|
||||
if (src[i] >= '0' && src[i] <= '9')
|
||||
tmp += src[i] - '0';
|
||||
if (i >= 15)
|
||||
return 0; // out of bounds
|
||||
}
|
||||
return tmp;
|
||||
}
|
||||
|
||||
typedef struct gpsDataNmea_s {
|
||||
bool fix;
|
||||
int32_t latitude;
|
||||
int32_t longitude;
|
||||
uint8_t numSat;
|
||||
int32_t altitude;
|
||||
uint16_t speed;
|
||||
uint16_t ground_course;
|
||||
uint16_t hdop;
|
||||
uint32_t time;
|
||||
uint32_t date;
|
||||
} gpsDataNmea_t;
|
||||
|
||||
#define NMEA_BUFFER_SIZE 16
|
||||
|
||||
static bool gpsNewFrameNMEA(char c)
|
||||
{
|
||||
static gpsDataNmea_t gps_Msg;
|
||||
|
||||
uint8_t frameOK = 0;
|
||||
static uint8_t param = 0, offset = 0, parity = 0;
|
||||
static char string[NMEA_BUFFER_SIZE];
|
||||
static uint8_t checksum_param, gps_frame = NO_FRAME;
|
||||
|
||||
switch (c) {
|
||||
case '$':
|
||||
param = 0;
|
||||
offset = 0;
|
||||
parity = 0;
|
||||
break;
|
||||
case ',':
|
||||
case '*':
|
||||
string[offset] = 0;
|
||||
if (param == 0) { //frame identification
|
||||
gps_frame = NO_FRAME;
|
||||
if (strcmp(string, "GPGGA") == 0 || strcmp(string, "GNGGA") == 0) {
|
||||
gps_frame = FRAME_GGA;
|
||||
}
|
||||
else if (strcmp(string, "GPRMC") == 0 || strcmp(string, "GNRMC") == 0) {
|
||||
gps_frame = FRAME_RMC;
|
||||
}
|
||||
}
|
||||
|
||||
switch (gps_frame) {
|
||||
case FRAME_GGA: //************* GPGGA FRAME parsing
|
||||
switch (param) {
|
||||
// case 1: // Time information
|
||||
// break;
|
||||
case 2:
|
||||
gps_Msg.latitude = GPS_coord_to_degrees(string);
|
||||
break;
|
||||
case 3:
|
||||
if (string[0] == 'S')
|
||||
gps_Msg.latitude *= -1;
|
||||
break;
|
||||
case 4:
|
||||
gps_Msg.longitude = GPS_coord_to_degrees(string);
|
||||
break;
|
||||
case 5:
|
||||
if (string[0] == 'W')
|
||||
gps_Msg.longitude *= -1;
|
||||
break;
|
||||
case 6:
|
||||
if (string[0] > '0') {
|
||||
gps_Msg.fix = true;
|
||||
} else {
|
||||
gps_Msg.fix = false;
|
||||
}
|
||||
break;
|
||||
case 7:
|
||||
gps_Msg.numSat = grab_fields(string, 0);
|
||||
break;
|
||||
case 8:
|
||||
gps_Msg.hdop = grab_fields(string, 1) * 10; // hdop
|
||||
break;
|
||||
case 9:
|
||||
gps_Msg.altitude = grab_fields(string, 1) * 10; // altitude in cm
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case FRAME_RMC: //************* GPRMC FRAME parsing
|
||||
// $GNRMC,130059.00,V,,,,,,,110917,,,N*62
|
||||
switch (param) {
|
||||
case 1:
|
||||
gps_Msg.time = grab_fields(string, 2);
|
||||
break;
|
||||
case 7:
|
||||
gps_Msg.speed = ((grab_fields(string, 1) * 5144L) / 1000L); // speed in cm/s added by Mis
|
||||
break;
|
||||
case 8:
|
||||
gps_Msg.ground_course = (grab_fields(string, 1)); // ground course deg * 10
|
||||
break;
|
||||
case 9:
|
||||
gps_Msg.date = grab_fields(string, 0);
|
||||
break;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
param++;
|
||||
offset = 0;
|
||||
if (c == '*')
|
||||
checksum_param = 1;
|
||||
else
|
||||
parity ^= c;
|
||||
break;
|
||||
case '\r':
|
||||
case '\n':
|
||||
if (checksum_param) { //parity checksum
|
||||
uint8_t checksum = 16 * ((string[0] >= 'A') ? string[0] - 'A' + 10 : string[0] - '0') + ((string[1] >= 'A') ? string[1] - 'A' + 10 : string[1] - '0');
|
||||
if (checksum == parity) {
|
||||
gpsStats.packetCount++;
|
||||
switch (gps_frame) {
|
||||
case FRAME_GGA:
|
||||
frameOK = 1;
|
||||
gpsSol.numSat = gps_Msg.numSat;
|
||||
if (gps_Msg.fix) {
|
||||
gpsSol.fixType = GPS_FIX_3D; // NMEA doesn't report fix type, assume 3D
|
||||
|
||||
gpsSol.llh.lat = gps_Msg.latitude;
|
||||
gpsSol.llh.lon = gps_Msg.longitude;
|
||||
gpsSol.llh.alt = gps_Msg.altitude;
|
||||
|
||||
// EPH/EPV are unreliable for NMEA as they are not real accuracy
|
||||
gpsSol.hdop = gpsConstrainHDOP(gps_Msg.hdop);
|
||||
gpsSol.eph = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER);
|
||||
gpsSol.epv = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER);
|
||||
gpsSol.flags.validEPE = false;
|
||||
}
|
||||
else {
|
||||
gpsSol.fixType = GPS_NO_FIX;
|
||||
}
|
||||
|
||||
// NMEA does not report VELNED
|
||||
gpsSol.flags.validVelNE = false;
|
||||
gpsSol.flags.validVelD = false;
|
||||
break;
|
||||
case FRAME_RMC:
|
||||
gpsSol.groundSpeed = gps_Msg.speed;
|
||||
gpsSol.groundCourse = gps_Msg.ground_course;
|
||||
|
||||
// This check will miss 00:00:00.00, but we shouldn't care - next report will be valid
|
||||
if (gps_Msg.date != 0 && gps_Msg.time != 0) {
|
||||
gpsSol.time.year = (gps_Msg.date % 100) + 2000;
|
||||
gpsSol.time.month = (gps_Msg.date / 100) % 100;
|
||||
gpsSol.time.day = (gps_Msg.date / 10000) % 100;
|
||||
gpsSol.time.hours = (gps_Msg.time / 1000000) % 100;
|
||||
gpsSol.time.minutes = (gps_Msg.time / 10000) % 100;
|
||||
gpsSol.time.seconds = (gps_Msg.time / 100) % 100;
|
||||
gpsSol.time.millis = (gps_Msg.time & 100) * 10;
|
||||
gpsSol.flags.validTime = true;
|
||||
}
|
||||
else {
|
||||
gpsSol.flags.validTime = false;
|
||||
}
|
||||
|
||||
break;
|
||||
} // end switch
|
||||
}
|
||||
else {
|
||||
gpsStats.errors++;
|
||||
}
|
||||
}
|
||||
checksum_param = 0;
|
||||
break;
|
||||
default:
|
||||
if (offset < (NMEA_BUFFER_SIZE-1)) { // leave 1 byte to trailing zero
|
||||
string[offset++] = c;
|
||||
|
||||
// only checksum if character is recorded and used (will cause checksum failure on dropped characters)
|
||||
if (!checksum_param)
|
||||
parity ^= c;
|
||||
}
|
||||
}
|
||||
return frameOK;
|
||||
}
|
||||
|
||||
static ptSemaphore_t semNewDataReady;
|
||||
|
||||
STATIC_PROTOTHREAD(gpsProtocolReceiverThread)
|
||||
{
|
||||
ptBegin(gpsProtocolReceiverThread);
|
||||
|
||||
while (1) {
|
||||
// Wait until there are bytes to consume
|
||||
ptWait(serialRxBytesWaiting(gpsState.gpsPort));
|
||||
|
||||
// Consume bytes until buffer empty of until we have full message received
|
||||
while (serialRxBytesWaiting(gpsState.gpsPort)) {
|
||||
uint8_t newChar = serialRead(gpsState.gpsPort);
|
||||
if (gpsNewFrameNMEA(newChar)) {
|
||||
gpsSol.flags.validVelNE = false;
|
||||
gpsSol.flags.validVelD = false;
|
||||
ptSemaphoreSignal(semNewDataReady);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
ptEnd(0);
|
||||
}
|
||||
|
||||
STATIC_PROTOTHREAD(gpsProtocolStateThreadNMEA)
|
||||
{
|
||||
ptBegin(gpsProtocolStateThreadNMEA);
|
||||
|
||||
// Change baud rate
|
||||
ptWait(isSerialTransmitBufferEmpty(gpsState.gpsPort));
|
||||
if (gpsState.gpsConfig->autoBaud != GPS_AUTOBAUD_OFF) {
|
||||
// Cycle through available baud rates and hope that we will match GPS
|
||||
serialSetBaudRate(gpsState.gpsPort, baudRates[gpsToSerialBaudRate[gpsState.autoBaudrateIndex]]);
|
||||
gpsState.autoBaudrateIndex = (gpsState.autoBaudrateIndex + 1) % GPS_BAUDRATE_COUNT;
|
||||
ptDelayMs(GPS_BAUD_CHANGE_DELAY);
|
||||
}
|
||||
else {
|
||||
// Set baud rate
|
||||
serialSetBaudRate(gpsState.gpsPort, baudRates[gpsToSerialBaudRate[gpsState.baudrateIndex]]);
|
||||
}
|
||||
|
||||
// No configuration is done for pure NMEA modules
|
||||
|
||||
// GPS setup done, reset timeout
|
||||
gpsSetProtocolTimeout(gpsState.baseTimeoutMs);
|
||||
|
||||
// GPS is ready - execute the gpsProcessNewSolutionData() based on gpsProtocolReceiverThread semaphore
|
||||
while (1) {
|
||||
ptSemaphoreWait(semNewDataReady);
|
||||
gpsProcessNewSolutionData();
|
||||
}
|
||||
|
||||
ptEnd(0);
|
||||
}
|
||||
|
||||
void gpsHandleNMEA(void)
|
||||
{
|
||||
// Run the protocol threads
|
||||
gpsProtocolReceiverThread();
|
||||
gpsProtocolStateThreadNMEA();
|
||||
|
||||
// If thread stopped - signal communication loss and restart
|
||||
if (ptIsStopped(ptGetHandle(gpsProtocolReceiverThread)) || ptIsStopped(ptGetHandle(gpsProtocolStateThreadNMEA))) {
|
||||
gpsSetState(GPS_LOST_COMMUNICATION);
|
||||
}
|
||||
}
|
||||
|
||||
void gpsRestartNMEA(void)
|
||||
{
|
||||
ptSemaphoreInit(semNewDataReady);
|
||||
ptRestart(ptGetHandle(gpsProtocolReceiverThread));
|
||||
ptRestart(ptGetHandle(gpsProtocolStateThreadNMEA));
|
||||
}
|
||||
|
||||
#endif
|
|
@ -76,9 +76,6 @@ void gpsSetProtocolTimeout(timeMs_t timeoutMs);
|
|||
extern void gpsRestartUBLOX(void);
|
||||
extern void gpsHandleUBLOX(void);
|
||||
|
||||
extern void gpsRestartNMEA(void);
|
||||
extern void gpsHandleNMEA(void);
|
||||
|
||||
extern void gpsRestartMSP(void);
|
||||
extern void gpsHandleMSP(void);
|
||||
|
||||
|
|
|
@ -69,6 +69,7 @@ static const uint32_t ubloxScanMode1[] = {
|
|||
(SBASMASK1_BITS(129) | SBASMASK1_BITS(137) | SBASMASK1_BITS(139)), // MSAS
|
||||
|
||||
(SBASMASK1_BITS(127) | SBASMASK1_BITS(128) | SBASMASK1_BITS(132)), // GAGAN
|
||||
(SBASMASK1_BITS(122)), // SPAN
|
||||
0x00000000, // NONE
|
||||
};
|
||||
|
||||
|
|
File diff suppressed because it is too large
Load diff
|
@ -274,6 +274,8 @@ typedef enum {
|
|||
OSD_PILOT_NAME,
|
||||
OSD_PAN_SERVO_CENTRED,
|
||||
OSD_MULTI_FUNCTION,
|
||||
OSD_ODOMETER,
|
||||
OSD_PILOT_LOGO,
|
||||
OSD_ITEM_COUNT // MUST BE LAST
|
||||
} osd_items_e;
|
||||
|
||||
|
@ -412,9 +414,7 @@ typedef struct osdConfig_s {
|
|||
#ifdef USE_WIND_ESTIMATOR
|
||||
bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance
|
||||
#endif
|
||||
|
||||
uint8_t coordinate_digits;
|
||||
|
||||
bool osd_failsafe_switch_layout;
|
||||
uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE
|
||||
uint8_t plus_code_short;
|
||||
|
@ -448,6 +448,9 @@ typedef struct osdConfig_s {
|
|||
char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3.
|
||||
uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3.
|
||||
bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch.
|
||||
bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo.
|
||||
uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width.
|
||||
uint16_t arm_screen_display_time; // Length of time the arm screen is displayed
|
||||
} osdConfig_t;
|
||||
|
||||
PG_DECLARE(osdConfig_t, osdConfig);
|
||||
|
@ -483,7 +486,7 @@ void osdStartedSaveProcess(void);
|
|||
void osdShowEEPROMSavedNotification(void);
|
||||
|
||||
void osdCrosshairPosition(uint8_t *x, uint8_t *y);
|
||||
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length);
|
||||
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length, bool leadingZeros);
|
||||
void osdFormatAltitudeSymbol(char *buff, int32_t alt);
|
||||
void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D, bool _max);
|
||||
// Returns a heading angle in degrees normalized to [0, 360).
|
||||
|
|
|
@ -256,18 +256,18 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu
|
|||
case OSD_UNIT_IMPERIAL:
|
||||
{
|
||||
if (poiType == 1) {
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 4, 4);
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 4, 4, false);
|
||||
} else {
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3);
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3, false);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case OSD_UNIT_GA:
|
||||
{
|
||||
if (poiType == 1) {
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 4, 4);
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 4, 4, false);
|
||||
} else {
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 3, 3);
|
||||
osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 3, 3, false);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -278,9 +278,9 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu
|
|||
case OSD_UNIT_METRIC:
|
||||
{
|
||||
if (poiType == 1) {
|
||||
osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 4, 4);
|
||||
osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 4, 4, false);
|
||||
} else {
|
||||
osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3);
|
||||
osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3, false);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -38,7 +38,7 @@ int digitCount(int32_t value)
|
|||
}
|
||||
|
||||
|
||||
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length)
|
||||
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length, bool leadingZeros)
|
||||
{
|
||||
char *ptr = buff;
|
||||
char *dec;
|
||||
|
@ -86,7 +86,11 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma
|
|||
// Done counting. Time to write the characters.
|
||||
// Write spaces at the start
|
||||
while (remaining > 0) {
|
||||
if (leadingZeros)
|
||||
*ptr = '0';
|
||||
else
|
||||
*ptr = SYM_BLANK;
|
||||
|
||||
ptr++;
|
||||
remaining--;
|
||||
}
|
||||
|
@ -98,7 +102,11 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma
|
|||
// Add any needed remaining leading spaces
|
||||
while(rem_spaces > 0)
|
||||
{
|
||||
if (leadingZeros)
|
||||
*ptr = '0';
|
||||
else
|
||||
*ptr = SYM_BLANK;
|
||||
|
||||
ptr++;
|
||||
remaining--;
|
||||
rem_spaces--;
|
||||
|
|
|
@ -33,6 +33,6 @@ int digitCount(int32_t value);
|
|||
* of the same length. If the value doesn't fit into the provided length
|
||||
* it will be divided by scale and true will be returned.
|
||||
*/
|
||||
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length);
|
||||
bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length, bool leadingZeros);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -92,3 +92,5 @@
|
|||
#define MSP2_INAV_LED_STRIP_CONFIG_EX 0x2048
|
||||
#define MSP2_INAV_SET_LED_STRIP_CONFIG_EX 0x2049
|
||||
|
||||
#define MSP2_INAV_RATE_DYNAMICS 0x2060
|
||||
#define MSP2_INAV_SET_RATE_DYNAMICS 0x2061
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
#include "fc/settings.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
@ -69,6 +69,7 @@
|
|||
#define MR_RTH_CLIMB_OVERSHOOT_CM 100 // target this amount of cm *above* the target altitude to ensure it is actually reached (Vz > 0 at target alt)
|
||||
#define MR_RTH_CLIMB_MARGIN_MIN_CM 100 // start cruising home this amount of cm *before* reaching the cruise altitude (while continuing the ascend)
|
||||
#define MR_RTH_CLIMB_MARGIN_PERCENT 15 // on high RTH altitudes use even bigger margin - percent of the altitude set
|
||||
#define MR_RTH_LAND_MARGIN_CM 2000 // pause landing if this amount of cm *before* remaining to the home point (2D distance)
|
||||
|
||||
// Planes:
|
||||
#define FW_RTH_CLIMB_OVERSHOOT_CM 100
|
||||
|
@ -308,6 +309,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_FINIS
|
|||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_INITIALIZE(navigationFSMState_t previousState);
|
||||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_WAIT(navigationFSMState_t previousState);
|
||||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_IN_PROGRESS(navigationFSMState_t previousState);
|
||||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE(navigationFSMState_t previousState);
|
||||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS(navigationFSMState_t previousState);
|
||||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_ABORT(navigationFSMState_t previousState);
|
||||
|
||||
static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
||||
/** Idle state ******************************************************/
|
||||
|
@ -328,6 +332,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
[NAV_FSM_EVENT_SWITCH_TO_LAUNCH] = NAV_STATE_LAUNCH_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE,
|
||||
}
|
||||
},
|
||||
|
||||
|
@ -596,6 +601,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
[NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE,
|
||||
}
|
||||
},
|
||||
|
||||
|
@ -654,6 +660,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
[NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE,
|
||||
}
|
||||
},
|
||||
|
||||
|
@ -807,6 +814,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
[NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE,
|
||||
}
|
||||
},
|
||||
|
||||
|
@ -941,6 +949,52 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
||||
}
|
||||
},
|
||||
|
||||
/** MIXER AUTOMATED TRANSITION mode, alternated althod ***************************************************/
|
||||
[NAV_STATE_MIXERAT_INITIALIZE] = {
|
||||
.persistentId = NAV_PERSISTENT_ID_MIXERAT_INITIALIZE,
|
||||
.onEntry = navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE,
|
||||
.timeoutMs = 0,
|
||||
.stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT | NAV_MIXERAT,
|
||||
.mapToFlightModes = NAV_ALTHOLD_MODE,
|
||||
.mwState = MW_NAV_STATE_NONE,
|
||||
.mwError = MW_NAV_ERROR_NONE,
|
||||
.onEvent = {
|
||||
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_MIXERAT_IN_PROGRESS,
|
||||
[NAV_FSM_EVENT_ERROR] = NAV_STATE_IDLE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
||||
}
|
||||
},
|
||||
|
||||
[NAV_STATE_MIXERAT_IN_PROGRESS] = {
|
||||
.persistentId = NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS,
|
||||
.onEntry = navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS,
|
||||
.timeoutMs = 10,
|
||||
.stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT | NAV_MIXERAT,
|
||||
.mapToFlightModes = NAV_ALTHOLD_MODE,
|
||||
.mwState = MW_NAV_STATE_NONE,
|
||||
.mwError = MW_NAV_ERROR_NONE,
|
||||
.onEvent = {
|
||||
[NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_MIXERAT_IN_PROGRESS, // re-process the state
|
||||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_MIXERAT_ABORT,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME] = NAV_STATE_RTH_HEAD_HOME, //switch to its pending state
|
||||
[NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING] = NAV_STATE_RTH_LANDING, //switch to its pending state
|
||||
}
|
||||
},
|
||||
[NAV_STATE_MIXERAT_ABORT] = {
|
||||
.persistentId = NAV_PERSISTENT_ID_MIXERAT_ABORT,
|
||||
.onEntry = navOnEnteringState_NAV_STATE_MIXERAT_ABORT, //will not switch to its pending state
|
||||
.timeoutMs = 10,
|
||||
.stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT,
|
||||
.mapToFlightModes = NAV_ALTHOLD_MODE,
|
||||
.mwState = MW_NAV_STATE_NONE,
|
||||
.mwError = MW_NAV_ERROR_NONE,
|
||||
.onEvent = {
|
||||
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_IDLE,
|
||||
[NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE,
|
||||
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
static navigationFSMStateFlags_t navGetStateFlags(navigationFSMState_t state)
|
||||
|
@ -1366,6 +1420,10 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HEAD_HOME(navigatio
|
|||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||
}
|
||||
|
||||
if (checkMixerATRequired(MIXERAT_REQUEST_RTH) && (calculateDistanceToDestination(&posControl.rthState.homePosition.pos) > (navConfig()->fw.loiter_radius * 3))){
|
||||
return NAV_FSM_EVENT_SWITCH_TO_MIXERAT;
|
||||
}
|
||||
|
||||
if (navConfig()->general.flags.rth_use_linear_descent && navConfig()->general.rth_home_altitude > 0) {
|
||||
// Check linear descent status
|
||||
uint32_t homeDistance = calculateDistanceToDestination(&posControl.rthState.homePosition.pos);
|
||||
|
@ -1457,11 +1515,21 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF
|
|||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||
}
|
||||
|
||||
float descentVelLimited = 0;
|
||||
int32_t landingElevation = posControl.rthState.homeTmpWaypoint.z;
|
||||
if (checkMixerATRequired(MIXERAT_REQUEST_LAND)){
|
||||
return NAV_FSM_EVENT_SWITCH_TO_MIXERAT;
|
||||
}
|
||||
|
||||
float descentVelLimited = 0;
|
||||
|
||||
fpVector3_t tmpHomePos = posControl.rthState.homeTmpWaypoint;
|
||||
uint32_t remaning_distance = calculateDistanceToDestination(&tmpHomePos);
|
||||
|
||||
int32_t landingElevation = posControl.rthState.homeTmpWaypoint.z;
|
||||
if(STATE(MULTIROTOR) && (remaning_distance>MR_RTH_LAND_MARGIN_CM)){
|
||||
descentVelLimited = navConfig()->general.land_minalt_vspd;
|
||||
}
|
||||
// A safeguard - if surface altitude sensors is available and it is reading < 50cm altitude - drop to low descend speed
|
||||
if ((posControl.flags.estAglStatus == EST_TRUSTED) && posControl.actualState.agl.pos.z < 50.0f) {
|
||||
else if ((posControl.flags.estAglStatus == EST_TRUSTED) && posControl.actualState.agl.pos.z < 50.0f) {
|
||||
// land_descent_rate == 200 : descend speed = 30 cm/s, gentle touchdown
|
||||
// Do not allow descent velocity slower than -30cm/s so the landing detector works.
|
||||
descentVelLimited = navConfig()->general.land_minalt_vspd;
|
||||
|
@ -1854,6 +1922,70 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_IN_PROGRESS(navi
|
|||
return NAV_FSM_EVENT_NONE;
|
||||
}
|
||||
|
||||
navigationFSMState_t navMixerATPendingState = NAV_STATE_IDLE;
|
||||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE(navigationFSMState_t previousState)
|
||||
{
|
||||
const navigationFSMStateFlags_t prevFlags = navGetStateFlags(previousState);
|
||||
|
||||
// Prepare altitude controller if idle, RTH or WP modes active or surface mode status changed
|
||||
if (!(prevFlags & NAV_CTL_ALT) || (prevFlags & NAV_AUTO_RTH) || (prevFlags & NAV_AUTO_WP)) {
|
||||
resetAltitudeController(false);
|
||||
setupAltitudeController();
|
||||
}
|
||||
setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z);
|
||||
navMixerATPendingState = previousState;
|
||||
return NAV_FSM_EVENT_SUCCESS;
|
||||
}
|
||||
|
||||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS(navigationFSMState_t previousState)
|
||||
{
|
||||
UNUSED(previousState);
|
||||
mixerProfileATRequest_e required_action;
|
||||
switch (navMixerATPendingState)
|
||||
{
|
||||
case NAV_STATE_RTH_HEAD_HOME:
|
||||
required_action = MIXERAT_REQUEST_RTH;
|
||||
break;
|
||||
case NAV_STATE_RTH_LANDING:
|
||||
required_action = MIXERAT_REQUEST_LAND;
|
||||
break;
|
||||
default:
|
||||
required_action = MIXERAT_REQUEST_NONE;
|
||||
break;
|
||||
}
|
||||
if (mixerATUpdateState(required_action)){
|
||||
// MixerAT is done, switch to next state
|
||||
resetPositionController();
|
||||
resetAltitudeController(false); // Make sure surface tracking is not enabled uses global altitude, not AGL
|
||||
mixerATUpdateState(MIXERAT_REQUEST_ABORT);
|
||||
switch (navMixerATPendingState)
|
||||
{
|
||||
case NAV_STATE_RTH_HEAD_HOME:
|
||||
setupAltitudeController();
|
||||
return NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME;
|
||||
break;
|
||||
case NAV_STATE_RTH_LANDING:
|
||||
setupAltitudeController();
|
||||
return NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING;
|
||||
break;
|
||||
default:
|
||||
return NAV_FSM_EVENT_SWITCH_TO_IDLE;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z);
|
||||
|
||||
return NAV_FSM_EVENT_NONE;
|
||||
}
|
||||
|
||||
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_ABORT(navigationFSMState_t previousState)
|
||||
{
|
||||
UNUSED(previousState);
|
||||
mixerATUpdateState(MIXERAT_REQUEST_ABORT);
|
||||
return NAV_FSM_EVENT_SUCCESS;
|
||||
}
|
||||
|
||||
static navigationFSMState_t navSetNewFSMState(navigationFSMState_t newState)
|
||||
{
|
||||
navigationFSMState_t previousState;
|
||||
|
@ -2747,6 +2879,9 @@ static void updateNavigationFlightStatistics(void)
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Total travel distance in cm
|
||||
*/
|
||||
uint32_t getTotalTravelDistance(void)
|
||||
{
|
||||
return lrintf(posControl.totalTripDistance);
|
||||
|
@ -3782,14 +3917,14 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
|
|||
}
|
||||
|
||||
// CRUISE has priority over COURSE_HOLD and AH
|
||||
if (IS_RC_MODE_ACTIVE(BOXNAVCRUISE)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXNAVCRUISE) && STATE(AIRPLANE)) {
|
||||
if ((FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) || (canActivatePosHold && canActivateAltHold))
|
||||
return NAV_FSM_EVENT_SWITCH_TO_CRUISE;
|
||||
}
|
||||
|
||||
// PH has priority over COURSE_HOLD
|
||||
// CRUISE has priority on AH
|
||||
if (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) && STATE(AIRPLANE)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXNAVALTHOLD) && ((FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) || (canActivatePosHold && canActivateAltHold))) {
|
||||
return NAV_FSM_EVENT_SWITCH_TO_CRUISE;
|
||||
}
|
||||
|
@ -3803,8 +3938,7 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
|
|||
if ((FLIGHT_MODE(NAV_ALTHOLD_MODE)) || (canActivateAltHold))
|
||||
return NAV_FSM_EVENT_SWITCH_TO_ALTHOLD;
|
||||
}
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
canActivateWaypoint = false;
|
||||
|
||||
// Launch mode can be activated if feature FW_LAUNCH is enabled or BOX is turned on prior to arming (avoid switching to LAUNCH in flight)
|
||||
|
@ -4203,15 +4337,6 @@ void navigationInit(void)
|
|||
/* Use system config */
|
||||
navigationUsePIDs();
|
||||
|
||||
if (
|
||||
mixerConfig()->platformType == PLATFORM_BOAT ||
|
||||
mixerConfig()->platformType == PLATFORM_ROVER ||
|
||||
navConfig()->fw.useFwNavYawControl
|
||||
) {
|
||||
ENABLE_STATE(FW_HEADING_USE_YAW);
|
||||
} else {
|
||||
DISABLE_STATE(FW_HEADING_USE_YAW);
|
||||
}
|
||||
#if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE)
|
||||
/* configure WP missions at boot */
|
||||
#ifdef USE_MULTI_MISSION
|
||||
|
@ -4272,7 +4397,7 @@ void abortForcedRTH(void)
|
|||
rthState_e getStateOfForcedRTH(void)
|
||||
{
|
||||
/* If forced RTH activated and in AUTO_RTH or EMERG state */
|
||||
if (posControl.flags.forcedRTHActivated && (navGetStateFlags(posControl.navState) & (NAV_AUTO_RTH | NAV_CTL_EMERG))) {
|
||||
if (posControl.flags.forcedRTHActivated && (navGetStateFlags(posControl.navState) & (NAV_AUTO_RTH | NAV_CTL_EMERG | NAV_MIXERAT))) {
|
||||
if (posControl.navState == NAV_STATE_RTH_FINISHED || posControl.navState == NAV_STATE_EMERGENCY_LANDING_FINISHED) {
|
||||
return RTH_HAS_LANDED;
|
||||
}
|
||||
|
@ -4367,7 +4492,7 @@ bool navigationRTHAllowsLanding(void)
|
|||
|
||||
bool isNavLaunchEnabled(void)
|
||||
{
|
||||
return IS_RC_MODE_ACTIVE(BOXNAVLAUNCH) || feature(FEATURE_FW_LAUNCH);
|
||||
return (IS_RC_MODE_ACTIVE(BOXNAVLAUNCH) || feature(FEATURE_FW_LAUNCH)) && STATE(AIRPLANE);
|
||||
}
|
||||
|
||||
bool abortLaunchAllowed(void)
|
||||
|
|
|
@ -39,6 +39,7 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
@ -293,6 +294,10 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod)
|
|||
needToCalculateCircularLoiter = isNavHoldPositionActive() &&
|
||||
(distanceToActualTarget <= (navLoiterRadius / TAN_15DEG)) &&
|
||||
(distanceToActualTarget > 50.0f);
|
||||
//if vtol landing is required, fly straight to homepoint
|
||||
if ((posControl.navState == NAV_STATE_RTH_HEAD_HOME) && navigationRTHAllowsLanding() && checkMixerATRequired(MIXERAT_REQUEST_LAND)){
|
||||
needToCalculateCircularLoiter = false;
|
||||
}
|
||||
|
||||
/* WP turn smoothing with 2 options, 1: pass through WP, 2: cut inside turn missing WP
|
||||
* Works for turns > 30 degs and < 160 degs.
|
||||
|
|
|
@ -157,6 +157,7 @@ typedef enum {
|
|||
NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD,
|
||||
NAV_FSM_EVENT_SWITCH_TO_CRUISE,
|
||||
NAV_FSM_EVENT_SWITCH_TO_COURSE_ADJ,
|
||||
NAV_FSM_EVENT_SWITCH_TO_MIXERAT,
|
||||
|
||||
NAV_FSM_EVENT_STATE_SPECIFIC_1, // State-specific event
|
||||
NAV_FSM_EVENT_STATE_SPECIFIC_2, // State-specific event
|
||||
|
@ -164,6 +165,7 @@ typedef enum {
|
|||
NAV_FSM_EVENT_STATE_SPECIFIC_4, // State-specific event
|
||||
NAV_FSM_EVENT_STATE_SPECIFIC_5, // State-specific event
|
||||
NAV_FSM_EVENT_STATE_SPECIFIC_6, // State-specific event
|
||||
NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME = NAV_FSM_EVENT_STATE_SPECIFIC_3,
|
||||
NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING = NAV_FSM_EVENT_STATE_SPECIFIC_1,
|
||||
NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_RTH_LAND = NAV_FSM_EVENT_STATE_SPECIFIC_1,
|
||||
NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED = NAV_FSM_EVENT_STATE_SPECIFIC_2,
|
||||
|
@ -228,6 +230,9 @@ typedef enum {
|
|||
NAV_PERSISTENT_ID_UNUSED_4 = 37, // was NAV_STATE_WAYPOINT_HOVER_ABOVE_HOME
|
||||
NAV_PERSISTENT_ID_RTH_TRACKBACK = 38,
|
||||
|
||||
NAV_PERSISTENT_ID_MIXERAT_INITIALIZE = 39,
|
||||
NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS = 40,
|
||||
NAV_PERSISTENT_ID_MIXERAT_ABORT = 41,
|
||||
} navigationPersistentId_e;
|
||||
|
||||
typedef enum {
|
||||
|
@ -275,6 +280,10 @@ typedef enum {
|
|||
NAV_STATE_CRUISE_IN_PROGRESS,
|
||||
NAV_STATE_CRUISE_ADJUSTING,
|
||||
|
||||
NAV_STATE_MIXERAT_INITIALIZE,
|
||||
NAV_STATE_MIXERAT_IN_PROGRESS,
|
||||
NAV_STATE_MIXERAT_ABORT,
|
||||
|
||||
NAV_STATE_COUNT,
|
||||
} navigationFSMState_t;
|
||||
|
||||
|
@ -304,6 +313,8 @@ typedef enum {
|
|||
/* Additional flags */
|
||||
NAV_CTL_LAND = (1 << 14),
|
||||
NAV_AUTO_WP_DONE = (1 << 15), //Waypoint mission reached the last waypoint and is idling
|
||||
|
||||
NAV_MIXERAT = (1 << 16), //MIXERAT in progress
|
||||
} navigationFSMStateFlags_t;
|
||||
|
||||
typedef struct {
|
||||
|
|
|
@ -46,6 +46,7 @@
|
|||
#include "sensors/rangefinder.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
#include "drivers/io_port_expander.h"
|
||||
#include "io/osd_common.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
|
@ -424,6 +425,7 @@ static int logicConditionCompute(
|
|||
pidInit();
|
||||
pidInitFilters();
|
||||
schedulePidGainsUpdate();
|
||||
navigationUsePIDs(); //set navigation pid gains
|
||||
profileChanged = true;
|
||||
}
|
||||
return profileChanged;
|
||||
|
@ -702,6 +704,10 @@ static int logicConditionGetFlightOperandValue(int operand) {
|
|||
return constrain(attitude.values.pitch / 10, -180, 180);
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW: // deg
|
||||
return constrain(attitude.values.yaw / 10, 0, 360);
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_IS_ARMED: // 0/1
|
||||
return ARMING_FLAG(ARMED) ? 1 : 0;
|
||||
break;
|
||||
|
@ -770,6 +776,14 @@ static int logicConditionGetFlightOperandValue(int operand) {
|
|||
return getConfigProfile() + 1;
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE: // int
|
||||
return currentMixerProfileIndex + 1;
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE: //0,1
|
||||
return isMixerTransitionMixing ? 1 : 0;
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS:
|
||||
return getLoiterRadius(navConfig()->fw.loiter_radius);
|
||||
|
||||
|
|
|
@ -135,6 +135,9 @@ typedef enum {
|
|||
LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS, //0,1,2 // 35
|
||||
LOGIC_CONDITION_OPERAND_FLIGHT_AGL, //0,1,2 // 36
|
||||
LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW, //int // 37
|
||||
LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE, //int // 38
|
||||
LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE, //0,1 // 39
|
||||
LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW, // deg // 40
|
||||
} logicFlightOperands_e;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -26,8 +26,10 @@
|
|||
|
||||
#include "programming/logic_condition.h"
|
||||
#include "programming/pid.h"
|
||||
#include "flight/mixer_profile.h"
|
||||
|
||||
void programmingFrameworkUpdateTask(timeUs_t currentTimeUs) {
|
||||
programmingPidUpdateTask(currentTimeUs);
|
||||
outputProfileUpdateTask(currentTimeUs);
|
||||
logicConditionUpdateTask(currentTimeUs);
|
||||
}
|
|
@ -63,7 +63,12 @@
|
|||
#define JETIEXBUS_BAUDRATE 125000 // EX Bus 125000; EX Bus HS 250000 not supported
|
||||
#define JETIEXBUS_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO)
|
||||
#define JETIEXBUS_MIN_FRAME_GAP 1000
|
||||
#define JETIEXBUS_CHANNEL_COUNT 16 // most Jeti TX transmit 16 channels
|
||||
|
||||
#ifdef USE_24CHANNELS
|
||||
#define JETIEXBUS_CHANNEL_COUNT 24
|
||||
#else
|
||||
#define JETIEXBUS_CHANNEL_COUNT 16
|
||||
#endif
|
||||
|
||||
|
||||
#define EXBUS_START_CHANNEL_FRAME (0x3E)
|
||||
|
|
|
@ -83,7 +83,11 @@ typedef enum {
|
|||
SERIALRX_FBUS,
|
||||
} rxSerialReceiverType_e;
|
||||
|
||||
#ifdef USE_24CHANNELS
|
||||
#define MAX_SUPPORTED_RC_CHANNEL_COUNT 26
|
||||
#else
|
||||
#define MAX_SUPPORTED_RC_CHANNEL_COUNT 18
|
||||
#endif
|
||||
|
||||
#define NON_AUX_CHANNEL_COUNT 4
|
||||
#define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT)
|
||||
|
|
|
@ -564,7 +564,7 @@ void currentMeterUpdate(timeUs_t timeDelta)
|
|||
if (allNav || autoNav) { // account for motors running in Nav modes with throttle low + motor stop
|
||||
throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000;
|
||||
} else {
|
||||
throttleOffset = (throttleStickIsLow() && feature(FEATURE_MOTOR_STOP)) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000;
|
||||
throttleOffset = (throttleStickIsLow() && ifMotorstopFeatureEnabled()) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000;
|
||||
}
|
||||
int32_t throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50);
|
||||
amperage += throttleFactor * batteryMetersConfig()->current.scale / 1000;
|
||||
|
|
29
src/main/target/AIKONF4/config.c
Normal file
29
src/main/target/AIKONF4/config.c
Normal file
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
// To improve backwards compatibility with INAV versions 6.x and older
|
||||
timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS;
|
||||
}
|
|
@ -29,12 +29,12 @@
|
|||
|
||||
timerHardware_t timerHardware[] = {
|
||||
// DEF_TIM(TIM2, CH2, PB3, TIM_USE_CAMERA_CONTROL, 0, 0), // There is not camera control in INAV
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S5
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S6
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_PPM | TIM_USE_LED, 0, 0), // LED & PPM (DMA1_ST0_CH2)
|
||||
};
|
||||
|
||||
|
|
|
@ -24,20 +24,20 @@
|
|||
#include "drivers/bus.h"
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D1_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D1_ST2
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT D1_ST6
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_ANY, 0, 0), // S5_OUT / LED
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0, 0), // LED D1_ST0, n/a on older AIRBOTF4
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO | TIM_USE_ANY, 0, 0), // S5_OUT / LED
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED | TIM_USE_ANY, 0, 0), // LED D1_ST0, n/a on older AIRBOTF4
|
||||
|
||||
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port)
|
||||
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S3_IN
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S4_IN
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S5_IN
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S6_IN
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S3_IN
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S4_IN
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S5_IN
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S6_IN
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
|
|
@ -45,10 +45,10 @@ timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // Cam control, SS, UNUSED
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0), //S1
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), //S2
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0), //S3
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), //S4
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), //S1
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), //S2
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), //S3
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), //S4
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
|
|
@ -28,14 +28,14 @@ timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0, 0), // PWM3 - PB1 RC3 - DMA1_ST7
|
||||
DEF_TIM(TIM1, CH2, PB14, TIM_USE_PWM, 0, 1), // PWM4 - PA14 RC4 - DMA2_ST2
|
||||
DEF_TIM(TIM1, CH3, PB15, TIM_USE_PWM | TIM_USE_LED, 0, 0), // PWM5 - PA15 RC5 - DMA2_ST6
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // PWM6 - PB8 OUT1 - DMA1_ST7
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // PWM7 - PB9 OUT2 - DMA_NONE
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM8 - PA0 OUT3 - DMA1_ST2
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM9 - PA1 OUT4 - DMA1_ST4
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM10 - PC6 OUT5 - DMA2_ST2
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM11 - PC7 OUT6 - DMA2_ST3
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // PWM13 - PC8 OUT7 - DMA2_ST4
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM13 - PC9 OUT8 - DMA2_ST7
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM6 - PB8 OUT1 - DMA1_ST7
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM7 - PB9 OUT2 - DMA_NONE
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM8 - PA0 OUT3 - DMA1_ST2
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM9 - PA1 OUT4 - DMA1_ST4
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM10 - PC6 OUT5 - DMA2_ST2
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM11 - PC7 OUT6 - DMA2_ST3
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // PWM13 - PC8 OUT7 - DMA2_ST4
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM13 - PC9 OUT8 - DMA2_ST7
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
|
|
@ -152,7 +152,7 @@
|
|||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_MOTOR_STOP | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
|
|
@ -24,18 +24,18 @@
|
|||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM | TIM_USE_LED, 0, 1), // PPM - DMA2_ST1
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_SERVO, 0, 0), // PWM1 - DMA2_ST2
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_SERVO, 0, 0), // PWM2 - DMA1_ST5
|
||||
DEF_TIM(TIM8, CH2N, PB14, TIM_USE_MC_SERVO, 0, 0), // PWM3 - DMA2_ST3
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO, 0, 0), // PWM4 - DMA1_ST7
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_SERVO, 0, 0), // PWM5 - DMA1_ST2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM6 - DMA2_ST4
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM7 - DMA1_ST4
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM8 - DMA2_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM9 - DMA1_ST2
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM10 - DMA2_ST6
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM11 - DMA1_ST7
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM12 - DMA_NONE
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM1 - DMA2_ST2
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM2 - DMA1_ST5
|
||||
DEF_TIM(TIM8, CH2N, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM3 - DMA2_ST3
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM4 - DMA1_ST7
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM5 - DMA1_ST2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM6 - DMA2_ST4
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM7 - DMA1_ST4
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM8 - DMA2_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM9 - DMA1_ST2
|
||||
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM10 - DMA2_ST6
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM11 - DMA1_ST7
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM12 - DMA_NONE
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
|
|
@ -165,7 +165,7 @@
|
|||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_MOTOR_STOP | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define RX_CHANNELS_TAER
|
||||
|
|
|
@ -30,16 +30,16 @@ timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S6_IN
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S5_IN
|
||||
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S10_OUT 16
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6_OUT 12
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT 11
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT 7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT 8
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT 9
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT 10
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7_OUT 13
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8_OUT 14
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S9_OUT 15
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S10_OUT 16
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT 12
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT 11
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT 7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT 8
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT 9
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT 10
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S7_OUT 13
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S8_OUT 14
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S9_OUT 15
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
|
|
@ -25,21 +25,21 @@
|
|||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN
|
||||
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S6_IN DMA2_ST7
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_IN DMA2_ST7
|
||||
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S10_OUT 1 DMA1_ST7
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S6_OUT 2 DMA1_ST0
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5_OUT
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT 4 DMA1_ST1 DMA1_ST3
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT 3 DMA1_ST4
|
||||
DEF_TIM(TIM9, CH2, PE6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S4_OUT DMA1_ST5
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7_OUT DMA1_ST2
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), // S8_OUT DMA1_ST6
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S9_OUT DMA1_ST4
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S10_OUT 1 DMA1_ST7
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT 2 DMA1_ST0
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_OUT
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT 4 DMA1_ST1 DMA1_ST3
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT 3 DMA1_ST4
|
||||
DEF_TIM(TIM9, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_OUT DMA1_ST5
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7_OUT DMA1_ST2
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), // S8_OUT DMA1_ST6
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S9_OUT DMA1_ST4
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
|
|
@ -33,16 +33,16 @@ timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S6_IN DMA2_ST7
|
||||
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S10_OUT 1 DMA1_ST7
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S6_OUT 2 DMA1_ST1
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5_OUT 3 DMA1_ST3
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1_OUT 4 DMA1_ST7 DMA1_ST6
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT DMA1_ST4
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3_OUT DMA2_ST6 DMA2_ST2
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), // S4_OUT DMA1_ST5
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7_OUT DMA1_ST2
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S8_OUT DMA2_ST6
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S9_OUT DMA1_ST4
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S10_OUT 1 DMA1_ST7
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT 2 DMA1_ST1
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_OUT 3 DMA1_ST3
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1_OUT 4 DMA1_ST7 DMA1_ST6
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT DMA1_ST4
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3_OUT DMA2_ST6 DMA2_ST2
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), // S4_OUT DMA1_ST5
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7_OUT DMA1_ST2
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S8_OUT DMA2_ST6
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S9_OUT DMA1_ST4
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
|
|
@ -30,10 +30,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_C
|
|||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM2, CH2, PA10, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
|
||||
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_LED, 0, 0), // LED
|
||||
};
|
||||
|
|
|
@ -27,16 +27,16 @@
|
|||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S3
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S4
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4
|
||||
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S6
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S6
|
||||
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S8
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S8
|
||||
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0 ), // LED_STRIP
|
||||
|
||||
|
|
1
src/main/target/AOCODARCF722AIO/CMakeLists.txt
Normal file
1
src/main/target/AOCODARCF722AIO/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32f722xe(AOCODARCF722AIO)
|
44
src/main/target/AOCODARCF722AIO/config.c
Normal file
44
src/main/target/AOCODARCF722AIO/config.c
Normal file
|
@ -0,0 +1,44 @@
|
|||
/*
|
||||
* @Author: g05047
|
||||
* @Date: 2023-03-22 17:15:53
|
||||
* @LastEditors: g05047
|
||||
* @LastEditTime: 2023-03-23 16:21:45
|
||||
* @Description: file content
|
||||
*/
|
||||
/*
|
||||
* 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 "fc/fc_msp_box.h"
|
||||
#include "io/piniobox.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
|
||||
compassConfigMutable()->mag_align = CW90_DEG;
|
||||
|
||||
// barometerConfigMutable()->baro_hardware = BARO_DPS310;
|
||||
|
||||
boardAlignmentMutable()->rollDeciDegrees = -450;
|
||||
|
||||
}
|
40
src/main/target/AOCODARCF722AIO/target.c
Normal file
40
src/main/target/AOCODARCF722AIO/target.c
Normal file
|
@ -0,0 +1,40 @@
|
|||
/*
|
||||
* 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/sensor.h"
|
||||
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN);
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S2
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S3
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S4
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
175
src/main/target/AOCODARCF722AIO/target.h
Normal file
175
src/main/target/AOCODARCF722AIO/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 "F722AIO"
|
||||
#define USBD_PRODUCT_STRING "AocodaRCF722AIO"
|
||||
|
||||
#define LED0 PA4
|
||||
|
||||
#define USE_BEEPER
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
/*** UART ***/
|
||||
#define USB_IO
|
||||
#define USE_VCP
|
||||
|
||||
#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 PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PA1
|
||||
#define UART4_TX_PIN PA0
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define SERIAL_PORT_COUNT 6
|
||||
|
||||
/*** 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_MPU6500
|
||||
#define MPU6500_CS_PIN PB2
|
||||
#define MPU6500_SPI_BUS BUS_SPI1
|
||||
#define MPU6500_EXTI_PIN PC4
|
||||
|
||||
#define IMU_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define MPU6000_CS_PIN PB2
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_EXTI_PIN PC4
|
||||
|
||||
#define IMU_MPU6000_ALIGN CW180_DEG
|
||||
|
||||
#define USE_IMU_ICM42605
|
||||
#define ICM42605_CS_PIN PB2
|
||||
#define ICM42605_SPI_BUS BUS_SPI1
|
||||
#define ICM42605_EXTI_PIN PC4
|
||||
|
||||
#define IMU_ICM42605_ALIGN CW180_DEG
|
||||
|
||||
/*** I2C (Baro & Mag) ***/
|
||||
#define USE_I2C
|
||||
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
// Baro
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_SPL06
|
||||
#define USE_BARO_DPS310
|
||||
|
||||
// Mag
|
||||
#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
|
||||
|
||||
/*** Onboard Flash ***/
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_MISO_PIN PC11
|
||||
#define SPI3_MOSI_PIN PC12
|
||||
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PD2
|
||||
|
||||
#define W25N01G_SPI_BUS BUS_SPI3
|
||||
#define W25N01G_CS_PIN PD2
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
/*** OSD ***/
|
||||
#define USE_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
|
||||
|
||||
/*** ADC ***/
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC2
|
||||
#define ADC_CHANNEL_2_PIN PC0
|
||||
#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
|
||||
|
||||
/*** LED ***/
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA8
|
||||
|
||||
/*** Optical Flow & Lidar ***/
|
||||
#define USE_RANGEFINDER
|
||||
#define USE_RANGEFINDER_MSP
|
||||
#define USE_OPFLOW
|
||||
#define USE_OPFLOW_MSP
|
||||
|
||||
/*** Misc ***/
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX)
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_CRSF
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
|
||||
#define CURRENT_METER_SCALE 250
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
|
@ -32,15 +32,15 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS,
|
|||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), //PPM
|
||||
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2, 2, 7)
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2, 3, 7)
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 D(2, 4, 7)
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 D(2, 7, 7)
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(2, 2, 7)
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(2, 3, 7)
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(2, 4, 7)
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(2, 7, 7)
|
||||
|
||||
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S5 D(1, 7, 5)
|
||||
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S6 D(1, 2, 5)
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S7 D(1, 0, 2)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S8 D(1, 3, 2)
|
||||
DEF_TIM(TIM8, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(1, 7, 5)
|
||||
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1, 2, 5)
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1, 0, 2)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 D(1, 3, 2)
|
||||
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), // LED_TRIP
|
||||
};
|
||||
|
|
|
@ -39,20 +39,20 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS,
|
|||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM, RX1
|
||||
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1, 4, 5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1, 5, 4)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 D(1, 7, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 D(1, 2, 5)
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1, 4, 5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1, 5, 4)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(1, 7, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(1, 2, 5)
|
||||
|
||||
#if defined(AOCODARCF7MINI_V2)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 D(2, 4, 7)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(2, 7, 7)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(2, 4, 7)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(2, 7, 7)
|
||||
#else
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(1, 6, 3)
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1, 6, 3)
|
||||
#endif
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 D(1, 0, 2)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 D(1, 3, 2)
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1, 0, 2)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 D(1, 3, 2)
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED
|
||||
|
||||
|
|
|
@ -32,20 +32,20 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_2, DEVHW_BMI270, BMI270_SPI_BUS
|
|||
|
||||
|
||||
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(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4
|
||||
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S5
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S6
|
||||
DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S7
|
||||
DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S8
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 4), // S5
|
||||
DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 5), // S6
|
||||
DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7
|
||||
DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8
|
||||
|
||||
DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S9
|
||||
DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S10 DMA_NONE
|
||||
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(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9
|
||||
DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE
|
||||
DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11
|
||||
DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 DMA_NONE
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_BEEPER, 0, 0), // BEEPER PWM
|
||||
|
|
|
@ -33,10 +33,10 @@
|
|||
timerHardware_t timerHardware[] = {
|
||||
// DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), // PPM - timer clash with SS1_TX
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1, 1), // M1 - D(2, 4, 7)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 1, 0), // M2 - D(1, 7, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 1, 0), // M3 - D(1, 2, 5)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 1, 0), // M4 - D(1, 3, 2)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 1, 1), // M1 - D(2, 4, 7)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // M2 - D(1, 7, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), // M3 - D(1, 2, 5)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 1, 0), // M4 - D(1, 3, 2)
|
||||
|
||||
// DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0), // LED strip - timer clash with M4 output
|
||||
|
||||
|
|
|
@ -33,10 +33,10 @@
|
|||
timerHardware_t timerHardware[] = {
|
||||
// DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), // PPM - timer clash with SS1_TX
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1, 0), // M1 - D(2, 4, 7)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 1, 0), // M2 - D(1, 7, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 1, 0), // M3 - D(1, 2, 5)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 1, 0), // M4 - D(1, 6, 3)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 1, 0), // M1 - D(2, 4, 7)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // M2 - D(1, 7, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), // M3 - D(1, 2, 5)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 1, 0), // M4 - D(1, 6, 3)
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_LED, 0, 0), // TX2; SA port ---> LED - D(1, 0, 6)
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0, 0), // SS1
|
||||
};
|
||||
|
|
|
@ -34,14 +34,14 @@
|
|||
#include "drivers/sensor.h"
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0), // S7
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S8
|
||||
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED_STRIP
|
||||
};
|
||||
|
|
|
@ -23,14 +23,14 @@
|
|||
#include "drivers/timer.h"
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S2
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S7
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 1), // S7
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
|
|
@ -26,14 +26,14 @@
|
|||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN
|
||||
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 - DMAR: DMA2_ST5
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M2 -
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // M3 - DMAR: DMA1_ST7
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // M4 -
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // M5 - DMAR: DMA2_ST1
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // M6 -
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // M7 - DMAR: DMA1_ST2
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // M8 - DMAR: DMA1_ST6
|
||||
DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1 - DMAR: DMA2_ST5
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2 -
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // M3 - DMAR: DMA1_ST7
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // M4 -
|
||||
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // M5 - DMAR: DMA2_ST1
|
||||
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // M6 -
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // M7 - DMAR: DMA1_ST2
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // M8 - DMAR: DMA1_ST6
|
||||
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0), // LED_STRIP / TRANSPONDER - DMA1_ST7
|
||||
};
|
||||
|
|
|
@ -27,10 +27,10 @@ timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
// Motors
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D1_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D1_ST2
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT D1_ST6
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT D1_ST6
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1
|
||||
|
||||
// LED strip
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // D1_ST0
|
||||
|
|
|
@ -30,13 +30,13 @@
|
|||
#include "drivers/sensor.h"
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TMR3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // TMR3_CH3 motor 1
|
||||
DEF_TIM(TMR3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // TMR3_CH4 motor 2
|
||||
DEF_TIM(TMR2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 7), // TMR2_CH4 motor 3
|
||||
DEF_TIM(TMR2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 6), // TMR2_CH3 motor 4
|
||||
DEF_TIM(TMR3, CH3, PB0, TIM_USE_MOTOR, 0, 1), // TMR3_CH3 motor 1
|
||||
DEF_TIM(TMR3, CH4, PB1, TIM_USE_MOTOR, 0, 2), // TMR3_CH4 motor 2
|
||||
DEF_TIM(TMR2, CH4, PA3, TIM_USE_MOTOR, 0, 7), // TMR2_CH4 motor 3
|
||||
DEF_TIM(TMR2, CH3, PA2, TIM_USE_MOTOR, 0, 6), // TMR2_CH3 motor 4
|
||||
|
||||
DEF_TIM(TMR8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO |TIM_USE_FW_MOTOR | TIM_USE_FW_SERVO | TIM_USE_ANY, 0, 4), // TMR8_CH3 motor 5
|
||||
DEF_TIM(TMR1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO |TIM_USE_FW_MOTOR | TIM_USE_FW_SERVO | TIM_USE_ANY, 0, 5), // TMR1_CH3 motor 6
|
||||
DEF_TIM(TMR8, CH3, PC8, TIM_USE_OUTPUT_AUTO | TIM_USE_ANY, 0, 4), // TMR8_CH3 motor 5
|
||||
DEF_TIM(TMR1, CH1, PA8, TIM_USE_OUTPUT_AUTO | TIM_USE_ANY, 0, 5), // TMR1_CH3 motor 6
|
||||
|
||||
DEF_TIM(TMR4, CH1, PB6, TIM_USE_LED, 0, 0), // TMR4_CH1 LED_STRIP
|
||||
};
|
||||
|
|
|
@ -27,14 +27,14 @@
|
|||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S1 D(1, 4, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S2 D(2, 3, 7)
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR, 0, 0), // S3 D(2, 4, 7)
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR, 0, 0), // S4 D(2, 7, 7)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S1 D(1, 4, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S2 D(2, 3, 7)
|
||||
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 0, 0), // S3 D(2, 4, 7)
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, 0, 0), // S4 D(2, 7, 7)
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), // S5 DMA1_ST2
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 DMA1_ST2
|
||||
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), // S6 DMA2_ST6
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DMA2_ST6
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), //camera
|
||||
|
||||
|
|
|
@ -24,12 +24,12 @@
|
|||
#include "drivers/pinio.h"
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,4,5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1,5,5)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 D(2,1,6)
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 D(2,2,6)
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S5 D(2,6,6)
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,7,2)
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1,4,5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1,5,5)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 D(2,1,6)
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 D(2,2,6)
|
||||
DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 D(2,6,6)
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1,7,2)
|
||||
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 pad - softserial_tx2
|
||||
|
||||
|
|
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