1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 16:55:29 +03:00

Merge branch 'master' of https://github.com/RomanLut/inav into submit-gps-fix-estimation

This commit is contained in:
Roman Lut 2023-10-01 00:05:07 +02:00
commit e4453c36d8
233 changed files with 3760 additions and 1918 deletions

3
.gitignore vendored
View file

@ -15,6 +15,7 @@ startup_stm32f10x_md_gcc.s
#.vscode/
cov-int*
/build/
/build_SITL/
/obj/
/patches/
/tools/
@ -32,3 +33,5 @@ README.pdf
# local changes only
make/local.mk
launch.json
.vscode/tasks.json
.vscode/c_cpp_properties.json

View file

@ -114,6 +114,7 @@ While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0
| `status` | Show status. Error codes can be looked up [here](https://github.com/iNavFlight/inav/wiki/%22Something%22-is-disabled----Reasons) |
| `tasks` | Show task stats |
| `temp_sensor` | List or configure temperature sensor(s). See [temperature sensors documentation](Temperature-sensors.md) for more information. |
| `timer_output_mode` | Override automatic timer / pwm function allocation. [Additional Information](#timer_outout_mode)|
| `version` | Show version |
| `wp` | List or configure waypoints. See the [navigation documentation](Navigation.md#cli-command-wp-to-manage-waypoints). |
@ -170,6 +171,66 @@ serial 0 -4
`serial` can also be used without any argument to print the current configuration of all the serial ports.
### `timer_output_mode`
Since INAV 7, the firmware can dynamically allocate servo and motor outputs. This removes the need for bespoke targets for special cases (e.g. `MATEKF405` and `MATEKF405_SERVOS6`).
#### Syntax
```
timer_output_mode [timer [function]]
```
where:
* Without parameters, lists the current timers and modes
* With just a `timer` lists the mode for that timer
* With both `timer` and `function`, sets the function for that timers
Note:
* `timer` identifies the timer **index** (from 0); thus is one less than the corresponding `TIMn` definition in a target's `target.c`.
* The function is one of `AUTO` (the default), `MOTORS` or `SERVOS`.
Motors are allocated first, hence having a servo before a motor may require use of `timer_output_mode`.
#### Example
The original `MATEKF405` target defined a multi-rotor (MR) servo on output S1. The later `MATEKF405_SERVOS6` target defined (for MR) S1 as a motor and S6 as a servo. This was more logical, but annoying for anyone who had a legacy `MATEKF405` tricopter with the servo on S1.
#### Solution
There is now a single `MATEKF405` target. The `target.c` sets the relevant outputs as:
```
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 UP(2,1)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 UP(2,1)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 UP(2,1)
DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_LED, 0, 0), // S5 UP(1,7)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 UP(2,5)
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1,7)!S5 UP(2,6)
```
Using the "motors first" allocation, the servo would end up on S6, which in the legacy "tricopter servo on S1" case is not desired.
Forcing the S1 output (`TIM3`) to servo is achieved by:
```
timer_output_mode 2 SERVOS
```
with resulting `resource` output:
```
C06: SERVO4 OUT
C07: MOTOR1 OUT
C08: MOTOR2 OUT
C09: MOTOR3 OUT
```
Note that the `timer` **index** in the `timer_output_mode` line is one less than the mnemonic in `target.c`, `timer` of 2 for `TIM3`.
Note that the usual caveat that one should not share a timer with both a motor and a servo still apply.
## Flash chip management
For targets that have a flash data chip, typically used for blackbox logs, the following additional comamnds are provided.

View file

@ -28,8 +28,23 @@ While motors are usually ordered sequentially, here is no standard output layout
## Modifying output mapping
INAV 5 allows the limited output type mapping by allowing to change the function of *ALL* outputs at the same time. It can be done with the `output_mode` CLI setting. Allowed values:
### Modifying all outputs at the same time
Since INAV 5, it has been possible to force *ALL* outputs to be `MOTORS` or `SERVOS`.
Traditional ESCs usually can be controlled via a servo output, but would require calibration.
This can be done with the `output_mode` CLI setting. Allowed values:
* `AUTO` assigns outputs according to the default mapping
* `SERVOS` assigns all outputs to servos
* `MOTORS` assigns all outputs to motors
* `MOTORS` assigns all outputs to motors
### Modifying only some outputs
INAV 7 introduced extra functionality that let you force only some outputs to be either *MOTORS* or *SERVOS*, with some restrictions dictated by the hardware.
The mains restrictions is that outputs need to be associated with timers, which are usually shared between multiple outputs. Two outputs on the same timer need to have the same function.
The easiest way to modify outputs, is to use the Mixer tab in the Configurator, as it will clearly show you which timer is used by all outputs, but you can also use `timer_output_mode` on the cli.
This can be used in conjunction to the previous method, in that cass all outputs will follow `output_mode` and `timer_output_mode` overrides are applied after that.

144
docs/MixerProfile.md Normal file
View 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:
![Alt text](Screenshots/mixer_profile.png)
| 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.

View file

@ -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
@ -158,7 +169,7 @@ The flight mode operands return `true` when the mode is active. These are modes
| 7 | HORIZON | `true` when you are in the **Horizon** flight mode. |
| 8 | AIR | `true` when you the **Airmode** flight mode modifier is active. |
| 9 | USER1 | `true` when the **USER 1** mode is active. |
| 10 | USER2 | `true` when the **USER 21** mode is active. |
| 10 | USER2 | `true` when the **USER 2** mode is active. |
| 11 | COURSE_HOLD | `true` when you are in the **Course Hold** flight mode. |
| 12 | USER3 | `true` when the **USER 3** mode is active. |
| 13 | USER4 | `true` when the **USER 4** mode is active. |
@ -310,3 +321,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.
![screenshot of override an RC channel with a value](./assets/images/ipf_set_get_rc_channel.png)

View file

@ -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
```

Binary file not shown.

After

Width:  |  Height:  |  Size: 24 KiB

View file

@ -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 |

View file

@ -1884,7 +1884,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 |
| --- | --- | --- |
@ -2572,6 +2572,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.
@ -2632,6 +2662,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.
@ -2682,6 +2722,16 @@ Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no speci
---
### nav_cruise_yaw_rate
Max YAW rate when NAV COURSE HOLD/CRUISE mode is enabled. Set to 0 to disable on fixed wing (Note: On multirotor setting to 0 will disable Course Hold/Cruise mode completely) [dps]
| Default | Min | Max |
| --- | --- | --- |
| 20 | 0 | 120 |
---
### nav_disarm_on_landing
If set to ON, INAV disarms the FC after landing
@ -2772,16 +2822,6 @@ Cruise throttle in GPS assisted modes, this includes RTH. Should be set high eno
---
### nav_fw_cruise_yaw_rate
Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]
| Default | Min | Max |
| --- | --- | --- |
| 20 | 0 | 60 |
---
### nav_fw_dive_angle
Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit
@ -4752,16 +4792,6 @@ Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF'
---
### output_mode
Output function assignment mode. AUTO assigns outputs according to the default mapping, SERVOS assigns all outputs to servos, MOTORS assigns all outputs to motors
| Default | Min | Max |
| --- | --- | --- |
| AUTO | | |
---
### pid_type
Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID`
@ -4858,7 +4888,7 @@ Selection of pitot hardware.
| Default | Min | Max |
| --- | --- | --- |
| NONE | | |
| VIRTUAL | | |
---

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

View file

@ -26,7 +26,7 @@ Install Git, Make, gcc and Ruby
- `sudo apt-get install git make cmake ruby`
Install python and python-yaml to allow updates to settings.md
- `sudo apt-get install python3 python-yaml`
- `sudo apt-get install python3`
### CMAKE and Ubuntu 18_04

View file

@ -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

View file

@ -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;

View file

@ -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
@ -119,7 +119,8 @@
#define PG_UNUSED_1 1029
#define PG_POWER_LIMITS_CONFIG 1030
#define PG_OSD_COMMON_CONFIG 1031
#define PG_INAV_END 1031
#define PG_TIMER_OVERRIDE_CONFIG 1032
#define PG_INAV_END 1032
// OSD configuration (subject to change)
//#define PG_OSD_FONT_CONFIG 2047

View file

@ -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);

View file

@ -211,46 +211,111 @@ static bool checkPwmTimerConflicts(const timerHardware_t *timHw)
}
static void timerHardwareOverride(timerHardware_t * timer) {
if (mixerConfig()->outputMode == OUTPUT_MODE_SERVOS) {
//Motors are rewritten as servos
if (timer->usageFlags & TIM_USE_MC_MOTOR) {
timer->usageFlags = timer->usageFlags & ~TIM_USE_MC_MOTOR;
timer->usageFlags = timer->usageFlags | TIM_USE_MC_SERVO;
switch (timerOverrides(timer2id(timer->tim))->outputMode) {
case OUTPUT_MODE_MOTORS:
if (TIM_IS_SERVO(timer->usageFlags)) {
timer->usageFlags &= ~TIM_USE_SERVO;
timer->usageFlags |= TIM_USE_MOTOR;
}
break;
case OUTPUT_MODE_SERVOS:
if (TIM_IS_MOTOR(timer->usageFlags)) {
timer->usageFlags &= ~TIM_USE_MOTOR;
timer->usageFlags |= TIM_USE_SERVO;
}
break;
}
}
bool pwmHasMotorOnTimer(timMotorServoHardware_t * timOutputs, HAL_Timer_t *tim)
{
for (int i = 0; i < timOutputs->maxTimMotorCount; ++i) {
if (timOutputs->timMotors[i]->tim == tim) {
return true;
}
if (timer->usageFlags & TIM_USE_FW_MOTOR) {
timer->usageFlags = timer->usageFlags & ~TIM_USE_FW_MOTOR;
timer->usageFlags = timer->usageFlags | TIM_USE_FW_SERVO;
}
return false;
}
bool pwmHasServoOnTimer(timMotorServoHardware_t * timOutputs, HAL_Timer_t *tim)
{
for (int i = 0; i < timOutputs->maxTimServoCount; ++i) {
if (timOutputs->timServos[i]->tim == tim) {
return true;
}
} else if (mixerConfig()->outputMode == OUTPUT_MODE_MOTORS) {
// Servos are rewritten as motors
if (timer->usageFlags & TIM_USE_MC_SERVO) {
timer->usageFlags = timer->usageFlags & ~TIM_USE_MC_SERVO;
timer->usageFlags = timer->usageFlags | TIM_USE_MC_MOTOR;
}
return false;
}
uint8_t pwmClaimTimer(HAL_Timer_t *tim, uint32_t usageFlags) {
uint8_t changed = 0;
for (int idx = 0; idx < timerHardwareCount; idx++) {
timerHardware_t *timHw = &timerHardware[idx];
if (timHw->tim == tim && timHw->usageFlags != usageFlags) {
timHw->usageFlags = usageFlags;
changed++;
}
if (timer->usageFlags & TIM_USE_FW_SERVO) {
timer->usageFlags = timer->usageFlags & ~TIM_USE_FW_SERVO;
timer->usageFlags = timer->usageFlags | TIM_USE_FW_MOTOR;
}
return changed;
}
void pwmEnsureEnoughtMotors(uint8_t motorCount)
{
uint8_t motorOnlyOutputs = 0;
for (int idx = 0; idx < timerHardwareCount; idx++) {
timerHardware_t *timHw = &timerHardware[idx];
timerHardwareOverride(timHw);
if (checkPwmTimerConflicts(timHw)) {
continue;
}
if (TIM_IS_MOTOR_ONLY(timHw->usageFlags)) {
motorOnlyOutputs++;
motorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags);
}
}
for (int idx = 0; idx < timerHardwareCount; idx++) {
timerHardware_t *timHw = &timerHardware[idx];
if (checkPwmTimerConflicts(timHw)) {
continue;
}
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 {
timHw->usageFlags &= ~TIM_USE_MOTOR;
pwmClaimTimer(timHw->tim, timHw->usageFlags);
}
}
}
}
void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos)
{
UNUSED(isMixerUsingServos);
timOutputs->maxTimMotorCount = 0;
timOutputs->maxTimServoCount = 0;
uint8_t motorCount = getMotorCount();
uint8_t motorIdx = 0;
pwmEnsureEnoughtMotors(motorCount);
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)
@ -259,39 +324,29 @@ 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 motor outputs get assigned to motor
if (TIM_IS_MOTOR(timHw->usageFlags) && (motorIdx < motorCount)) {
timHw->usageFlags &= ~TIM_USE_SERVO;
pwmClaimTimer(timHw->tim, timHw->usageFlags);
motorIdx += 1;
}
// 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;
motorIdx += 1;
}
// We enable mapping to servos if mixer is actually using them
if (isMixerUsingServos && timHw->usageFlags & TIM_USE_MC_SERVO) {
type = MAP_TO_SERVO_OUTPUT;
}
else if (timHw->usageFlags & TIM_USE_MC_MOTOR) {
type = MAP_TO_MOTOR_OUTPUT;
}
} else {
// Fixed wing or HELI (one/two motors and a lot of servos
if (timHw->usageFlags & TIM_USE_FW_SERVO) {
type = MAP_TO_SERVO_OUTPUT;
}
else if (timHw->usageFlags & TIM_USE_FW_MOTOR) {
type = MAP_TO_MOTOR_OUTPUT;
}
if (TIM_IS_SERVO(timHw->usageFlags) && !pwmHasMotorOnTimer(timOutputs, timHw->tim)) {
type = MAP_TO_SERVO_OUTPUT;
} 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_MOTOR;
timOutputs->timMotors[timOutputs->maxTimMotorCount++] = timHw;
pwmClaimTimer(timHw->tim, timHw->usageFlags);
break;
case MAP_TO_SERVO_OUTPUT:
timHw->usageFlags &= TIM_USE_SERVO;
timOutputs->timServos[timOutputs->maxTimServoCount++] = timHw;
pwmClaimTimer(timHw->tim, timHw->usageFlags);
break;
default:
break;

View file

@ -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)

View file

@ -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();
@ -430,18 +431,30 @@ static void executeDShotCommands(void){
dshotCommands_e cmd;
circularBufferPopHead(&commandsCircularBuffer, (uint8_t *) &cmd);
currentExecutingCommand.cmd = cmd;
currentExecutingCommand.remainingRepeats = getDShotCommandRepeats(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;
}
currentExecutingCommand.remainingRepeats--;
lastCommandSent = tNow;
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++) {

View file

@ -38,8 +38,18 @@
timHardwareContext_t * timerCtx[HARDWARE_TIMER_DEFINITION_COUNT];
uint8_t timer2id(const HAL_Timer_t *tim)
{
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; ++i) {
if (timerDefinitions[i].tim == tim) return i;
}
return (uint8_t)-1;
}
#if defined(AT32F43x)
uint8_t lookupTimerIndex(const tmr_type *tim)
uint8_t lookupTimerIndex(const HAL_Timer_t *tim)
{
int i;
@ -54,7 +64,7 @@ uint8_t lookupTimerIndex(const tmr_type *tim)
}
#else
// return index of timer in timer table. Lowest timer has index 0
uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
uint8_t lookupTimerIndex(const HAL_Timer_t *tim)
{
int i;

View file

@ -25,6 +25,8 @@
#include "drivers/rcc_types.h"
#include "drivers/timer_def.h"
#include "platform.h"
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)
@ -63,8 +65,9 @@ typedef uint32_t timCNT_t;
#endif
// tmr_type instead in AT32
#if defined(AT32F43x)
typedef tmr_type HAL_Timer_t;
typedef struct timerDef_s {
tmr_type * tim;
HAL_Timer_t * tim;
rccPeriphTag_t rcc;
uint8_t irq;
uint8_t secondIrq;
@ -82,8 +85,9 @@ typedef struct timerHardware_s {
uint32_t dmaMuxid; //DMAMUX ID
} timerHardware_t;
#else
typedef TIM_TypeDef HAL_Timer_t;
typedef struct timerDef_s {
TIM_TypeDef * tim;
HAL_Timer_t * tim;
rccPeriphTag_t rcc;
uint8_t irq;
uint8_t secondIrq;
@ -106,15 +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_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,
@ -248,7 +259,9 @@ bool timerPWMDMAInProgress(TCH_t * tch);
volatile timCCR_t *timerCCR(TCH_t * tch);
uint8_t timer2id(const HAL_Timer_t *tim);
#ifdef USE_DSHOT_DMAR
bool timerPWMConfigDMABurst(burstDmaTimer_t *burstDmaTimer, TCH_t * tch, void * dmaBuffer, uint8_t dmaBufferElementSize, uint32_t dmaBufferElementCount);
void pwmBurstDMAStart(burstDmaTimer_t * burstDmaTimer, uint32_t BurstLength);
#endif
#endif

View file

@ -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"
@ -156,6 +156,13 @@ static const char * const featureNames[] = {
"OSD", "FW_LAUNCH", "FW_AUTOTRIM", NULL
};
static const char * outputModeNames[] = {
"AUTO",
"MOTORS",
"SERVOS",
NULL
};
#ifdef USE_BLACKBOX
static const char * const blackboxIncludeFlagNames[] = {
"NAV_ACC",
@ -282,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),
@ -1038,7 +1045,7 @@ static void cliAdjustmentRange(char *cmdline)
}
static void printMotorMix(uint8_t dumpMask, const motorMixer_t *primaryMotorMixer, const motorMixer_t *defaultprimaryMotorMixer)
{
{
const char *format = "mmix %d %s %s %s %s";
char buf0[FTOA_BUFFER_SIZE];
char buf1[FTOA_BUFFER_SIZE];
@ -1862,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);
@ -2514,6 +2521,82 @@ static void cliOsdLayout(char *cmdline)
#endif
static void printTimerOutputModes(dumpFlags_e dumpFlags, const timerOverride_t* to, const timerOverride_t* defaultTimerOverride, int timer)
{
const char *format = "timer_output_mode %d %s";
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; ++i) {
if (timer < 0 || timer == i) {
outputMode_e mode = to[i].outputMode;
bool equalsDefault = false;
if(defaultTimerOverride) {
outputMode_e defaultMode = defaultTimerOverride[i].outputMode;
equalsDefault = mode == defaultMode;
cliDefaultPrintLinef(dumpFlags, equalsDefault, format, i, outputModeNames[defaultMode]);
}
cliDumpPrintLinef(dumpFlags, equalsDefault, format, i, outputModeNames[mode]);
}
}
}
static void cliTimerOutputMode(char *cmdline)
{
char * saveptr;
int timer = -1;
uint8_t mode;
char *tok = strtok_r(cmdline, " ", &saveptr);
int ii;
for (ii = 0; tok != NULL; ii++, tok = strtok_r(NULL, " ", &saveptr)) {
switch (ii) {
case 0:
timer = fastA2I(tok);
if (timer < 0 || timer >= HARDWARE_TIMER_DEFINITION_COUNT) {
cliShowParseError();
return;
}
break;
case 1:
if(!sl_strcasecmp("AUTO", tok)) {
mode = OUTPUT_MODE_AUTO;
} else if(!sl_strcasecmp("MOTORS", tok)) {
mode = OUTPUT_MODE_MOTORS;
} else if(!sl_strcasecmp("SERVOS", tok)) {
mode = OUTPUT_MODE_SERVOS;
} else {
cliShowParseError();
return;
}
break;
default:
cliShowParseError();
return;
}
}
switch (ii) {
case 0:
FALLTHROUGH;
case 1:
// No args, or just timer. If any of them not provided,
// it will be the -1 that we used during initialization, so printOsdLayout()
// won't use them for filtering.
printTimerOutputModes(DUMP_MASTER, timerOverrides(0), NULL, timer);
break;
case 2:
timerOverridesMutable(timer)->outputMode = mode;
printTimerOutputModes(DUMP_MASTER, timerOverrides(0), NULL, timer);
break;
default:
// Unhandled
cliShowParseError();
return;
}
}
static void printFeature(uint8_t dumpMask, const featureConfig_t *featureConfig, const featureConfig_t *featureConfigDefault)
{
uint32_t mask = featureConfig->enabledFeatures;
@ -3049,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)
{
@ -3604,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 {
@ -3616,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
@ -3652,15 +3772,8 @@ static void printConfig(const char *cmdline, bool doDiff)
cliPrintHashLine("resources");
//printResource(dumpMask, &defaultConfig);
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));
cliPrintHashLine("Timer overrides");
printTimerOutputModes(dumpMask, timerOverrides_CopyArray, timerOverrides(0), -1);
// print servo parameters
cliPrintHashLine("Outputs [servo]");
@ -3743,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);
}
@ -3751,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);
@ -3761,11 +3880,15 @@ 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);
}
@ -3925,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)
@ -3968,6 +4093,7 @@ const clicmd_t cmdTable[] = {
#ifdef USE_OSD
CLI_COMMAND_DEF("osd_layout", "get or set the layout of OSD items", "[<layout> [<item> [<col> <row> [<visible>]]]]", cliOsdLayout),
#endif
CLI_COMMAND_DEF("timer_output_mode", "get or set the outputmode for a given timer.", "[<timer> [<AUTO|MOTORS|SERVOS>]]", cliTimerOutputMode),
};
static void cliHelp(char *cmdline)

View file

@ -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)
@ -330,6 +331,7 @@ void readEEPROM(void)
setConfigProfile(getConfigProfile());
setConfigBatteryProfile(getConfigBatteryProfile());
setConfigMixerProfile(getConfigMixerProfile());
validateAndFixConfig();
activateConfig();
@ -469,6 +471,37 @@ 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;
// setMixerProfile(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];

View file

@ -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);

View 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) {
@ -705,14 +706,14 @@ 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)) {
if (!FLIGHT_MODE(HEADFREE_MODE)) {
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
}
}
@ -745,8 +746,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 {
@ -764,7 +765,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);
}
@ -792,7 +793,7 @@ void processRx(timeUs_t currentTimeUs)
}
}
//---------------------------------------------------------
if (mixerConfig()->platformType == PLATFORM_AIRPLANE) {
if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) {
DISABLE_FLIGHT_MODE(HEADFREE_MODE);
}
@ -833,13 +834,25 @@ void FAST_CODE taskGyro(timeUs_t currentTimeUs) {
#endif
}
static float calculateThrottleTiltCompensationFactor(uint8_t throttleTiltCompensationStrength)
static void applyThrottleTiltCompensation(void)
{
if (throttleTiltCompensationStrength) {
float tiltCompFactor = 1.0f / constrainf(calculateCosTiltAngle(), 0.6f, 1.0f); // max tilt about 50 deg
return 1.0f + (tiltCompFactor - 1.0f) * (throttleTiltCompensationStrength / 100.f);
} else {
return 1.0f;
if (STATE(MULTIROTOR)) {
int16_t thrTiltCompStrength = 0;
if (navigationRequiresThrottleTiltCompensation()) {
thrTiltCompStrength = 100;
}
else if (systemConfig()->throttle_tilt_compensation_strength && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
thrTiltCompStrength = systemConfig()->throttle_tilt_compensation_strength;
}
if (thrTiltCompStrength) {
const int throttleIdleValue = getThrottleIdleValue();
float tiltCompFactor = 1.0f / constrainf(calculateCosTiltAngle(), 0.6f, 1.0f); // max tilt about 50 deg
tiltCompFactor = 1.0f + (tiltCompFactor - 1.0f) * (thrTiltCompStrength / 100.f);
rcCommand[THROTTLE] = setDesiredThrottle(throttleIdleValue + (rcCommand[THROTTLE] - throttleIdleValue) * tiltCompFactor, false);
}
}
}
@ -891,26 +904,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
applyWaypointNavigationAndAltitudeHold();
// Apply throttle tilt compensation
if (!STATE(FIXED_WING_LEGACY)) {
int16_t thrTiltCompStrength = 0;
if (navigationRequiresThrottleTiltCompensation()) {
thrTiltCompStrength = 100;
}
else if (systemConfig()->throttle_tilt_compensation_strength && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
thrTiltCompStrength = systemConfig()->throttle_tilt_compensation_strength;
}
if (thrTiltCompStrength) {
rcCommand[THROTTLE] = constrain(getThrottleIdleValue()
+ (rcCommand[THROTTLE] - getThrottleIdleValue()) * calculateThrottleTiltCompensationFactor(thrTiltCompStrength),
getThrottleIdleValue(),
motorConfig()->maxthrottle);
}
}
else {
// FIXME: throttle pitch comp for FW
}
applyThrottleTiltCompensation();
#ifdef USE_POWER_LIMITS
powerLimiterApply(&rcCommand[THROTTLE]);

View file

@ -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) {

View file

@ -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);
@ -1516,6 +1518,18 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
}
break;
case MSP2_INAV_OUTPUT_MAPPING_EXT:
for (uint8_t i = 0; i < timerHardwareCount; ++i)
if (!(timerHardware[i].usageFlags & (TIM_USE_PPM | TIM_USE_PWM))) {
#if defined(SITL_BUILD)
sbufWriteU8(dst, i);
#else
sbufWriteU8(dst, timer2id(timerHardware[i].tim));
#endif
sbufWriteU8(dst, timerHardware[i].usageFlags);
}
break;
case MSP2_INAV_MC_BRAKING:
#ifdef USE_MR_BRAKING_MODE
sbufWriteU16(dst, navConfig()->mc.braking_speed_threshold);
@ -2854,7 +2868,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);
@ -3218,6 +3233,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)
@ -3659,7 +3678,43 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
*ret = MSP_RESULT_ACK;
break;
#endif
#ifndef SITL_BUILD
case MSP2_INAV_TIMER_OUTPUT_MODE:
if (dataSize == 0) {
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; ++i) {
sbufWriteU8(dst, i);
sbufWriteU8(dst, timerOverrides(i)->outputMode);
}
*ret = MSP_RESULT_ACK;
} else if(dataSize == 1) {
uint8_t timer = sbufReadU8(src);
if(timer < HARDWARE_TIMER_DEFINITION_COUNT) {
sbufWriteU8(dst, timer);
sbufWriteU8(dst, timerOverrides(timer)->outputMode);
*ret = MSP_RESULT_ACK;
} else {
*ret = MSP_RESULT_ERROR;
}
} else {
*ret = MSP_RESULT_ERROR;
}
break;
case MSP2_INAV_SET_TIMER_OUTPUT_MODE:
if(dataSize == 2) {
uint8_t timer = sbufReadU8(src);
uint8_t outputMode = sbufReadU8(src);
if(timer < HARDWARE_TIMER_DEFINITION_COUNT) {
timerOverridesMutable(timer)->outputMode = outputMode;
*ret = MSP_RESULT_ACK;
} else {
*ret = MSP_RESULT_ERROR;
}
} else {
*ret = MSP_RESULT_ERROR;
}
break;
#endif
default:
// Not handled
return false;

View file

@ -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,6 +100,8 @@ 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 = BOXMIXERPROFILE, .boxName = "MIXER PROFILE 2", .permanentId = 62 },
{ .boxId = BOXMIXERTRANSITION, .boxName = "MIXER TRANSITION", .permanentId = 63 },
{ .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF }
};
@ -231,6 +234,8 @@ void initActiveBoxIds(void)
if (!STATE(ALTITUDE_CONTROL) || (STATE(ALTITUDE_CONTROL) && navReadyAltControl)) {
ADD_ACTIVE_BOX(BOXNAVRTH);
ADD_ACTIVE_BOX(BOXNAVWP);
ADD_ACTIVE_BOX(BOXNAVCRUISE);
ADD_ACTIVE_BOX(BOXNAVCOURSEHOLD);
ADD_ACTIVE_BOX(BOXHOMERESET);
ADD_ACTIVE_BOX(BOXGCSNAV);
ADD_ACTIVE_BOX(BOXPLANWPMISSION);
@ -240,8 +245,6 @@ void initActiveBoxIds(void)
}
if (STATE(AIRPLANE)) {
ADD_ACTIVE_BOX(BOXNAVCRUISE);
ADD_ACTIVE_BOX(BOXNAVCOURSEHOLD);
ADD_ACTIVE_BOX(BOXSOARING);
}
}
@ -350,6 +353,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)
@ -418,6 +426,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
memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t));
for (uint32_t i = 0; i < activeBoxIdCount; i++) {

View file

@ -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();

View file

@ -79,6 +79,8 @@ typedef enum {
BOXCHANGEMISSION = 50,
BOXBEEPERMUTE = 51,
BOXMULTIFUNCTION = 52,
BOXMIXERPROFILE = 53,
BOXMIXERTRANSITION = 54,
CHECKBOX_ITEM_COUNT
} boxId_e;

View file

@ -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;
}

View file

@ -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 {

View file

@ -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"]
@ -112,9 +112,6 @@ tables:
enum: smartportFuelUnit_e
- name: platform_type
values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT"]
- name: output_mode
values: ["AUTO", "MOTORS", "SERVOS"]
enum: outputMode_e
- name: tz_automatic_dst
values: ["OFF", "EU", "USA"]
enum: tz_automatic_dst_e
@ -588,7 +585,7 @@ groups:
members:
- name: pitot_hardware
description: "Selection of pitot hardware."
default_value: "NONE"
default_value: "VIRTUAL"
table: pitot_hardware
- name: pitot_lpf_milli_hz
min: 0
@ -1143,36 +1140,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: output_mode
description: "Output function assignment mode. AUTO assigns outputs according to the default mapping, SERVOS assigns all outputs to servos, MOTORS assigns all outputs to motors"
default_value: "AUTO"
field: outputMode
table: output_mode
- 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
@ -2262,7 +2279,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
@ -2596,6 +2613,12 @@ groups:
default_value: ON
field: general.flags.mission_planner_reset
type: bool
- name: nav_cruise_yaw_rate
description: "Max YAW rate when NAV COURSE HOLD/CRUISE mode is enabled. Set to 0 to disable on fixed wing (Note: On multirotor setting to 0 will disable Course Hold/Cruise mode completely) [dps]"
default_value: 20
field: general.cruise_yaw_rate
min: 0
max: 120
- name: nav_mc_bank_angle
description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude"
default_value: 30
@ -2831,12 +2854,6 @@ groups:
field: fw.launch_abort_deadband
min: 2
max: 250
- name: nav_fw_cruise_yaw_rate
description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]"
default_value: 20
field: fw.cruise_yaw_rate
min: 0
max: 60
- name: nav_fw_allow_manual_thr_increase
description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing"
default_value: OFF

View file

@ -149,6 +149,10 @@ static const failsafeProcedureLogic_t failsafeProcedureLogic[] = {
*/
void failsafeReset(void)
{
if (failsafeState.active) { // can't reset if still active
return;
}
failsafeState.rxDataFailurePeriod = PERIOD_RXDATA_FAILURE + failsafeConfig()->failsafe_delay * MILLIS_PER_TENTH_SECOND;
failsafeState.rxDataRecoveryPeriod = PERIOD_RXDATA_RECOVERY + failsafeConfig()->failsafe_recovery_delay * MILLIS_PER_TENTH_SECOND;
failsafeState.validRxDataReceivedAt = 0;
@ -160,6 +164,7 @@ void failsafeReset(void)
failsafeState.phase = FAILSAFE_IDLE;
failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN;
failsafeState.activeProcedure = failsafeConfig()->failsafe_procedure;
failsafeState.controlling = false;
failsafeState.lastGoodRcCommand[ROLL] = 0;
failsafeState.lastGoodRcCommand[PITCH] = 0;
@ -214,14 +219,6 @@ bool failsafeRequiresAngleMode(void)
failsafeProcedureLogic[failsafeState.activeProcedure].forceAngleMode;
}
bool failsafeRequiresMotorStop(void)
{
return failsafeState.active &&
failsafeState.activeProcedure == FAILSAFE_PROCEDURE_AUTO_LANDING &&
posControl.flags.estAltStatus < EST_USABLE &&
currentBatteryProfile->failsafe_throttle < getThrottleIdleValue();
}
void failsafeStartMonitoring(void)
{
failsafeState.monitoring = true;

View file

@ -176,7 +176,6 @@ void failsafeOnRxResume(void);
bool failsafeMayRequireNavigationMode(void);
void failsafeApplyControlInput(void);
bool failsafeRequiresAngleMode(void);
bool failsafeRequiresMotorStop(void);
bool failsafeShouldApplyControlInput(void);
bool failsafeBypassNavigation(void);
void failsafeUpdateRcCommandValues(void);

View file

@ -28,9 +28,11 @@
#include "common/maths.h"
#include "common/utils.h"
#include "config/config_reset.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"
@ -81,17 +83,7 @@ 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
.outputMode = SETTING_OUTPUT_MODE_DEFAULT,
);
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 9);
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 10);
PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
.motorPwmProtocol = SETTING_MOTOR_PWM_PROTOCOL_DEFAULT,
@ -100,11 +92,17 @@ 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
void pgResetFn_timerOverrides(timerOverride_t *instance)
{
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; ++i) {
RESET_CONFIG(timerOverride_t, &instance[i], .outputMode = OUTPUT_MODE_AUTO);
}
}
int getThrottleIdleValue(void)
{
if (!throttleIdleValue) {
@ -116,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) {
@ -149,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)
@ -199,7 +221,7 @@ void mixerInit(void)
mixerResetDisarmedMotors();
if (mixerConfig()->motorDirectionInverted) {
if (currentMixerConfig.motorDirectionInverted) {
motorYawMultiplier = -1;
} else {
motorYawMultiplier = 1;
@ -208,6 +230,7 @@ void mixerInit(void)
void mixerResetDisarmedMotors(void)
{
getThrottleIdleValue();
if (feature(FEATURE_REVERSIBLE_MOTORS)) {
motorZeroCommand = reversibleMotorsConfig()->neutral;
@ -215,16 +238,16 @@ void mixerResetDisarmedMotors(void)
throttleRangeMax = motorConfig()->maxthrottle;
} else {
motorZeroCommand = motorConfig()->mincommand;
throttleRangeMin = getThrottleIdleValue();
throttleRangeMin = throttleIdleValue;
throttleRangeMax = motorConfig()->maxthrottle;
}
reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD;
if (feature(FEATURE_MOTOR_STOP)) {
if (ifMotorstopFeatureEnabled()) {
motorValueWhenStopped = motorZeroCommand;
} else {
motorValueWhenStopped = getThrottleIdleValue();
motorValueWhenStopped = throttleIdleValue;
}
// set disarmed motor values
@ -279,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);
@ -458,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)
@ -469,6 +492,19 @@ void FAST_CODE mixTable(void)
return;
}
#endif
#ifdef USE_DEV_TOOLS
bool isDisarmed = !ARMING_FLAG(ARMED) || systemConfig()->groundTestMode;
#else
bool isDisarmed = !ARMING_FLAG(ARMED);
#endif
bool motorStopIsActive = getMotorStatus() != MOTOR_RUNNING && !isDisarmed;
if (isDisarmed || motorStopIsActive) {
for (int i = 0; i < motorCount; i++) {
motor[i] = isDisarmed ? motor_disarmed[i] : motorValueWhenStopped;
}
mixerThrottleCommand = motor[0];
return;
}
int16_t input[3]; // RPY, range [-500:+500]
// Allow direct stick input to motors in passthrough mode on airplanes
@ -551,11 +587,11 @@ void FAST_CODE mixTable(void)
throttleRangeMax = motorConfig()->maxthrottle;
// Throttle scaling to limit max throttle when battery is full
#ifdef USE_PROGRAMMING_FRAMEWORK
#ifdef USE_PROGRAMMING_FRAMEWORK
mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * getThrottleScale(currentBatteryProfile->motor.throttleScale)) + throttleRangeMin;
#else
#else
mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * currentBatteryProfile->motor.throttleScale) + throttleRangeMin;
#endif
#endif
// Throttle compensation based on battery voltage
if (feature(FEATURE_THR_VBAT_COMP) && isAmperageConfigured() && feature(FEATURE_VBAT)) {
mixerThrottleCommand = MIN(throttleRangeMin + (mixerThrottleCommand - throttleRangeMin) * calculateThrottleCompensationFactor(), throttleRangeMax);
@ -564,7 +600,6 @@ void FAST_CODE mixTable(void)
throttleMin = throttleRangeMin;
throttleMax = throttleRangeMax;
throttleRange = throttleMax - throttleMin;
#define THROTTLE_CLIPPING_FACTOR 0.33f
@ -584,54 +619,53 @@ void FAST_CODE mixTable(void)
// Now add in the desired throttle, but keep in a range that doesn't clip adjusted
// roll/pitch/yaw. This could move throttle down, but also up for those low throttle flips.
if (ARMING_FLAG(ARMED)) {
const motorStatus_e currentMotorStatus = getMotorStatus();
for (int i = 0; i < motorCount; i++) {
motor[i] = rpyMix[i] + constrain(mixerThrottleCommand * currentMixer[i].throttle, throttleMin, throttleMax);
for (int i = 0; i < motorCount; i++) {
motor[i] = rpyMix[i] + constrain(mixerThrottleCommand * currentMixer[i].throttle, throttleMin, throttleMax);
if (failsafeIsActive()) {
motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle);
} else {
motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax);
}
// Motor stop handling
if (currentMotorStatus != MOTOR_RUNNING) {
motor[i] = motorValueWhenStopped;
}
#ifdef USE_DEV_TOOLS
if (systemConfig()->groundTestMode) {
motor[i] = motorZeroCommand;
}
#endif
if (failsafeIsActive()) {
motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle);
} else {
motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax);
}
} else {
for (int i = 0; i < motorCount; i++) {
motor[i] = motor_disarmed[i];
//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);
}
}
}
int16_t getThrottlePercent(bool useScaled)
{
int16_t thr = constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX);
const int idleThrottle = getThrottleIdleValue();
int16_t thr = constrain(mixerThrottleCommand, PWM_RANGE_MIN, PWM_RANGE_MAX);
if (useScaled) {
thr = (thr - idleThrottle) * 100 / (motorConfig()->maxthrottle - idleThrottle);
thr = (thr - throttleIdleValue) * 100 / (motorConfig()->maxthrottle - throttleIdleValue);
} else {
thr = (rxGetChannelValue(THROTTLE) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
}
return thr;
}
uint16_t setDesiredThrottle(uint16_t throttle, bool allowMotorStop)
{
const uint16_t throttleIdleValue = getThrottleIdleValue();
if (allowMotorStop && throttle < throttleIdleValue) {
ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE);
return throttle;
}
return constrain(throttle, throttleIdleValue, motorConfig()->maxthrottle);
}
motorStatus_e getMotorStatus(void)
{
if (failsafeRequiresMotorStop()) {
return MOTOR_STOPPED_AUTO;
}
if (!failsafeIsActive() && STATE(NAV_MOTOR_STOP_OR_IDLE)) {
if (STATE(NAV_MOTOR_STOP_OR_IDLE)) {
return MOTOR_STOPPED_AUTO;
}

View file

@ -19,6 +19,8 @@
#include "config/parameter_group.h"
#include "drivers/timer.h"
#if defined(TARGET_MOTOR_COUNT)
#define MAX_SUPPORTED_MOTORS TARGET_MOTOR_COUNT
#else
@ -62,17 +64,12 @@ typedef struct motorMixer_s {
float yaw;
} motorMixer_t;
PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer);
typedef struct mixerConfig_s {
int8_t motorDirectionInverted;
uint8_t platformType;
bool hasFlaps;
int16_t appliedMixerPreset;
typedef struct timerOverride_s {
uint8_t outputMode;
} mixerConfig_t;
} timerOverride_t;
PG_DECLARE(mixerConfig_t, mixerConfig);
PG_DECLARE_ARRAY(timerOverride_t, HARDWARE_TIMER_DEFINITION_COUNT, timerOverrides);
typedef struct reversibleMotorsConfig_s {
uint16_t deadband_low; // min 3d value
@ -110,8 +107,10 @@ 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);
uint8_t getMotorCount(void);
float getMotorMixRange(void);
bool mixerIsOutputSaturated(void);
@ -127,7 +126,8 @@ 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);
bool areMotorsRunning(void);
bool areMotorsRunning(void);

View file

@ -0,0 +1,239 @@
#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 "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 mixerConfigInit(void)
{
currentMixerProfileIndex = getConfigMixerProfile();
currentMixerConfig = *mixerConfig();
nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT;
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 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);
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;
}

View file

@ -0,0 +1,77 @@
#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 outputProfileHotSwitch(int profile_index);
bool checkMixerProfileHotSwitchAvalibility(void);
void mixerConfigInit(void);
void outputProfileUpdateTask(timeUs_t currentTimeUs);

View file

@ -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"
@ -898,17 +899,14 @@ float pidHeadingHold(float dT)
{
float headingHoldRate;
/* Convert absolute error into relative to current heading */
int16_t error = DECIDEGREES_TO_DEGREES(attitude.values.yaw) - headingHoldTarget;
/*
* Convert absolute error into relative to current heading
*/
if (error <= -180) {
error += 360;
}
if (error >= +180) {
/* Convert absolute error into relative to current heading */
if (error > 180) {
error -= 360;
} else if (error < -180) {
error += 360;
}
/*
@ -1068,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
@ -1216,9 +1214,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 {

View file

@ -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);

View file

@ -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,
@ -83,7 +82,7 @@ void pgResetFn_customServoMixers(servoMixer_t *instance)
#ifdef USE_PROGRAMMING_FRAMEWORK
,.conditionId = -1
#endif
);
);
}
}
@ -104,7 +103,8 @@ void pgResetFn_servoParams(servoParam_t *instance)
int16_t servo[MAX_SUPPORTED_SERVOS];
static uint8_t servoRuleCount = 0;
static servoMixer_t currentServoMixer[MAX_SERVO_RULES];
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;
@ -115,7 +115,7 @@ static biquadFilter_t servoFilter[MAX_SUPPORTED_SERVOS];
static bool servoFilterIsSet;
static servoMetadata_t servoMetadata[MAX_SUPPORTED_SERVOS];
static rateLimitFilter_t servoSpeedLimitFilter[MAX_SERVO_RULES];
static rateLimitFilter_t servoSpeedLimitFilter[MAX_SERVO_RULES*MAX_MIXER_PROFILE_COUNT];
STATIC_FASTRAM pt1Filter_t rotRateFilter;
STATIC_FASTRAM pt1Filter_t targetRateFilter;
@ -172,28 +172,31 @@ 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)
break;
for (int j = 0; j < MAX_MIXER_PROFILE_COUNT; j++) {
const servoMixer_t* tmp_customServoMixers = &mixerServoMixersByIndex(j)[0];
// load custom mixer into currentServoMixer
for (int i = 0; i < MAX_SERVO_RULES; i++) {
// check if done
if (tmp_customServoMixers[i].rate == 0)
break;
if (customServoMixers(i)->targetChannel < minServoIndex) {
minServoIndex = customServoMixers(i)->targetChannel;
if (tmp_customServoMixers[i].targetChannel < minServoIndex) {
minServoIndex = tmp_customServoMixers[i].targetChannel;
}
if (tmp_customServoMixers[i].targetChannel > maxServoIndex) {
maxServoIndex = tmp_customServoMixers[i].targetChannel;
}
memcpy(&currentServoMixer[servoRuleCount], &tmp_customServoMixers[i], sizeof(servoMixer_t));
currentServoMixerActivative[servoRuleCount] = j==currentMixerProfileIndex;
servoRuleCount++;
}
if (customServoMixers(i)->targetChannel > maxServoIndex) {
maxServoIndex = customServoMixers(i)->targetChannel;
}
memcpy(&currentServoMixer[i], customServoMixers(i), sizeof(servoMixer_t));
servoRuleCount++;
}
}
@ -231,7 +234,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 +264,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 +300,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 +340,22 @@ 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;
if (!currentServoMixerActivative[i]) {
inputRaw = 0;
}
/*
* Apply mixer speed limit. 1 [one] speed unit is defined as 10us/s:
* 0 = no limiting
@ -355,7 +363,7 @@ 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;
}
@ -430,6 +438,8 @@ void processServoAutotrimMode(void)
if (ARMING_FLAG(ARMED)) {
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
for (int i = 0; i < servoRuleCount; i++) {
if (!currentServoMixerActivative[i]) {continue;}
// Reset servo middle accumulator
const uint8_t target = currentServoMixer[i].targetChannel;
const uint8_t source = currentServoMixer[i].inputSource;
if (source == axis) {
@ -451,6 +461,7 @@ void processServoAutotrimMode(void)
if (ARMING_FLAG(ARMED)) {
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
for (int i = 0; i < servoRuleCount; i++) {
if (!currentServoMixerActivative[i]) {continue;}
const uint8_t target = currentServoMixer[i].targetChannel;
const uint8_t source = currentServoMixer[i].inputSource;
if (source == axis) {
@ -463,6 +474,7 @@ void processServoAutotrimMode(void)
if ((millis() - trimStartedAt) > SERVO_AUTOTRIM_TIMER_MS) {
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
for (int i = 0; i < servoRuleCount; i++) {
if (!currentServoMixerActivative[i]) {continue;}
const uint8_t target = currentServoMixer[i].targetChannel;
const uint8_t source = currentServoMixer[i].inputSource;
if (source == axis) {
@ -496,6 +508,7 @@ void processServoAutotrimMode(void)
if (trimState == AUTOTRIM_SAVE_PENDING) {
for (int axis = FD_ROLL; axis <= FD_YAW; axis++) {
for (int i = 0; i < servoRuleCount; i++) {
if (!currentServoMixerActivative[i]) {continue;}
const uint8_t target = currentServoMixer[i].targetChannel;
const uint8_t source = currentServoMixer[i].inputSource;
if (source == axis) {
@ -593,6 +606,10 @@ void processServoAutotrim(const float dT) {
return;
}
#endif
if(!STATE(AIRPLANE))
{
return;
}
if (feature(FEATURE_FW_AUTOTRIM)) {
processContinuousServoAutotrim(dT);
} else {

View file

@ -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);

View file

@ -95,13 +95,6 @@ gpsSolutionData_t gpsSol; //used in the rest of the code
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 },
@ -131,7 +124,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,
@ -452,7 +445,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)

View file

@ -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;

View file

@ -1,341 +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;
gpsSolDRV.numSat = gps_Msg.numSat;
if (gps_Msg.fix) {
gpsSolDRV.fixType = GPS_FIX_3D; // NMEA doesn't report fix type, assume 3D
gpsSolDRV.llh.lat = gps_Msg.latitude;
gpsSolDRV.llh.lon = gps_Msg.longitude;
gpsSolDRV.llh.alt = gps_Msg.altitude;
// EPH/EPV are unreliable for NMEA as they are not real accuracy
gpsSolDRV.hdop = gpsConstrainHDOP(gps_Msg.hdop);
gpsSolDRV.eph = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER);
gpsSolDRV.epv = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER);
gpsSolDRV.flags.validEPE = false;
}
else {
gpsSolDRV.fixType = GPS_NO_FIX;
}
// NMEA does not report VELNED
gpsSolDRV.flags.validVelNE = false;
gpsSolDRV.flags.validVelD = false;
break;
case FRAME_RMC:
gpsSolDRV.groundSpeed = gps_Msg.speed;
gpsSolDRV.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) {
gpsSolDRV.time.year = (gps_Msg.date % 100) + 2000;
gpsSolDRV.time.month = (gps_Msg.date / 100) % 100;
gpsSolDRV.time.day = (gps_Msg.date / 10000) % 100;
gpsSolDRV.time.hours = (gps_Msg.time / 1000000) % 100;
gpsSolDRV.time.minutes = (gps_Msg.time / 10000) % 100;
gpsSolDRV.time.seconds = (gps_Msg.time / 100) % 100;
gpsSolDRV.time.millis = (gps_Msg.time & 100) * 10;
gpsSolDRV.flags.validTime = true;
}
else {
gpsSolDRV.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)) {
gpsSolDRV.flags.validVelNE = false;
gpsSolDRV.flags.validVelD = false;
gpsProcessNewDriverData();
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(false);
}
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

View file

@ -78,9 +78,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);

View file

@ -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
};

View file

@ -159,12 +159,12 @@ typedef struct ledStripConfig_s {
PG_DECLARE(ledStripConfig_t, ledStripConfig);
#define DEFINE_LED(ledConfigPtr, x, y, col, dir, func, ol, params) { \
ledConfigPtr->led_position = CALCULATE_LED_XY(x, y); \
ledConfigPtr->led_color = (col); \
ledConfigPtr->led_direction = (dir); \
ledConfigPtr->led_function = (func); \
ledConfigPtr->led_overlay = (ol); \
ledConfigPtr->led_params = (params); }
(ledConfigPtr)->led_position = CALCULATE_LED_XY(x, y); \
(ledConfigPtr)->led_color = (col); \
(ledConfigPtr)->led_direction = (dir); \
(ledConfigPtr)->led_function = (func); \
(ledConfigPtr)->led_overlay = (ol); \
(ledConfigPtr)->led_params = (params); }
static inline uint8_t ledGetXY(const ledConfig_t *lcfg) { return (lcfg->led_position); }
static inline uint8_t ledGetX(const ledConfig_t *lcfg) { return ((lcfg->led_position >> (LED_X_BIT_OFFSET)) & LED_XY_MASK); }

View file

@ -831,13 +831,14 @@ static const char * osdArmingDisabledReasonMessage(void)
// See handling of FAILSAFE_RX_LOSS_MONITORING in failsafe.c
if (failsafePhase() == FAILSAFE_RX_LOSS_MONITORING) {
if (failsafeIsReceivingRxData()) {
// If we're not using sticks, it means the ARM switch
// hasn't been off since entering FAILSAFE_RX_LOSS_MONITORING
// yet
return OSD_MESSAGE_STR(OSD_MSG_TURN_ARM_SW_OFF);
// reminder to disarm to exit FAILSAFE_RX_LOSS_MONITORING once timeout period ends
if (IS_RC_MODE_ACTIVE(BOXARM)) {
return OSD_MESSAGE_STR(OSD_MSG_TURN_ARM_SW_OFF);
}
} else {
// Not receiving RX data
return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST);
}
// Not receiving RX data
return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST);
}
return OSD_MESSAGE_STR(OSD_MSG_DISABLED_BY_FS);
case ARMING_DISABLED_NOT_LEVEL:
@ -991,10 +992,10 @@ static const char * osdFailsafeInfoMessage(void)
#if defined(USE_SAFE_HOME)
static const char * divertingToSafehomeMessage(void)
{
if (NAV_Status.state != MW_NAV_STATE_HOVER_ABOVE_HOME && posControl.safehomeState.isApplied) {
return OSD_MESSAGE_STR(OSD_MSG_DIVERT_SAFEHOME);
}
return NULL;
if (NAV_Status.state != MW_NAV_STATE_HOVER_ABOVE_HOME && posControl.safehomeState.isApplied) {
return OSD_MESSAGE_STR(OSD_MSG_DIVERT_SAFEHOME);
}
return NULL;
}
#endif
@ -1116,11 +1117,7 @@ bool osdUsingScaledThrottle(void)
**/
static void osdFormatThrottlePosition(char *buff, bool useScaled, textAttributes_t *elemAttr)
{
if (useScaled) {
buff[0] = SYM_SCALE;
} else {
buff[0] = SYM_BLANK;
}
buff[0] = SYM_BLANK;
buff[1] = SYM_THR;
if (navigationIsControllingThrottle()) {
buff[0] = SYM_AUTO_THR0;
@ -1135,7 +1132,14 @@ static void osdFormatThrottlePosition(char *buff, bool useScaled, textAttributes
TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr);
}
#endif
tfp_sprintf(buff + 2, "%3d", getThrottlePercent(useScaled));
int8_t throttlePercent = getThrottlePercent(useScaled);
if ((useScaled && throttlePercent <= 0) || !ARMING_FLAG(ARMED)) {
const char* message = ARMING_FLAG(ARMED) ? throttlePercent == 0 ? "IDLE" : "STOP" : "DARM";
buff[0] = SYM_THR;
strcpy(buff + 1, message);
return;
}
tfp_sprintf(buff + 2, "%3d", throttlePercent);
}
/**
@ -4483,14 +4487,14 @@ static void osdShowArmed(void)
if (posControl.safehomeState.distance) { // safehome found during arming
if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) {
strcpy(buf, "SAFEHOME FOUND; MODE OFF");
} else {
char buf2[12]; // format the distance first
osdFormatDistanceStr(buf2, posControl.safehomeState.distance);
tfp_sprintf(buf, "%c - %s -> SAFEHOME %u", SYM_HOME, buf2, posControl.safehomeState.index);
}
textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT;
// write this message above the ARMED message to make it obvious
displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y - 8, buf, elemAttr);
} else {
char buf2[12]; // format the distance first
osdFormatDistanceStr(buf2, posControl.safehomeState.distance);
tfp_sprintf(buf, "%c - %s -> SAFEHOME %u", SYM_HOME, buf2, posControl.safehomeState.index);
}
textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT;
// write this message above the ARMED message to make it obvious
displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y - 8, buf, elemAttr);
}
#endif
} else {
@ -4943,6 +4947,16 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
// by OSD_FLYMODE.
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD);
}
if (STATE(MULTIROTOR) && FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) {
if (posControl.cruise.multicopterSpeed >= 50.0f) {
char buf[6];
osdFormatVelocityStr(buf, posControl.cruise.multicopterSpeed, false, false);
tfp_sprintf(messageBuf, "(SPD %s)", buf);
} else {
strcpy(messageBuf, "(HOLD)");
}
messages[messageCount++] = messageBuf;
}
if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM);
}

View file

@ -31,6 +31,9 @@
#define MSP2_INAV_OUTPUT_MAPPING 0x200A
#define MSP2_INAV_MC_BRAKING 0x200B
#define MSP2_INAV_SET_MC_BRAKING 0x200C
#define MSP2_INAV_OUTPUT_MAPPING_EXT 0x200D
#define MSP2_INAV_TIMER_OUTPUT_MODE 0x200E
#define MSP2_INAV_SET_TIMER_OUTPUT_MODE 0x200F
#define MSP2_INAV_MIXER 0x2010
#define MSP2_INAV_SET_MIXER 0x2011

View file

@ -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
@ -95,7 +96,7 @@ STATIC_ASSERT(NAV_MAX_WAYPOINTS < 254, NAV_MAX_WAYPOINTS_exceeded_allowable_rang
PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 2);
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 4);
PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 5);
PG_RESET_TEMPLATE(navConfig_t, navConfig,
.general = {
@ -152,6 +153,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.land_detect_sensitivity = SETTING_NAV_LAND_DETECT_SENSITIVITY_DEFAULT, // Changes sensitivity of landing detection
.auto_disarm_delay = SETTING_NAV_AUTO_DISARM_DELAY_DEFAULT, // 2000 ms - time delay to disarm when auto disarm after landing enabled
.rth_linear_descent_start_distance = SETTING_NAV_RTH_LINEAR_DESCENT_START_DISTANCE_DEFAULT,
.cruise_yaw_rate = SETTING_NAV_CRUISE_YAW_RATE_DEFAULT, // 20dps
},
// MC-specific
@ -207,7 +209,6 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT,// OFF
.launch_abort_deadband = SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT, // 100 us
.cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps
.allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT,
.useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT,
.yawControlDeadband = SETTING_NAV_FW_YAW_DEADBAND_DEFAULT,
@ -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,
}
},
@ -422,7 +427,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
.persistentId = NAV_PERSISTENT_ID_COURSE_HOLD_IN_PROGRESS,
.onEntry = navOnEnteringState_NAV_STATE_COURSE_HOLD_IN_PROGRESS,
.timeoutMs = 10,
.stateFlags = NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_RC_POS | NAV_RC_YAW,
.stateFlags = NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_RC_POS | NAV_RC_YAW,
.mapToFlightModes = NAV_COURSE_HOLD_MODE,
.mwState = MW_NAV_STATE_NONE,
.mwError = MW_NAV_ERROR_NONE,
@ -481,7 +486,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
.persistentId = NAV_PERSISTENT_ID_CRUISE_IN_PROGRESS,
.onEntry = navOnEnteringState_NAV_STATE_CRUISE_IN_PROGRESS,
.timeoutMs = 10,
.stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_RC_POS | NAV_RC_YAW | NAV_RC_ALT,
.stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_RC_POS | NAV_RC_YAW | NAV_RC_ALT,
.mapToFlightModes = NAV_ALTHOLD_MODE | NAV_COURSE_HOLD_MODE,
.mwState = MW_NAV_STATE_NONE,
.mwError = MW_NAV_ERROR_NONE,
@ -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)
@ -948,7 +1002,7 @@ static navigationFSMStateFlags_t navGetStateFlags(navigationFSMState_t state)
return navFSM[state].stateFlags;
}
static flightModeFlags_e navGetMappedFlightModes(navigationFSMState_t state)
flightModeFlags_e navGetMappedFlightModes(navigationFSMState_t state)
{
return navFSM[state].mapToFlightModes;
}
@ -1055,7 +1109,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_INITIALIZE(
{
UNUSED(previousState);
if (!STATE(FIXED_WING_LEGACY)) { // Only on FW for now
if (STATE(MULTIROTOR) && !navConfig()->general.cruise_yaw_rate) { // course hold not possible on MR without yaw control
return NAV_FSM_EVENT_ERROR;
}
@ -1067,7 +1121,13 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_INITIALIZE(
resetPositionController();
posControl.cruise.course = posControl.actualState.cog; // Store the course to follow
if (STATE(AIRPLANE)) {
posControl.cruise.course = posControl.actualState.cog; // Store the course to follow
} else { // Multicopter
posControl.cruise.course = posControl.actualState.yaw;
posControl.cruise.multicopterSpeed = constrainf(posControl.actualState.velXY, 10.0f, navConfig()->general.max_manual_speed);
posControl.desiredState.pos = posControl.actualState.abs.pos;
}
posControl.cruise.previousCourse = posControl.cruise.course;
posControl.cruise.lastCourseAdjustmentTime = 0;
@ -1088,15 +1148,24 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_IN_PROGRESS
DEBUG_SET(DEBUG_CRUISE, 0, 2);
DEBUG_SET(DEBUG_CRUISE, 2, 0);
if (posControl.flags.isAdjustingPosition) {
if (STATE(AIRPLANE) && posControl.flags.isAdjustingPosition) { // inhibit for MR, pitch/roll only adjusts speed using pitch
return NAV_FSM_EVENT_SWITCH_TO_COURSE_ADJ;
}
// User is yawing. We record the desidered yaw and we change the desidered target in the meanwhile
if (posControl.flags.isAdjustingHeading) {
const bool mcRollStickHeadingAdjustmentActive = STATE(MULTIROTOR) && ABS(rcCommand[ROLL]) > rcControlsConfig()->pos_hold_deadband;
// User demanding yaw -> yaw stick on FW, yaw or roll sticks on MR
// We record the desired course and change the desired target in the meanwhile
if (posControl.flags.isAdjustingHeading || mcRollStickHeadingAdjustmentActive) {
int16_t cruiseYawRate = DEGREES_TO_CENTIDEGREES(navConfig()->general.cruise_yaw_rate);
int16_t headingAdjustCommand = rcCommand[YAW];
if (mcRollStickHeadingAdjustmentActive && ABS(rcCommand[ROLL]) > ABS(headingAdjustCommand)) {
headingAdjustCommand = -rcCommand[ROLL];
}
timeMs_t timeDifference = currentTimeMs - posControl.cruise.lastCourseAdjustmentTime;
if (timeDifference > 100) timeDifference = 0; // if adjustment was called long time ago, reset the time difference.
float rateTarget = scaleRangef((float)rcCommand[YAW], -500.0f, 500.0f, -DEGREES_TO_CENTIDEGREES(navConfig()->fw.cruise_yaw_rate), DEGREES_TO_CENTIDEGREES(navConfig()->fw.cruise_yaw_rate));
float rateTarget = scaleRangef((float)headingAdjustCommand, -500.0f, 500.0f, -cruiseYawRate, cruiseYawRate);
float centidegsPerIteration = rateTarget * MS2S(timeDifference);
posControl.cruise.course = wrap_36000(posControl.cruise.course - centidegsPerIteration);
DEBUG_SET(DEBUG_CRUISE, 1, CENTIDEGREES_TO_DEGREES(posControl.cruise.course));
@ -1129,7 +1198,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_COURSE_HOLD_ADJUSTING(n
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_CRUISE_INITIALIZE(navigationFSMState_t previousState)
{
if (!STATE(FIXED_WING_LEGACY)) { return NAV_FSM_EVENT_ERROR; } // only on FW for now
if (STATE(MULTIROTOR) && !navConfig()->general.cruise_yaw_rate) { // course hold not possible on MR without yaw control
return NAV_FSM_EVENT_ERROR;
}
navOnEnteringState_NAV_STATE_ALTHOLD_INITIALIZE(previousState);
@ -1349,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);
@ -1439,12 +1514,22 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF
if (posControl.flags.estHeadingStatus == EST_NONE || checkForPositionSensorTimeout() || !validateRTHSanityChecker()) {
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
}
if (checkMixerATRequired(MIXERAT_REQUEST_LAND)){
return NAV_FSM_EVENT_SWITCH_TO_MIXERAT;
}
float descentVelLimited = 0;
int32_t landingElevation = posControl.rthState.homeTmpWaypoint.z;
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;
@ -1789,8 +1874,6 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_FINIS
{
UNUSED(previousState);
disarm(DISARM_NAVIGATION);
return NAV_FSM_EVENT_NONE;
}
@ -1839,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;
@ -2459,13 +2606,13 @@ void checkSafeHomeState(bool shouldBeEnabled)
safehomeNotApplicable = safehomeNotApplicable || (MULTI_FUNC_FLAG(MF_SUSPEND_SAFEHOMES) && !posControl.flags.forcedRTHActivated);
#endif
if (safehomeNotApplicable) {
shouldBeEnabled = false;
} else if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_RTH_FS && shouldBeEnabled) {
// if safehomes are only used with failsafe and we're trying to enable safehome
// then enable the safehome only with failsafe
shouldBeEnabled = posControl.flags.forcedRTHActivated;
}
if (safehomeNotApplicable) {
shouldBeEnabled = false;
} else if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_RTH_FS && shouldBeEnabled) {
// if safehomes are only used with failsafe and we're trying to enable safehome
// then enable the safehome only with failsafe
shouldBeEnabled = posControl.flags.forcedRTHActivated;
}
// no safe homes found when arming or safehome feature in the correct state, then we don't need to do anything
if (posControl.safehomeState.distance == 0 || posControl.safehomeState.isApplied == shouldBeEnabled) {
return;
@ -2496,8 +2643,8 @@ bool findNearestSafeHome(void)
gpsLocation_t shLLH;
shLLH.alt = 0;
for (uint8_t i = 0; i < MAX_SAFE_HOMES; i++) {
if (!safeHomeConfig(i)->enabled)
continue;
if (!safeHomeConfig(i)->enabled)
continue;
shLLH.lat = safeHomeConfig(i)->lat;
shLLH.lon = safeHomeConfig(i)->lon;
@ -2834,7 +2981,7 @@ void updateLandingStatus(timeMs_t currentTimeMs)
}
} else if (STATE(LANDING_DETECTED)) {
pidResetErrorAccumulators();
if (navConfig()->general.flags.disarm_on_landing) {
if (navConfig()->general.flags.disarm_on_landing && !FLIGHT_MODE(FAILSAFE_MODE)) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED);
disarm(DISARM_LANDING);
} else if (!navigationInAutomaticThrottleMode()) {
@ -3437,33 +3584,34 @@ bool isNavHoldPositionActive(void)
navigationIsExecutingAnEmergencyLanding();
}
float getActiveWaypointSpeed(void)
float getActiveSpeed(void)
{
if (posControl.flags.isAdjustingPosition) {
// In manual control mode use different cap for speed
/* Currently only applicable for multicopter */
// Speed limit for modes where speed manually controlled
if (posControl.flags.isAdjustingPosition || FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) {
return navConfig()->general.max_manual_speed;
}
else {
uint16_t waypointSpeed = navConfig()->general.auto_speed;
if (navGetStateFlags(posControl.navState) & NAV_AUTO_WP) {
if (posControl.waypointCount > 0 && (posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_LAND)) {
float wpSpecificSpeed = 0.0f;
if(posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_HOLD_TIME)
wpSpecificSpeed = posControl.waypointList[posControl.activeWaypointIndex].p2; // P1 is hold time
else
wpSpecificSpeed = posControl.waypointList[posControl.activeWaypointIndex].p1; // default case
uint16_t waypointSpeed = navConfig()->general.auto_speed;
if (wpSpecificSpeed >= 50.0f && wpSpecificSpeed <= navConfig()->general.max_auto_speed) {
waypointSpeed = wpSpecificSpeed;
} else if (wpSpecificSpeed > navConfig()->general.max_auto_speed) {
waypointSpeed = navConfig()->general.max_auto_speed;
}
if (navGetStateFlags(posControl.navState) & NAV_AUTO_WP) {
if (posControl.waypointCount > 0 && (posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_LAND)) {
float wpSpecificSpeed = 0.0f;
if(posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_HOLD_TIME)
wpSpecificSpeed = posControl.waypointList[posControl.activeWaypointIndex].p2; // P1 is hold time
else
wpSpecificSpeed = posControl.waypointList[posControl.activeWaypointIndex].p1; // default case
if (wpSpecificSpeed >= 50.0f && wpSpecificSpeed <= navConfig()->general.max_auto_speed) {
waypointSpeed = wpSpecificSpeed;
} else if (wpSpecificSpeed > navConfig()->general.max_auto_speed) {
waypointSpeed = navConfig()->general.max_auto_speed;
}
}
return waypointSpeed;
}
return waypointSpeed;
}
bool isWaypointNavTrackingActive(void)
@ -3482,29 +3630,21 @@ static void processNavigationRCAdjustments(void)
{
/* Process pilot's RC input. Disable all pilot's input when in FAILSAFE_MODE */
navigationFSMStateFlags_t navStateFlags = navGetStateFlags(posControl.navState);
if ((navStateFlags & NAV_RC_ALT) && (!FLIGHT_MODE(FAILSAFE_MODE))) {
posControl.flags.isAdjustingAltitude = adjustAltitudeFromRCInput();
}
else {
posControl.flags.isAdjustingAltitude = false;
}
if (navStateFlags & NAV_RC_POS) {
posControl.flags.isAdjustingPosition = adjustPositionFromRCInput() && !FLIGHT_MODE(FAILSAFE_MODE);
if (STATE(MULTIROTOR) && FLIGHT_MODE(FAILSAFE_MODE)) {
if (FLIGHT_MODE(FAILSAFE_MODE)) {
if (STATE(MULTIROTOR) && navStateFlags & NAV_RC_POS) {
resetMulticopterBrakingMode();
}
}
else {
posControl.flags.isAdjustingAltitude = false;
posControl.flags.isAdjustingPosition = false;
posControl.flags.isAdjustingHeading = false;
return;
}
if ((navStateFlags & NAV_RC_YAW) && (!FLIGHT_MODE(FAILSAFE_MODE))) {
posControl.flags.isAdjustingHeading = adjustHeadingFromRCInput();
}
else {
posControl.flags.isAdjustingHeading = false;
}
posControl.flags.isAdjustingAltitude = (navStateFlags & NAV_RC_ALT) && adjustAltitudeFromRCInput();
posControl.flags.isAdjustingPosition = (navStateFlags & NAV_RC_POS) && adjustPositionFromRCInput();
posControl.flags.isAdjustingHeading = (navStateFlags & NAV_RC_YAW) && adjustHeadingFromRCInput();
}
/*-----------------------------------------------------------
@ -3787,14 +3927,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;
}
@ -3861,17 +4001,16 @@ int8_t navigationGetHeadingControlState(void)
}
// For multirotors it depends on navigation system mode
// Course hold requires Auto Control to update heading hold target whilst RC adjustment active
if (navGetStateFlags(posControl.navState) & NAV_REQUIRE_MAGHOLD) {
if (posControl.flags.isAdjustingHeading) {
if (posControl.flags.isAdjustingHeading && !FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) {
return NAV_HEADING_CONTROL_MANUAL;
}
else {
return NAV_HEADING_CONTROL_AUTO;
}
}
else {
return NAV_HEADING_CONTROL_NONE;
return NAV_HEADING_CONTROL_AUTO;
}
return NAV_HEADING_CONTROL_NONE;
}
bool navigationTerrainFollowingEnabled(void)
@ -4213,15 +4352,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
@ -4282,7 +4412,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;
}
@ -4377,7 +4507,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)
@ -4413,3 +4543,8 @@ bool isAdjustingHeading(void) {
int32_t getCruiseHeadingAdjustment(void) {
return wrap_18000(posControl.cruise.course - posControl.cruise.previousCourse);
}
int32_t navigationGetHeadingError(void)
{
return wrap_18000(posControl.desiredState.yaw - posControl.actualState.cog);
}

View file

@ -271,6 +271,7 @@ typedef struct navConfig_s {
uint8_t land_detect_sensitivity; // Sensitivity of landing detector
uint16_t auto_disarm_delay; // safety time delay for landing detector
uint16_t rth_linear_descent_start_distance; // Distance from home to start the linear descent (0 = immediately)
uint8_t cruise_yaw_rate; // Max yaw rate (dps) when CRUISE MODE is enabled
} general;
struct {
@ -319,7 +320,6 @@ typedef struct navConfig_s {
uint8_t launch_max_angle; // Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]
bool launch_manual_throttle; // Allows launch with manual throttle control
uint8_t launch_abort_deadband; // roll/pitch stick movement deadband for launch abort
uint8_t cruise_yaw_rate; // Max yaw rate (dps) when CRUISE MODE is enabled
bool allow_manual_thr_increase;
bool useFwNavYawControl;
uint8_t yawControlDeadband;

View file

@ -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"
@ -71,7 +72,6 @@ static bool isRollAdjustmentValid = false;
static bool isYawAdjustmentValid = false;
static float throttleSpeedAdjustment = 0;
static bool isAutoThrottleManuallyIncreased = false;
static int32_t navHeadingError;
static float navCrossTrackError;
static int8_t loiterDirYaw = 1;
bool needToCalculateCircularLoiter;
@ -294,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.
@ -445,7 +449,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta
* Calculate NAV heading error
* Units are centidegrees
*/
navHeadingError = wrap_18000(virtualTargetBearing - posControl.actualState.cog);
int32_t navHeadingError = wrap_18000(virtualTargetBearing - posControl.actualState.cog);
// Forced turn direction
// If heading error is close to 180 deg we initiate forced turn and only disable it when heading error goes below 90 deg
@ -647,7 +651,7 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat
isAutoThrottleManuallyIncreased = false;
}
rcCommand[THROTTLE] = constrain(correctedThrottleValue, getThrottleIdleValue(), motorConfig()->maxthrottle);
rcCommand[THROTTLE] = setDesiredThrottle(correctedThrottleValue, false);
}
#ifdef NAV_FIXED_WING_LANDING
@ -662,7 +666,6 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat
(posControl.flags.estAglStatus == EST_TRUSTED && posControl.actualState.agl.pos.z <= navConfig()->general.land_slowdown_minalt)) {
// Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled
rcCommand[THROTTLE] = getThrottleIdleValue();
ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE);
// Stabilize ROLL axis on 0 degrees banking regardless of loiter radius and position
@ -762,7 +765,7 @@ bool isFixedWingLandingDetected(void)
*-----------------------------------------------------------*/
void applyFixedWingEmergencyLandingController(timeUs_t currentTimeUs)
{
rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle;
rcCommand[THROTTLE] = setDesiredThrottle(currentBatteryProfile->failsafe_throttle, true);
if (posControl.flags.estAltStatus >= EST_USABLE) {
// target min descent rate 10m above takeoff altitude
@ -851,11 +854,6 @@ void applyFixedWingNavigationController(navigationFSMStateFlags_t navStateFlags,
}
}
int32_t navigationGetHeadingError(void)
{
return navHeadingError;
}
float navigationGetCrossTrackError(void)
{
return navCrossTrackError;

View file

@ -234,19 +234,12 @@ static void setCurrentState(fixedWingLaunchState_t nextState, timeUs_t currentTi
/* Wing control Helpers */
static bool isThrottleIdleEnabled(void)
{
return currentBatteryProfile->nav.fw.launch_idle_throttle > getThrottleIdleValue();
}
static void applyThrottleIdleLogic(bool forceMixerIdle)
{
if (isThrottleIdleEnabled() && !forceMixerIdle) {
rcCommand[THROTTLE] = currentBatteryProfile->nav.fw.launch_idle_throttle;
}
else {
ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); // If MOTOR_STOP is enabled mixer will keep motor stopped
rcCommand[THROTTLE] = getThrottleIdleValue(); // If MOTOR_STOP is disabled, motors will spin given throttle value
if (forceMixerIdle) {
ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); // If MOTOR_STOP is enabled mixer will keep motor stopped, otherwise motor will run at idle
} else {
rcCommand[THROTTLE] = setDesiredThrottle(currentBatteryProfile->nav.fw.launch_idle_throttle, true);
}
}
@ -290,7 +283,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs
UNUSED(currentTimeUs);
if (!throttleStickIsLow()) {
if (isThrottleIdleEnabled()) {
if (currentBatteryProfile->nav.fw.launch_idle_throttle > getThrottleIdleValue()) {
return FW_LAUNCH_EVENT_SUCCESS;
}
else {
@ -404,7 +397,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_SPINUP(timeUs_
const timeMs_t elapsedTimeMs = currentStateElapsedMs(currentTimeUs);
const uint16_t motorSpinUpMs = navConfig()->fw.launch_motor_spinup_time;
const uint16_t launchThrottle = constrain(currentBatteryProfile->nav.fw.launch_throttle, getThrottleIdleValue(), motorConfig()->maxthrottle);
const uint16_t launchThrottle = setDesiredThrottle(currentBatteryProfile->nav.fw.launch_throttle, false);
if (elapsedTimeMs > motorSpinUpMs) {
rcCommand[THROTTLE] = launchThrottle;
@ -438,7 +431,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IN_PROGRESS(timeUs_t
}
} else {
initialTime = navConfig()->fw.launch_motor_timer + navConfig()->fw.launch_motor_spinup_time;
rcCommand[THROTTLE] = constrain(currentBatteryProfile->nav.fw.launch_throttle, getThrottleIdleValue(), motorConfig()->maxthrottle);
rcCommand[THROTTLE] = setDesiredThrottle(currentBatteryProfile->nav.fw.launch_throttle, false);
}
if (isLaunchMaxAltitudeReached()) {
@ -468,7 +461,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_FINISH(timeUs_t curr
// Make a smooth transition from the launch state to the current state for pitch angle
// Do the same for throttle when manual launch throttle isn't used
if (!navConfig()->fw.launch_manual_throttle) {
const uint16_t launchThrottle = constrain(currentBatteryProfile->nav.fw.launch_throttle, getThrottleIdleValue(), motorConfig()->maxthrottle);
const uint16_t launchThrottle = setDesiredThrottle(currentBatteryProfile->nav.fw.launch_throttle, false);
rcCommand[THROTTLE] = scaleRangef(elapsedTimeMs, 0.0f, endTimeMs, launchThrottle, rcCommand[THROTTLE]);
}
fwLaunch.pitchAngle = scaleRangef(elapsedTimeMs, 0.0f, endTimeMs, navConfig()->fw.launch_climb_angle, rcCommand[PITCH]);

View file

@ -121,7 +121,7 @@ static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros)
int16_t rcThrottleCorrection = pt1FilterApply4(&altholdThrottleFilterState, velocity_controller, NAV_THROTTLE_CUTOFF_FREQENCY_HZ, US2S(deltaMicros));
rcThrottleCorrection = constrain(rcThrottleCorrection, thrCorrectionMin, thrCorrectionMax);
posControl.rcAdjustment[THROTTLE] = constrain(currentBatteryProfile->nav.mc.hover_throttle + rcThrottleCorrection, getThrottleIdleValue(), motorConfig()->maxthrottle);
posControl.rcAdjustment[THROTTLE] = setDesiredThrottle(currentBatteryProfile->nav.mc.hover_throttle + rcThrottleCorrection, false);
}
bool adjustMulticopterAltitudeFromRCInput(void)
@ -218,7 +218,7 @@ void resetMulticopterAltitudeController(void)
pt1FilterReset(&posControl.pids.vel[Z].dterm_filter_state, 0.0f);
if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) {
const float maxSpeed = getActiveWaypointSpeed();
const float maxSpeed = getActiveSpeed();
nav_speed_up = maxSpeed;
nav_accel_z = maxSpeed;
nav_speed_down = navConfig()->general.max_auto_climb_rate;
@ -285,14 +285,15 @@ static void applyMulticopterAltitudeController(timeUs_t currentTimeUs)
bool adjustMulticopterHeadingFromRCInput(void)
{
if (ABS(rcCommand[YAW]) > rcControlsConfig()->pos_hold_deadband) {
// Can only allow pilot to set the new heading if doing PH, during RTH copter will target itself to home
posControl.desiredState.yaw = posControl.actualState.yaw;
// Heading during Cruise Hold mode set by Nav function so no adjustment required here
if (!FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) {
posControl.desiredState.yaw = posControl.actualState.yaw;
}
return true;
}
else {
return false;
}
return false;
}
/*-----------------------------------------------------------
@ -402,8 +403,44 @@ void resetMulticopterPositionController(void)
}
}
static bool adjustMulticopterCruiseSpeed(int16_t rcPitchAdjustment)
{
static timeMs_t lastUpdateTimeMs;
const timeMs_t currentTimeMs = millis();
const timeMs_t updateDeltaTimeMs = currentTimeMs - lastUpdateTimeMs;
lastUpdateTimeMs = currentTimeMs;
const float rcVelX = rcPitchAdjustment * navConfig()->general.max_manual_speed / (float)(500 - rcControlsConfig()->pos_hold_deadband);
if (rcVelX > posControl.cruise.multicopterSpeed) {
posControl.cruise.multicopterSpeed = rcVelX;
} else if (rcVelX < 0 && updateDeltaTimeMs < 100) {
posControl.cruise.multicopterSpeed += MS2S(updateDeltaTimeMs) * rcVelX / 2.0f;
} else {
return false;
}
posControl.cruise.multicopterSpeed = constrainf(posControl.cruise.multicopterSpeed, 10.0f, navConfig()->general.max_manual_speed);
return true;
}
static void setMulticopterStopPosition(void)
{
fpVector3_t stopPosition;
calculateMulticopterInitialHoldPosition(&stopPosition);
setDesiredPosition(&stopPosition, 0, NAV_POS_UPDATE_XY);
}
bool adjustMulticopterPositionFromRCInput(int16_t rcPitchAdjustment, int16_t rcRollAdjustment)
{
if (navGetMappedFlightModes(posControl.navState) & NAV_COURSE_HOLD_MODE) {
if (rcPitchAdjustment) {
return adjustMulticopterCruiseSpeed(rcPitchAdjustment);
}
return false;
}
// Process braking mode
processMulticopterBrakingMode(rcPitchAdjustment || rcRollAdjustment);
@ -425,16 +462,12 @@ bool adjustMulticopterPositionFromRCInput(int16_t rcPitchAdjustment, int16_t rcR
return true;
}
else {
else if (posControl.flags.isAdjustingPosition) {
// Adjusting finished - reset desired position to stay exactly where pilot released the stick
if (posControl.flags.isAdjustingPosition) {
fpVector3_t stopPosition;
calculateMulticopterInitialHoldPosition(&stopPosition);
setDesiredPosition(&stopPosition, 0, NAV_POS_UPDATE_XY);
}
return false;
setMulticopterStopPosition();
}
return false;
}
static float getVelocityHeadingAttenuationFactor(void)
@ -463,15 +496,28 @@ static float getVelocityExpoAttenuationFactor(float velTotal, float velMax)
static void updatePositionVelocityController_MC(const float maxSpeed)
{
if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) {
// Position held at cruise speeds below 0.5 m/s, otherwise desired neu velocities set directly from cruise speed
if (posControl.cruise.multicopterSpeed >= 50) {
// Rotate multicopter x velocity from body frame to earth frame
posControl.desiredState.vel.x = posControl.cruise.multicopterSpeed * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.cruise.course));
posControl.desiredState.vel.y = posControl.cruise.multicopterSpeed * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.cruise.course));
return;
} else if (posControl.flags.isAdjustingPosition) {
setMulticopterStopPosition();
}
}
const float posErrorX = posControl.desiredState.pos.x - navGetCurrentActualPositionAndVelocity()->pos.x;
const float posErrorY = posControl.desiredState.pos.y - navGetCurrentActualPositionAndVelocity()->pos.y;
// Calculate target velocity
float newVelX = posErrorX * posControl.pids.pos[X].param.kP;
float newVelY = posErrorY * posControl.pids.pos[Y].param.kP;
float neuVelX = posErrorX * posControl.pids.pos[X].param.kP;
float neuVelY = posErrorY * posControl.pids.pos[Y].param.kP;
// Scale velocity to respect max_speed
float newVelTotal = calc_length_pythagorean_2D(newVelX, newVelY);
float neuVelTotal = calc_length_pythagorean_2D(neuVelX, neuVelY);
/*
* We override computed speed with max speed in following cases:
@ -481,26 +527,23 @@ static void updatePositionVelocityController_MC(const float maxSpeed)
if (
((navGetCurrentStateFlags() & NAV_AUTO_WP || posControl.flags.rthTrackbackActive) &&
!isNavHoldPositionActive() &&
newVelTotal < maxSpeed &&
neuVelTotal < maxSpeed &&
!navConfig()->mc.slowDownForTurning
) || newVelTotal > maxSpeed
) || neuVelTotal > maxSpeed
) {
newVelX = maxSpeed * (newVelX / newVelTotal);
newVelY = maxSpeed * (newVelY / newVelTotal);
newVelTotal = maxSpeed;
neuVelX = maxSpeed * (neuVelX / neuVelTotal);
neuVelY = maxSpeed * (neuVelY / neuVelTotal);
neuVelTotal = maxSpeed;
}
posControl.pids.pos[X].output_constrained = newVelX;
posControl.pids.pos[Y].output_constrained = newVelY;
posControl.pids.pos[X].output_constrained = neuVelX;
posControl.pids.pos[Y].output_constrained = neuVelY;
// Apply expo & attenuation if heading in wrong direction - turn first, accelerate later (effective only in WP mode)
const float velHeadFactor = getVelocityHeadingAttenuationFactor();
const float velExpoFactor = getVelocityExpoAttenuationFactor(newVelTotal, maxSpeed);
posControl.desiredState.vel.x = newVelX * velHeadFactor * velExpoFactor;
posControl.desiredState.vel.y = newVelY * velHeadFactor * velExpoFactor;
navDesiredVelocity[X] = constrain(lrintf(posControl.desiredState.vel.x), -32678, 32767);
navDesiredVelocity[Y] = constrain(lrintf(posControl.desiredState.vel.y), -32678, 32767);
const float velExpoFactor = getVelocityExpoAttenuationFactor(neuVelTotal, maxSpeed);
posControl.desiredState.vel.x = neuVelX * velHeadFactor * velExpoFactor;
posControl.desiredState.vel.y = neuVelY * velHeadFactor * velExpoFactor;
}
static float computeNormalizedVelocity(const float value, const float maxValue)
@ -660,49 +703,53 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA
static void applyMulticopterPositionController(timeUs_t currentTimeUs)
{
static timeUs_t previousTimePositionUpdate = 0; // Occurs @ GPS update rate
bool bypassPositionController;
// We should passthrough rcCommand is adjusting position in GPS_ATTI mode
bypassPositionController = (navConfig()->general.flags.user_control_mode == NAV_GPS_ATTI) && posControl.flags.isAdjustingPosition;
// Apply controller only if position source is valid. In absence of valid pos sensor (GPS loss), we'd stick in forced ANGLE mode
// and pilots input would be passed thru to PID controller
if ((posControl.flags.estPosStatus >= EST_USABLE)) {
// If we have new position - update velocity and acceleration controllers
if (posControl.flags.horizontalPositionDataNew) {
const timeDeltaLarge_t deltaMicrosPositionUpdate = currentTimeUs - previousTimePositionUpdate;
previousTimePositionUpdate = currentTimeUs;
if (!bypassPositionController) {
// Update position controller
if (deltaMicrosPositionUpdate < MAX_POSITION_UPDATE_INTERVAL_US) {
// Get max speed from generic NAV (waypoint specific), don't allow to move slower than 0.5 m/s
const float maxSpeed = getActiveWaypointSpeed();
updatePositionVelocityController_MC(maxSpeed);
updatePositionAccelController_MC(deltaMicrosPositionUpdate, NAV_ACCELERATION_XY_MAX, maxSpeed);
}
else {
// Position update has not occurred in time (first start or glitch), reset altitude controller
resetMulticopterPositionController();
}
}
// Indicate that information is no longer usable
posControl.flags.horizontalPositionDataConsumed = true;
}
}
else {
if (posControl.flags.estPosStatus < EST_USABLE) {
/* No position data, disable automatic adjustment, rcCommand passthrough */
posControl.rcAdjustment[PITCH] = 0;
posControl.rcAdjustment[ROLL] = 0;
bypassPositionController = true;
return;
}
if (!bypassPositionController) {
rcCommand[PITCH] = pidAngleToRcCommand(posControl.rcAdjustment[PITCH], pidProfile()->max_angle_inclination[FD_PITCH]);
rcCommand[ROLL] = pidAngleToRcCommand(posControl.rcAdjustment[ROLL], pidProfile()->max_angle_inclination[FD_ROLL]);
// Passthrough rcCommand if adjusting position in GPS_ATTI mode except when Course Hold active
bool bypassPositionController = !FLIGHT_MODE(NAV_COURSE_HOLD_MODE) &&
navConfig()->general.flags.user_control_mode == NAV_GPS_ATTI &&
posControl.flags.isAdjustingPosition;
if (posControl.flags.horizontalPositionDataNew) {
// Indicate that information is no longer usable
posControl.flags.horizontalPositionDataConsumed = true;
static timeUs_t previousTimePositionUpdate = 0; // Occurs @ GPS update rate
const timeDeltaLarge_t deltaMicrosPositionUpdate = currentTimeUs - previousTimePositionUpdate;
previousTimePositionUpdate = currentTimeUs;
if (bypassPositionController) {
return;
}
// If we have new position data - update velocity and acceleration controllers
if (deltaMicrosPositionUpdate < MAX_POSITION_UPDATE_INTERVAL_US) {
// Get max speed for current NAV mode
float maxSpeed = getActiveSpeed();
updatePositionVelocityController_MC(maxSpeed);
updatePositionAccelController_MC(deltaMicrosPositionUpdate, NAV_ACCELERATION_XY_MAX, maxSpeed);
navDesiredVelocity[X] = constrain(lrintf(posControl.desiredState.vel.x), -32678, 32767);
navDesiredVelocity[Y] = constrain(lrintf(posControl.desiredState.vel.y), -32678, 32767);
}
else {
// Position update has not occurred in time (first start or glitch), reset position controller
resetMulticopterPositionController();
}
} else if (bypassPositionController) {
return;
}
rcCommand[PITCH] = pidAngleToRcCommand(posControl.rcAdjustment[PITCH], pidProfile()->max_angle_inclination[FD_PITCH]);
rcCommand[ROLL] = pidAngleToRcCommand(posControl.rcAdjustment[ROLL], pidProfile()->max_angle_inclination[FD_ROLL]);
}
bool isMulticopterFlying(void)
@ -867,13 +914,14 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs)
rcCommand[YAW] = 0;
rcCommand[ROLL] = 0;
rcCommand[PITCH] = 0;
rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle;
/* Altitude sensors gone haywire, attempt to land regardless */
if (posControl.flags.estAltStatus < EST_USABLE) {
if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_DROP_IT) {
rcCommand[THROTTLE] = getThrottleIdleValue();
return;
}
rcCommand[THROTTLE] = setDesiredThrottle(currentBatteryProfile->failsafe_throttle, true);
return;
}
@ -926,6 +974,10 @@ void resetMulticopterHeadingController(void)
static void applyMulticopterHeadingController(void)
{
if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { // heading set by Nav during Course Hold so disable yaw stick input
rcCommand[YAW] = 0;
}
updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(posControl.desiredState.yaw));
}

View file

@ -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 {
@ -327,6 +338,7 @@ typedef struct {
int32_t course;
int32_t previousCourse;
timeMs_t lastCourseAdjustmentTime;
float multicopterSpeed;
} navCruise_t;
typedef struct {
@ -453,6 +465,7 @@ bool isFixedWingFlying(void);
bool isMulticopterFlying(void);
navigationFSMStateFlags_t navGetCurrentStateFlags(void);
flightModeFlags_e navGetMappedFlightModes(navigationFSMState_t state);
void setHomePosition(const fpVector3_t * pos, int32_t heading, navSetWaypointFlags_t useMask, navigationHomeFlags_t homeFlags);
void setDesiredPosition(const fpVector3_t * pos, int32_t yaw, navSetWaypointFlags_t useMask);
@ -462,7 +475,7 @@ void updateClimbRateToAltitudeController(float desiredClimbRate, float targetAlt
bool isNavHoldPositionActive(void);
bool isLastMissionWaypoint(void);
float getActiveWaypointSpeed(void);
float getActiveSpeed(void);
bool isWaypointNavTrackingActive(void);
void updateActualHeading(bool headingValid, int32_t newHeading, int32_t newGroundCourse);

View file

@ -138,7 +138,7 @@ void applyRoverBoatNavigationController(navigationFSMStateFlags_t navStateFlags,
rcCommand[ROLL] = 0;
rcCommand[PITCH] = 0;
rcCommand[YAW] = 0;
rcCommand[THROTTLE] = currentBatteryProfile->failsafe_throttle;
rcCommand[THROTTLE] = setDesiredThrottle(currentBatteryProfile->failsafe_throttle, true);
} else if (navStateFlags & NAV_CTL_POS) {
applyRoverBoatPositionController(currentTimeUs);
applyRoverBoatPitchRollThrottleController(navStateFlags, currentTimeUs);

View file

@ -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;
@ -785,6 +787,14 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_PROFILE: // int
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);

View file

@ -138,6 +138,8 @@ 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 // 39
LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE, //0,1 // 40
} logicFlightOperands_e;
typedef enum {

View file

@ -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);
}

View file

@ -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;

View 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;
}

View file

@ -29,13 +29,13 @@
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(TIM4, CH1, PB6, TIM_USE_PPM | TIM_USE_LED, 0, 0), // LED & PPM (DMA1_ST0_CH2)
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)
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -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(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_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]);

View file

@ -42,13 +42,13 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6500, DEVHW_MPU6500, GYRO_1_SPI_BUS,
#endif
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(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]);

View file

@ -23,19 +23,19 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0, 1), // PWM1 - PA8 RC1 - DMA2_ST1
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0), // PWM2 - PB0 RC2 - DMA1_ST5
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(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0, 1), // PWM1 - PA8 RC1 - DMA2_ST1
DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0), // PWM2 - PB0 RC2 - DMA1_ST5
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_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]);

View file

@ -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

View file

@ -23,19 +23,19 @@
#include "drivers/timer.h"
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(TIM1, CH1, PA8, TIM_USE_PPM | TIM_USE_LED, 0, 1), // PPM - DMA2_ST1
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]);

View file

@ -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

View file

@ -23,23 +23,23 @@
#include "drivers/timer.h"
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, 0, 0), // S3_IN
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN
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(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, 0, 0), // S3_IN
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN
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]);

View file

@ -23,23 +23,23 @@
#include "drivers/timer.h"
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(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_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]);

View file

@ -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]);

View file

@ -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
};

View file

@ -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

View file

@ -55,6 +55,7 @@
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_DPS310
//*********** Magnetometer / Compass *************
#define USE_MAG

View file

@ -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
};

View file

@ -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

View file

@ -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

View file

@ -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

View file

@ -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
};

View file

@ -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
};

View file

@ -23,17 +23,17 @@
#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
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), // CAM CONTROL
};

View file

@ -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
};

View file

@ -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

View file

@ -0,0 +1 @@
target_at32f43x_xGT7(BETAFPVF435 SKIP_RELEASES)

View file

@ -0,0 +1,36 @@
/*
* 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/>.
*
* This target has been autgenerated by bf2inav.py
*/
#include <stdint.h>
#include "platform.h"
#include "fc/fc_msp_box.h"
#include "fc/config.h"
#include "io/ledstrip.h"
void targetConfiguration(void)
{
ledStripConfig_t *config = ledStripConfigMutable();
ledConfig_t *lc = config->ledConfigs;
DEFINE_LED(lc, 0, 0, COLOR_RED, 0, LED_FUNCTION_COLOR, LED_FLAG_OVERLAY(LED_OVERLAY_STROBE), 0);
DEFINE_LED(lc+1, 0, 1, COLOR_GREEN, 0, LED_FUNCTION_COLOR, LED_FLAG_OVERLAY(LED_OVERLAY_STROBE), 0);
}

View file

@ -0,0 +1,44 @@
/*
* This file is part of INAV.
*
* INAV are free software. You can redistribute
* this software and/or modify this software 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 are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"
timerHardware_t timerHardware[] = {
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_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
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,201 @@
/*
* This file is part of INAV.
*
* INAV are free software. You can redistribute
* this software and/or modify this software 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 are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
//https://www.arterychip.com/download/DS/DS_AT32F435_437_V2.02-EN.pdf
#pragma once
#define TARGET_BOARD_IDENTIFIER "BHER"
#define USBD_PRODUCT_STRING "BETAFPVF435"
#define LED0 PB5
#define USE_BEEPER
#define BEEPER PB4
#define BEEPER_INVERTED
//#define ENABLE_DSHOT_DMAR DSHOT_DMAR_AUTO
//#define DSHOT_BITBANG_DEFAULT DSHOT_BITBANG_AUTO
//#define ENABLE_DSHOT
// *************** Gyro & ACC **********************
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI1_NSS_PIN PA4
//#define GYRO_1_SPI_INSTANCE SPI1
//#define USE_EXTI
//#define USE_GYRO_EXTI
//#define GYRO_1_EXTI_PIN PC4
//#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
// MPU6000
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG
#define MPU6000_SPI_BUS BUS_SPI1
#define MPU6000_CS_PIN SPI1_NSS_PIN
// ICM42605/ICM42688P
#define USE_IMU_ICM42605
#define IMU_ICM42605_ALIGN CW270_DEG
#define ICM42605_SPI_BUS BUS_SPI1
#define ICM42605_CS_PIN SPI1_NSS_PIN
//#define USE_ACC
#define USE_IMU_BMI270
#define IMU_BMI270_ALIGN CW270_DEG
#define BMI270_SPI_BUS BUS_SPI1
#define BMI270_CS_PIN SPI1_NSS_PIN
// *************** Baro **************************
#define USE_BARO
#define USE_BARO_BMP280
#define SPI3_NSS_PIN PB3
#define BMP280_SPI_BUS BUS_SPI3
#define BMP280_CS_PIN SPI3_NSS_PIN
#define USE_BARO_DPS310
#define DPS310_SPI_BUS BUS_SPI3
#define DPS310_CS_PIN SPI3_NSS_PIN
// *************** BLACKBOX **************************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define USE_FLASHFS
#define FLASH_CS_PIN PB12
#define USE_FLASH_M25P16
#define M25P16_SPI_BUS BUS_SPI2
#define M25P16_CS_PIN FLASH_CS_PIN
#define USE_FLASH_W25N01G // 1Gb NAND flash support
#define W25N01G_SPI_BUS BUS_SPI2
#define W25N01G_CS_PIN FLASH_CS_PIN
#define USE_FLASH_W25M // Stacked die support
#define W25M_SPI_BUS BUS_SPI2
#define W25M_CS_PIN FLASH_CS_PIN
#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support
#define W25M512_SPI_BUS BUS_SPI2
#define W25M512_CS_PIN FLASH_CS_PIN
#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support
#define W25M02G_SPI_BUS BUS_SPI2
#define W25M02G_CS_PIN FLASH_CS_PIN
// *************** OSD *****************************
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
#if 0
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PA15
#endif
#if 0
// I2C
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10 // SCL pad
#define I2C2_SDA PB11 // SDA pad
#define USE_I2C_PULLUP
#endif
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
#define USE_BARO_BMP280
#define USE_BARO_DPS310
// *************** UART *****************************
#define USE_VCP
#define USE_USB_DETECT
//#define USB_DETECT_PIN PC5
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10
#define USE_UART_INVERTER
#define INVERTER_PIN_UART3_RX PC9
#define INVERTER_PIN_USART3_RX PC9
#define USE_UART4
#define UART4_RX_PIN PA1
#define UART4_TX_PIN PA0
#define USE_UART5
#define UART5_RX_PIN PD2
#define UART5_TX_PIN PD2
#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6
#define SERIAL_PORT_COUNT 6
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_CRSF
#define SERIALRX_UART SERIAL_PORT_USART3
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_CHANNEL5
#define ADC_CHANNEL1_PIN PC2
#define ADC_CHANNEL2_PIN PC1
#define ADC_CHANNEL3_PIN PC0
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
#define USE_LED_STRIP
#define WS2811_PIN PB6
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP )
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
#define VBAT_SCALE_DEFAULT 110
#define CURRENT_METER_SCALE_DEFAULT 800
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE BIT(2)
#define MAX_PWM_OUTPUT_PORTS 8
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
//#define USE_DSHOT
//#define USE_ESC_SENSOR
#define USE_ESCSERIAL

View file

@ -25,20 +25,20 @@
#include "drivers/timer.h"
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM
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
DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), //camera
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP D(1, 5, 3)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP D(1, 5, 3)
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -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

View file

@ -25,13 +25,13 @@
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0 ), // PPM IN
DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT - DMA1_ST2
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT - DMA1_ST4
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1
DEF_TIM(TIM9, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S4_OUT - no DMA
// DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4_OUT - DMA1_ST3 (Could be DMA1_ST1 with dmaopt=0)
DEF_TIM(TIM3, CH4, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), // S5_OUT - DMA1_ST2
DEF_TIM(TIM3, CH3, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S6_OUT - DMA1_ST7
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT - DMA1_ST2
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT - DMA1_ST4
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT - DMA1_ST1
DEF_TIM(TIM9, CH2, PA3, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_OUT - no DMA
//DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4_OUT - DMA1_ST3 (Could be DMA1_ST1 with dmaopt=0)
DEF_TIM(TIM3, CH4, PB0, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), // S5_OUT - DMA1_ST2
DEF_TIM(TIM3, CH3, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT - DMA1_ST7
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -52,4 +52,9 @@
void targetConfiguration(void)
{
compassConfigMutable()->mag_align = CW90_DEG;
#if defined(CLRACINGF4AIRV2) || defined(CLRACINGF4AIRV3)
// To improve backwards compatibility with INAV versions 6.x and older
timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS;
#endif
}

View file

@ -25,19 +25,19 @@
DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0),
#if defined(CLRACINGF4AIRV2) || defined(CLRACINGF4AIRV3)
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0),
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0),
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0),
#else
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0),
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0),
DEF_TIM(TIM9, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0),
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM9, CH2, PA3, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0),
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0),
#endif
};

View file

@ -33,14 +33,14 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // S7_IN
DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // S8_IN
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1_OUT
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2_OUT
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT
DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT
DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6_OUT
DEF_TIM(TIM10, CH1, PB8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7_OUT
DEF_TIM(TIM11, CH1, PB9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8_OUT
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT
DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT
DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT
DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT
DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT
DEF_TIM(TIM10, CH1, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7_OUT
DEF_TIM(TIM11, CH1, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8_OUT
DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0)
};

View file

@ -24,14 +24,14 @@
timerHardware_t timerHardware[] = {
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S1 (1,7)
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 (2,2)
DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 (2,6)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 (2,1) (2.3 2.6)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S5 (2,4) (2.2)
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S6 (1,2)
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S7 (2,3)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 (2,7)
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 (1,7)
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 (2,2)
DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 (2,6)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 (2,1) (2.3 2.6)
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 (2,4) (2.2)
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 (1,2)
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1), // S7 (2,3)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 (2,7)
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED STRIP(1,0)
DEF_TIM(TIM2, CH1, PA5, TIM_USE_ANY, 0, 0), // FC CAM

View 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(TIM1))->outputMode = OUTPUT_MODE_MOTORS;
}

View file

@ -30,12 +30,12 @@
timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM ,0, 0),
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO,0,0), //S1 DMA2_ST2 T8CH1
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO,0,0), //S2 DMA2_ST3 T8CH2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO,0,0), //S3 DMA2_ST4 T8CH3
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO,0,0), //S4 DMA2_ST7 T8CH4
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR,0,0), //S5 DMA2_ST1 T1CH1
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR,0,0), //S6 DMA2_ST6 T1CH2
DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO,0,0), //S1 DMA2_ST2 T8CH1
DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO,0,0), //S2 DMA2_ST3 T8CH2
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO,0,0), //S3 DMA2_ST4 T8CH3
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO,0,0), //S4 DMA2_ST7 T8CH4
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO,0,0), //S5 DMA2_ST1 T1CH1
DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO,0,0), //S6 DMA2_ST6 T1CH2
DEF_TIM(TIM2, CH1, PA15,TIM_USE_LED,0,0), //2812 STRIP DMA1_ST5
};

View file

@ -15,14 +15,14 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PD13, TIM_USE_PWM, 0, 0), // S7_IN
DEF_TIM(TIM4, CH1, PD12, TIM_USE_PWM, 0, 0), // S8_IN
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT
DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT
DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT
DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT
DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT
DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6_OUT
DEF_TIM(TIM1, CH3, PE13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7_OUT
DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8_OUT
DEF_TIM(TIM2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT
DEF_TIM(TIM2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT
DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT
DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT
DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT
DEF_TIM(TIM1, CH3, PE13, TIM_USE_OUTPUT_AUTO, 0, 0), // S7_OUT
DEF_TIM(TIM1, CH4, PE14, TIM_USE_OUTPUT_AUTO, 0, 0), // S8_OUT
DEF_TIM(TIM9, CH2, PE6, TIM_USE_ANY, 0, 0), // sonar echo if needed
};

View file

@ -19,7 +19,7 @@
#include <platform.h>
#include "config/config_master.h"
#include "flight/mixer.h"
#include "flight/mixer_profile.h"
#include "rx/rx.h"
#include "io/serial.h"
#include "telemetry/telemetry.h"

View file

@ -23,12 +23,12 @@
timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0),
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0),
DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0),
DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0),
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0),
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0),
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 0),
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0),
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 1, 0),
DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 1, 0),
DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0),
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0),
DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0),
DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 0),

Some files were not shown because too many files have changed in this diff Show more