1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 16:25:26 +03:00

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

This commit is contained in:
Roman Lut 2023-11-03 14:40:40 +01:00
commit 9a633d1337
32 changed files with 960 additions and 368 deletions

View file

@ -1,80 +1,30 @@
# MixerProfile # MixerProfile
A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings to enable VTOL transitions. A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings. It is designed for experienced inav users.
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. ### For a tutorial of vtol setup, Read https://github.com/iNavFlight/inav/blob/master/docs/VTOL.md
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. Not limited to VTOL. air/land/sea mixed vehicle is also achievable with this feature. Model behaves according to current mixer_profile's platform_type and configured custom motor/servo mixer
Currently two profiles are supported on targets other than F411(due to resource constraints on F411). i.e VTOL transition is not available on F411.
For VTOL setup. one mixer_profile is used for multi-rotor(MR) and the other is used for fixed-wing(FW)
By default, switching between profiles requires reboot to take affect. However, using the RC mode: `MIXER PROFILE 2` will allow in flight switching for things like VTOL operation
. And will re-initialize pid and navigation controllers for current MC or FW flying mode.
Please note that this is an emerging / experimental capability that will require some effort by the pilot to implement. Please note that this is an emerging / experimental capability that will require some effort by the pilot to implement.
## Setup for VTOL ## Mixer Transition input
- 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. 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. The associated motor or servo will then move accordingly when transition mode is activated.
Transition input is disabled when navigation mode is activate 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 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 ## Servo
38 is the input source for transition input; use this to tilt motor to gain airspeed. `Mixer Transition` 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: Example: Increase servo 1 output by +45 with speed of 150 when transition mode is activated for tilted motor setup:
@ -82,15 +32,14 @@ Example: Increase servo 1 output by +45 with speed of 150 when transition mode i
# rule no; servo index; input source; rate; speed; activate logic function number # rule no; servo index; input source; rate; speed; activate logic function number
smix 6 1 38 45 150 -1 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 ## 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. The default `mmix` throttle value is 0.0, It will not show in `diff` command when throttle value is 0.0 (unused);
- 0.0<throttle<=1.0 : normal mapping - 0.0<throttle<=1.0 : normal mapping
- -1.0<throttle<=0.0 : motor stop, default value 0 - -1.0<throttle<=0.0 : motor stop, default value 0, set to -1 to use a place holder for subsequent motor rules
- -2.0<throttle<-1.0 : spin regardless of the radio's throttle position at speed `abs(throttle)-1` when Mixer Transition is activated. - -2.0<throttle<-1.0 : spin regardless of 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: 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:
@ -99,14 +48,13 @@ Example: This will spin motor number 5 (counting from 1) at 20%, in transition m
mmix 4 -1.200 0.000 0.000 0.000 mmix 4 -1.200 0.000 0.000 0.000
``` ```
### RC mode settings ## RC mode settings
It is recommend that the pilot uses a RC mode switch to activate modes or switch profiles. 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. Profile files Switching is not available until the runtime sensor calibration is done. Switching is NOT available when navigation mode is activate.
`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. `mixer_profile` 1 will be used as default, `mixer_profile` 2 will be used when the `MIXER PROFILE 2` mode box is activated.
Set `MIXER TRANSITION` accordingly when you want to use `MIXER TRANSITION` input for motors and servos. Here is sample of using these RC modes:
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) ![Alt text](Screenshots/mixer_profile.png)
@ -116,29 +64,50 @@ Set `MIXER TRANSITION` accordingly when you want to use `MIXER TRANSITION` input
It is also possible to set it as 4 state switch by adding FW(profile1) with transition on. It is also possible to set it as 4 state switch by adding FW(profile1) with transition on.
### Automated Transition ## 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. 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. `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.
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.
When `mixer_automated_switch`:`OFF` is set for all mixer_profiles(defaults). Model will not perform automated transition at all. When `mixer_automated_switch`:`OFF` is set for all mixer_profiles(defaults). Model will not perform automated transition at all.
## TailSitter (planned for INAV 7.1)
TailSitter is supported by add a 90deg offset to the board alignment. Set the board aliment normally in the mixer_profile for FW mode(`set platform_type = AIRPLANE`), The motor trust axis should be same direction as the airplane nose. Then, in the mixer_profile for takeoff and landing set `tailsitter_orientation_offset = ON ` to apply orientation offset. orientation offset will also add a 45deg orientation offset.
## Parameter list (Partial List)
#### Please be aware of what parameter is shared among FW/MC modes and what isn't.
### Shared Parameters
- **Timer Overrides**
- **Outputs [Servo]:**
- Servo min-point, mid-point, max-point settings
- **Motor Configuration:**
- motor_pwm_protocol
- motor_poles
- **Servo Configuration:**
- servo_protocol
- servo_pwm_rate
- **Board Alignment**
- ·······
### Profile-Specific Parameters in VTOL
- **Mixer Profile**
- **Mixer Configuration:**
- platform_type
- motor_stop_on_low
- tailsitter_orientation_offset
- motor_direction_inverted, and more·······
- **Motor Mixing (mmix)**
- **Servo Mixing (smix)**
- **PID Profile**
- PIDs for Roll, Pitch, Yaw
- PIDs for Navigation Modes
- TPA (Throttle PID Attenuation) Settings
- Rate Settings
- ·······
## Happy flying ## Happy flying
Remember that this is currently an emerging capability: Remember that this is currently an emerging capability:
* Test every thing on bench first. * Test every thing on bench first.
* Remove the props and try `MIXER PROFILE 2`, `MIXER TRANSITION` RC modes while arming. * Try MR or FW mode separately see if there are any problems.
* 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. * 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

@ -5,163 +5,190 @@ The On Screen Display, or OSD, is a feature that overlays flight data over the v
## Features and Limitations ## Features and Limitations
Not all OSDs are created equally. This table shows the differences between the different systems available. Not all OSDs are created equally. This table shows the differences between the different systems available.
| OSD System | Character grid | Character | Canvas | MSP DisplayPort | All elements supported | | OSD System | Character grid | Character | Canvas | MSP DisplayPort | All elements supported |
|---------------|-------------------|-----------|-----------|-------------------|---------------------------| |---------------|----------------|-----------|--------|-----------------|-------------------------|
| Analogue PAL | 30 x 16 | X | | | YES | | Analogue PAL | 30 x 16 | X | | | YES |
| Analogue NTSC | 30 x 13 | X | | | YES | | Analogue NTSC | 30 x 13 | X | | | YES |
| PixelOSD | As PAL or NTSC | | X | | YES | | PixelOSD | As PAL or NTSC | | X | | YES |
| DJI OSD | 30 x 16 | X | | | NO - BF Characters only | | DJI OSD | 30 x 16 | X | | | NO - BF Characters only |
| DJI WTFOS | 60 x 22 | X | | X | YES | | DJI WTFOS | 60 x 22 | X | | X | YES |
| HDZero | 50 x 18 | X | | X | YES | | HDZero | 50 x 18 | X | | X | YES |
| Avatar | 53 x 20 | X | | X | YES | | Avatar | 53 x 20 | X | | X | YES |
| DJI O3 | 53 x 20 (HD) | X | | X (partial) | NO - BF Characters only | | DJI O3 | 53 x 20 (HD) | X | | X (partial) | NO - BF Characters only |
## OSD Elements ## OSD Elements
Here are the OSD Elements provided by INAV. Here are the OSD Elements provided by INAV.
| ID | Element | Added | | ID | Element | Added |
|-------|-----------------------------------------------|-------| |-----|--------------------------------------------------|--------|
| 0 | OSD_RSSI_VALUE | 1.0.0 | | 0 | OSD_RSSI_VALUE | 1.0.0 |
| 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 | | 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 |
| 2 | OSD_CROSSHAIRS | 1.0.0 | | 2 | OSD_CROSSHAIRS | 1.0.0 |
| 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 | | 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 |
| 4 | OSD_HORIZON_SIDEBARS | 1.0.0 | | 4 | OSD_HORIZON_SIDEBARS | 1.0.0 |
| 5 | OSD_ONTIME | 1.0.0 | | 5 | OSD_ONTIME | 1.0.0 |
| 6 | OSD_FLYTIME | 1.0.0 | | 6 | OSD_FLYTIME | 1.0.0 |
| 7 | OSD_FLYMODE | 1.0.0 | | 7 | OSD_FLYMODE | 1.0.0 |
| 8 | OSD_CRAFT_NAME | 1.0.0 | | 8 | OSD_CRAFT_NAME | 1.0.0 |
| 9 | OSD_THROTTLE_POS | 1.0.0 | | 9 | OSD_THROTTLE_POS | 1.0.0 |
| 10 | OSD_VTX_CHANNEL | 1.0.0 | | 10 | OSD_VTX_CHANNEL | 1.0.0 |
| 11 | OSD_CURRENT_DRAW | 1.0.0 | | 11 | OSD_CURRENT_DRAW | 1.0.0 |
| 12 | OSD_MAH_DRAWN | 1.0.0 | | 12 | OSD_MAH_DRAWN | 1.0.0 |
| 13 | OSD_GPS_SPEED | 1.0.0 | | 13 | OSD_GPS_SPEED | 1.0.0 |
| 14 | OSD_GPS_SATS | 1.0.0 | | 14 | OSD_GPS_SATS | 1.0.0 |
| 15 | OSD_ALTITUDE | 1.0.0 | | 15 | OSD_ALTITUDE | 1.0.0 |
| 16 | OSD_ROLL_PIDS | 1.6.0 | | 16 | OSD_ROLL_PIDS | 1.6.0 |
| 17 | OSD_PITCH_PIDS | 1.6.0 | | 17 | OSD_PITCH_PIDS | 1.6.0 |
| 18 | OSD_YAW_PIDS | 1.6.0 | | 18 | OSD_YAW_PIDS | 1.6.0 |
| 19 | OSD_POWER | 1.6.0 | | 19 | OSD_POWER | 1.6.0 |
| 20 | OSD_GPS_LON | 1.6.0 | | 20 | OSD_GPS_LON | 1.6.0 |
| 21 | OSD_GPS_LAT | 1.6.0 | | 21 | OSD_GPS_LAT | 1.6.0 |
| 22 | OSD_HOME_DIR | 1.6.0 | | 22 | OSD_HOME_DIR | 1.6.0 |
| 23 | OSD_HOME_DIST | 1.6.0 | | 23 | OSD_HOME_DIST | 1.6.0 |
| 24 | OSD_HEADING | 1.6.0 | | 24 | OSD_HEADING | 1.6.0 |
| 25 | OSD_VARIO | 1.6.0 | | 25 | OSD_VARIO | 1.6.0 |
| 26 | OSD_VARIO_NUM | 1.6.0 | | 26 | OSD_VARIO_NUM | 1.6.0 |
| 27 | OSD_AIR_SPEED | 1.7.3 | | 27 | OSD_AIR_SPEED | 1.7.3 |
| 28 | OSD_ONTIME_FLYTIME | 1.8.0 | | 28 | OSD_ONTIME_FLYTIME | 1.8.0 |
| 29 | OSD_RTC_TIME | 1.8.0 | | 29 | OSD_RTC_TIME | 1.8.0 |
| 30 | OSD_MESSAGES | 1.8.0 | | 30 | OSD_MESSAGES | 1.8.0 |
| 31 | OSD_GPS_HDOP | 1.8.0 | | 31 | OSD_GPS_HDOP | 1.8.0 |
| 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 | | 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 |
| 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 | | 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 |
| 34 | OSD_HEADING_GRAPH | 1.8.0 | | 34 | OSD_HEADING_GRAPH | 1.8.0 |
| 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 | | 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 |
| 36 | OSD_WH_DRAWN | 1.9.0 | | 36 | OSD_WH_DRAWN | 1.9.0 |
| 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 | | 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 |
| 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 | | 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 |
| 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 | | 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 |
| 40 | OSD_TRIP_DIST | 1.9.1 | | 40 | OSD_TRIP_DIST | 1.9.1 |
| 41 | OSD_ATTITUDE_PITCH | 2.0.0 | | 41 | OSD_ATTITUDE_PITCH | 2.0.0 |
| 42 | OSD_ATTITUDE_ROLL | 2.0.0 | | 42 | OSD_ATTITUDE_ROLL | 2.0.0 |
| 43 | OSD_MAP_NORTH | 2.0.0 | | 43 | OSD_MAP_NORTH | 2.0.0 |
| 44 | OSD_MAP_TAKEOFF | 2.0.0 | | 44 | OSD_MAP_TAKEOFF | 2.0.0 |
| 45 | OSD_RADAR | 2.0.0 | | 45 | OSD_RADAR | 2.0.0 |
| 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 | | 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 |
| 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 | | 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 |
| 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 | | 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 |
| 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 | | 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 |
| 50 | OSD_HOME_HEADING_ERROR | 2.0.0 | | 50 | OSD_HOME_HEADING_ERROR | 2.0.0 |
| 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 | | 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 |
| 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 | | 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 |
| 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 | | 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 |
| 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 | | 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 |
| 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 | | 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 |
| 56 | OSD_LEVEL_PIDS | 2.0.0 | | 56 | OSD_LEVEL_PIDS | 2.0.0 |
| 57 | OSD_POS_XY_PIDS | 2.0.0 | | 57 | OSD_POS_XY_PIDS | 2.0.0 |
| 58 | OSD_POS_Z_PIDS | 2.0.0 | | 58 | OSD_POS_Z_PIDS | 2.0.0 |
| 59 | OSD_VEL_XY_PIDS | 2.0.0 | | 59 | OSD_VEL_XY_PIDS | 2.0.0 |
| 60 | OSD_VEL_Z_PIDS | 2.0.0 | | 60 | OSD_VEL_Z_PIDS | 2.0.0 |
| 61 | OSD_HEADING_P | 2.0.0 | | 61 | OSD_HEADING_P | 2.0.0 |
| 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 | | 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 |
| 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 | | 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 |
| 64 | OSD_RC_EXPO | 2.0.0 | | 64 | OSD_RC_EXPO | 2.0.0 |
| 65 | OSD_RC_YAW_EXPO | 2.0.0 | | 65 | OSD_RC_YAW_EXPO | 2.0.0 |
| 66 | OSD_THROTTLE_EXPO | 2.0.0 | | 66 | OSD_THROTTLE_EXPO | 2.0.0 |
| 67 | OSD_PITCH_RATE | 2.0.0 | | 67 | OSD_PITCH_RATE | 2.0.0 |
| 68 | OSD_ROLL_RATE | 2.0.0 | | 68 | OSD_ROLL_RATE | 2.0.0 |
| 69 | OSD_YAW_RATE | 2.0.0 | | 69 | OSD_YAW_RATE | 2.0.0 |
| 70 | OSD_MANUAL_RC_EXPO | 2.0.0 | | 70 | OSD_MANUAL_RC_EXPO | 2.0.0 |
| 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 | | 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 |
| 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 | | 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 |
| 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 | | 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 |
| 74 | OSD_MANUAL_YAW_RATE | 2.0.0 | | 74 | OSD_MANUAL_YAW_RATE | 2.0.0 |
| 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 | | 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 |
| 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 | | 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 |
| 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 | | 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 |
| 78 | OSD_DEBUG | 2.0.0 | | 78 | OSD_DEBUG | 2.0.0 |
| 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 | | 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 |
| 80 | OSD_FW_POS_PID_OUTPUTS | 2.0.0 | | 80 | OSD_FW_POS_PID_OUTPUTS | 2.0.0 |
| 81 | OSD_MC_VEL_X_PID_OUTPUTS | 2.0.0 | | 81 | OSD_MC_VEL_X_PID_OUTPUTS | 2.0.0 |
| 82 | OSD_MC_VEL_Y_PID_OUTPUTS | 2.0.0 | | 82 | OSD_MC_VEL_Y_PID_OUTPUTS | 2.0.0 |
| 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 | | 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 |
| 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 | | 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 |
| 85 | OSD_3D_SPEED | 2.1.0 | | 85 | OSD_3D_SPEED | 2.1.0 |
| 86 | OSD_IMU_TEMPERATURE | 2.1.0 | | 86 | OSD_IMU_TEMPERATURE | 2.1.0 |
| 87 | OSD_BARO_TEMPERATURE | 2.1.0 | | 87 | OSD_BARO_TEMPERATURE | 2.1.0 |
| 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 | | 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 |
| 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 | | 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 |
| 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 | | 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 |
| 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 | | 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 |
| 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 | | 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 |
| 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 | | 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 |
| 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 | | 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 |
| 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 | | 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 |
| 96 | OSD_ALTITUDE_MSL | 2.1.0 | | 96 | OSD_ALTITUDE_MSL | 2.1.0 |
| 97 | OSD_PLUS_CODE | 2.1.0 | | 97 | OSD_PLUS_CODE | 2.1.0 |
| 98 | OSD_MAP_SCALE | 2.2.0 | | 98 | OSD_MAP_SCALE | 2.2.0 |
| 99 | OSD_MAP_REFERENCE | 2.2.0 | | 99 | OSD_MAP_REFERENCE | 2.2.0 |
| 100 | OSD_GFORCE | 2.2.0 | | 100 | OSD_GFORCE | 2.2.0 |
| 101 | OSD_GFORCE_X | 2.2.0 | | 101 | OSD_GFORCE_X | 2.2.0 |
| 102 | OSD_GFORCE_Y | 2.2.0 | | 102 | OSD_GFORCE_Y | 2.2.0 |
| 103 | OSD_GFORCE_Z | 2.2.0 | | 103 | OSD_GFORCE_Z | 2.2.0 |
| 104 | OSD_RC_SOURCE | 2.2.0 | | 104 | OSD_RC_SOURCE | 2.2.0 |
| 105 | OSD_VTX_POWER | 2.2.0 | | 105 | OSD_VTX_POWER | 2.2.0 |
| 106 | OSD_ESC_RPM | 2.3.0 | | 106 | OSD_ESC_RPM | 2.3.0 |
| 107 | OSD_ESC_TEMPERATURE | 2.5.0 | | 107 | OSD_ESC_TEMPERATURE | 2.5.0 |
| 108 | OSD_AZIMUTH | 2.6.0 | | 108 | OSD_AZIMUTH | 2.6.0 |
| 109 | OSD_CRSF_RSSI_DBM | 2.6.0 | | 109 | OSD_CRSF_RSSI_DBM | 2.6.0 |
| 110 | OSD_CRSF_LQ | 2.6.0 | | 110 | OSD_CRSF_LQ | 2.6.0 |
| 111 | OSD_CRSF_SNR_DB | 2.6.0 | | 111 | OSD_CRSF_SNR_DB | 2.6.0 |
| 112 | OSD_CRSF_TX_POWER | 2.6.0 | | 112 | OSD_CRSF_TX_POWER | 2.6.0 |
| 113 | OSD_GVAR_0 | 2.6.0 | | 113 | OSD_GVAR_0 | 2.6.0 |
| 114 | OSD_GVAR_1 | 2.6.0 | | 114 | OSD_GVAR_1 | 2.6.0 |
| 115 | OSD_GVAR_2 | 2.6.0 | | 115 | OSD_GVAR_2 | 2.6.0 |
| 116 | OSD_GVAR_3 | 2.6.0 | | 116 | OSD_GVAR_3 | 2.6.0 |
| 117 | OSD_TPA | 2.6.0 | | 117 | OSD_TPA | 2.6.0 |
| 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 | | 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 |
| 119 | OSD_VERSION | 3.0.0 | | 119 | OSD_VERSION | 3.0.0 |
| 120 | OSD_RANGEFINDER | 3.0.0 | | 120 | OSD_RANGEFINDER | 3.0.0 |
| 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 | | 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 |
| 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 | | 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 |
| 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 | | 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 |
| 124 | OSD_GLIDESLOPE | 3.0.1 | | 124 | OSD_GLIDESLOPE | 3.0.1 |
| 125 | OSD_GPS_MAX_SPEED | 4.0.0 | | 125 | OSD_GPS_MAX_SPEED | 4.0.0 |
| 126 | OSD_3D_MAX_SPEED | 4.0.0 | | 126 | OSD_3D_MAX_SPEED | 4.0.0 |
| 127 | OSD_AIR_MAX_SPEED | 4.0.0 | | 127 | OSD_AIR_MAX_SPEED | 4.0.0 |
| 128 | OSD_ACTIVE_PROFILE | 4.0.0 | | 128 | OSD_ACTIVE_PROFILE | 4.0.0 |
| 129 | OSD_MISSION | 4.0.0 | | 129 | OSD_MISSION | 4.0.0 |
| 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 | | 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 |
| 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 | | 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 |
| 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 | | 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 |
| 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 | | 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 |
| 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 | | 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 |
| 135 | OSD_FW_LEVEL_TRIM | 5.0.0 | | 135 | OSD_FW_LEVEL_TRIM | 5.0.0 |
| 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 | | 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 |
| 137 | OSD_GLIDE_RANGE | 6.0.0 | | 137 | OSD_GLIDE_RANGE | 6.0.0 |
| 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 | | 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 |
| 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 | | 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 |
| 140 | OSD_GROUND_COURSE | 6.0.0 | | 140 | OSD_GROUND_COURSE | 6.0.0 |
| 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 | | 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 |
| 142 | OSD_PILOT_NAME | 6.0.0 | | 142 | OSD_PILOT_NAME | 6.0.0 |
| 143 | OSD_PAN_SERVO_CENTRED | 6.0.0 | | 143 | OSD_PAN_SERVO_CENTRED | 6.0.0 |
| 144 | OSD_MULTI_FUNCTION | 7.0.0 |
| 145 | OSD_ODOMETER | 7.0.0 |
| 146 | OSD_PILOT_LOGO | 7.0.0 |
# Pilot Logos
From INAV 7.0.0, pilots can add their own logos to the OSD. These can appear in 2 places: the power on/arming screens or as an element on the standard OSD. Please note that the power on/arming screen large pilot logos are only available on HD systems.
To use the pilot logos, you will need to make a custom font for your OSD system. Base fonts and information can be found in the [OSD folder](https://github.com/iNavFlight/inav-configurator/tree/master/resources/osd) in the Configurator resources. Each system will need a specific method to create the font image files. So they will not be covered here. There are two pilot logos.
<img alt="Default small INAV Pilot logo" src="https://github.com/iNavFlight/inav-configurator/raw/master/resources/osd/digital/default/24x36/469_471.png" align="right" />The small pilot logo appears on standard OSD layouts, when you add the elemement to the OSD screen. This is a 3 character wide symbol (characters 469-471).
<img alt="Default large INAV Pilot logo" src="https://github.com/iNavFlight/inav-configurator/raw/master/resources/osd/digital/default/24x36/472_511.png" align="right" />The large pilot logo appears on the power on and arming screens, when you enable the feature in the CLI. To do this, set the `osd_use_pilot_logo` parameter to `on`. This is a 10 character wide, 4 character high symbol (characters 472-511).
## Settings
* `osd_arm_screen_display_time` The amount of time the arming screen is displayed.
* `osd_inav_to_pilot_logo_spacing` The spacing between two logos. This can be set to `0`, so the original INAV logo and Pilot Logo can be combined in to a larger logo. Any non-0 value will be adjusted to best align the logos. For example, the Avatar system has an odd number of columns. If you set the spacing to 8, the logos would look misaligned. So the even number will be changed to an odd number for better alignment.
* `osd_use_pilot_logo` Enable to use the large pilot logo.
## Examples
This is an example of the arming screen with the pilot logo enabled. This is using the default settings.
![Arming screen example using default settings with osd_use_pilot_logo set to on](https://user-images.githubusercontent.com/17590174/271817487-eb18da4d-0911-44b2-b670-ea5940f79176.png)
This is an example of setting the `osd_inav_to_pilot_logo_spacing` to 0. This will allow a larger, single logo.
![Power on screen example with 0 spacing between logos](https://user-images.githubusercontent.com/17590174/271817352-6206402c-9da4-4682-9d83-790cc2396b00.png)

View file

@ -83,7 +83,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
| 35 | Trigonometry: Tangent | Computes TAN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` | | 35 | Trigonometry: Tangent | Computes TAN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` |
| 36 | MAP_INPUT | Scales `Operand A` from [`0` : `Operand B`] to [`0` : `1000`]. Note: input will be constrained and then scaled | | 36 | MAP_INPUT | Scales `Operand A` from [`0` : `Operand B`] to [`0` : `1000`]. Note: input will be constrained and then scaled |
| 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled | | 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled |
| 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B` | | 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B`. Note operand A should normally be set as a "Value", NOT as "Get RC Channel"|
| 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. | | 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. |
| 40 | Modulo | Modulo. Divide `Operand A` by `Operand B` and returns the remainder | | 40 | Modulo | Modulo. Divide `Operand A` by `Operand B` and returns the remainder |
| 41 | LOITER_RADIUS_OVERRIDE | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. If the value is lower than the loiter radius set in the **Advanced Tuning**, that will be used. | | 41 | LOITER_RADIUS_OVERRIDE | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. If the value is lower than the loiter radius set in the **Advanced Tuning**, that will be used. |

Binary file not shown.

After

Width:  |  Height:  |  Size: 21 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 24 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 314 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 19 KiB

236
docs/VTOL.md Normal file
View file

@ -0,0 +1,236 @@
# Welcome to INAV VTOL
Thank you for trying the INAV VTOL. Read every line in this tutorial. Your patience can save both time and potential repair costs for the model.
## Who Should Use This Tutorial?
This tutorial is designed for individuals who
- have prior experience with **both INAV multi-rotor and INAV fixed-wing configurations/operations.**
- know how to create a custom mixer for their model.
- know basic physics of vtol operation
## Firmware Status
The firmware is in a flyable state, but it hasn't undergone extensive testing yet. This means there may be potential issues that have not yet been discovered.
## Future Changes
Please be aware that both the setup procedure and firmware may change in response to user feedback and testing results.
## Your Feedback Matters
We highly value your feedback as it plays a crucial role in the development and refinement of INAV VTOL capabilities. Please share your experiences, suggestions, and any issues you encounter during testing. Your insights are invaluable in making INAV VTOL better for everyone.
# VTOL Configuration Steps
### The VTOL functionality is achieved by switching/transitioning between two configurations stored in the FC. VTOL specific configurations are Mixer Profiles with associated PID profiles. One profile set is for fixed-wing(FW) mode, One is for multi-copter(MC) mode. Configuration/Settings other than Mixer/PID profiles are shared among two modes
![Alt text](Screenshots/mixerprofile_flow.png)
0. **Find a DIFF ALL file for your model and start from there if possible**
- Be aware that `MIXER PROFILE 2` RC mode setting introduced by diff file can get your stuck in a mixer_profile. remove or change channel to proceed
1. **Setup Profile 1:**
- Configure it as a normal fixed-wing/multi-copter.
2. **Setup Profile 2:**
- Configure it as a normal multi-copter/fixed-wing.
3. **Mode Tab Settings:**
- Set up switching in the mode tab.
4. *(Recommended)* **Transition Mixing (Multi-Rotor Profile):**
- Configure transition mixing to gain airspeed in the multi-rotor profile.
5. *(Optional)* **Automated Switching (RTH):**
- Optionally, set up automated switching in case of failsafe.
# STEP0: Load parameter preset/templates
Find a working diff file if you can and start from there. If not, select keep current settings and apply following parameter in cli but read description about which one to apply.
```
set small_angle = 180
set gyro_main_lpf_hz = 80
set dynamic_gyro_notch_min_hz = 50
set dynamic_gyro_notch_mode = 3D
set motor_pwm_protocol = DSHOT300 #Try dshot first and see if it works
set airmode_type = STICK_CENTER_ONCE
set nav_disarm_on_landing = OFF #band-aid for false landing detection in NAV landing of multi-copter
set nav_rth_allow_landing = FS_ONLY
set nav_wp_max_safe_distance = 500
set nav_fw_control_smoothness = 2
set nav_fw_launch_max_altitude = 5000
set servo_pwm_rate = 160 #If model using servo for stabilization in MC mode and servo can tolerate it
set servo_lpf_hz = 30 #If model using servo for stabilization in MC mode
## profile 1 as airplane and profile 2 as multi rotor
mixer_profile 1
set platform_type = AIRPLANE
set model_preview_type = 26
set motorstop_on_low = ON
set mixer_pid_profile_linking = ON
mixer_profile 2
set platform_type = TRICOPTER
set model_preview_type = 1
set mixer_pid_profile_linking = ON
profile 1 #pid profile
set dterm_lpf_hz = 10
set d_boost_min = 1.000
set d_boost_max = 1.000
set fw_level_pitch_trim = 5.000
set roll_rate = 18
set pitch_rate = 9
set yaw_rate = 3
set fw_turn_assist_pitch_gain = 0.4
set max_angle_inclination_rll = 450
set fw_ff_pitch = 80
set fw_ff_roll = 50
set fw_p_pitch = 15
set fw_p_roll = 15
profile 2
set dterm_lpf_hz = 60
set dterm_lpf_type = PT3
set d_boost_min = 0.800
set d_boost_max = 1.200
set d_boost_gyro_delta_lpf_hz = 60
set antigravity_gain = 2.000
set antigravity_accelerator = 5.000
set smith_predictor_delay = 1.500
set tpa_rate = 20
set tpa_breakpoint = 1200
set tpa_on_yaw = ON #If model using control surface/tilt mechanism for stabilization in MC mode
set roll_rate = 18
set pitch_rate = 18
set yaw_rate = 9
set mc_iterm_relax = RPY
save
```
# STEP1&2: Configuring as a Normal fixed-wing/Multi-Copter in two profiles separately
1. **Select the fisrt Mixer Profile and PID Profile:**
- In the CLI, switch to the mixer_profile and pid_profile you wish to set first. You can also switch mixer_profile/pid_profile through gui if with aforementioned presets loaded.
```
mixer_profile 1 #in this example, we set profile 1 first
set mixer_pid_profile_linking = ON # Let the mixer_profile handle the pid_profile switch on this mixer_profile
set platform_type = AIRPLANE
save
```
2. **Configure the fixed-wing/Multi-Copter:**
- Configure your fixed-wing/Multi-Copter as you normally would, or you can copy and paste default settings to expedite the process.
- Dshot esc protocol availability might be limited depends on outputs and fc board you are using. change the motor wiring or use oneshot/multishot esc protocol and calibrate throttle range.
- You can use throttle = -1 as a placeholder for the motor you wish to stop if the motor isn't the last motor
- Consider conducting a test flight to ensure that everything operates as expected. And tune the settings, trim the servos.
![Alt text](Screenshots/mixerprofile_fw_mixer.png)
3. **Switch to Another Mixer Profile with PID Profile:**
- In the CLI, switch to another mixer_profile along with the appropriate pid_profile. You can also switch mixer_profile/pid_profile through gui if with aforementioned presets loaded.
```
mixer_profile 2
set mixer_pid_profile_linking = ON
set platform_type = MULTIROTOR/TRICOPTER
save
```
4. **Configure the Multi-Copter/fixed-wing:**
- Set up your multi-copter/fixed-wing as usual, this time for mixer_profile 2 and pid_profile 2.
- Utilize the 'MAX' input in the servo mixer to tilt the motors without altering the servo midpoint.
- At this stage, focus on configuring profile-specific settings. You can streamline this process by copying and pasting the default PID settings.
- you can set -1 in motor mixer throttle as a place holder: disable that motor but will load following motor rules
- compass is required to enable navigation modes for multi-rotor profile.
- Consider conducting a test flight to ensure that everything operates as expected. And tune the settings.
- It is advisable to have a certain degree of control surface (elevon / elevator) mapping for stabilization even in multi-copter mode. This helps improve control authority when airspeed is high. It might be unable to recover from a dive without them.
![Alt text](Screenshots/mixerprofile_mc_mixer.png)
5. **Tailsitters:planned for INAV 7.1**
- Configure the fixed-wing mode/profile sets normally. Use MultiCopter platform type for tail_sitting flying mode/profile sets.
- The baseline board aliment is FW mode(ROLL axis is the trust axis). So set `tailsitter_orientation_offset = ON ` in the tail_sitting MC mode.
- Configure mixer ROLL/YAW mixing according to tail_sitting orientation in the tail_sitting MC mode. YAW axis is the trust axis.
- Conduct a bench test and see the orientation of the model changes in inav-configurator setup tab
# STEP3: Mode Tab Settings:
### We recommend using an 3-pos switch on you radio to activate these modes, So pilot can jump in or bell out at any moment.
### Here is a example, in the bottom of inav-configurator Modes tab:
![Alt text](Screenshots/mixer_profile.png)
| 1000~1300 | 1300~1700 | 1700~2000 |
| :-- | :-- | :-- |
| Profile1(FW) with transition off | Profile2(MC) with transition on | Profile2(MC) with transition off |
- Profile file switching becomes available after completing the runtime sensor calibration(15-30s after booting). And It is **not available** when a navigation mode or position hold is active.
- By default, `mixer_profile 1` is used. `mixer_profile 2` is used when the `MIXER PROFILE 2` mode is activate. Once configured successfully, you will notice that the profiles and model preview changes accordingly when you refresh the relevant INAV Configurator tabs.
- Use the `MIXER TRANSITION` mode to gain airspeed in MC profile, set `MIXER TRANSITION` accordingly.
Conduct a bench test on the model (without props attached). The model can now switch between fixed-wing and multi-copter modes while armed. Furthermore, it is capable of mid-air switching, resulting in an immediate stall upon entering fixed-wing profile
# STEP4: Transition Mixing (Multi-Rotor Profile)(Recommended)
### Transition Mixing is typically useful in multi-copter profile to gain airspeed in prior to entering the fixed-wing profile. When the `MIXER TRANSITION` mode is activated, the associated motor or servo will move according to your configured Transition Mixing.
Please note that transition input is disabled when a navigation mode is activated. The use of Transition Mixing is necessary to enable additional features such as VTOL RTH with out stalling.
## Servo 'Transition Mixing': Tilting rotor configuration.
Add new servo mixer rules, and select 'Mixer Transition' in input. Set the weight/rate according to your desired angle. This will allow tilting the motor for tilting rotor model.
![Alt text](Screenshots/mixerprofile_servo_transition_mix.png)
## Motor 'Transition Mixing': Dedicated forward motor configuration
In motor mixer set:
- -2.0 < throttle < -1.0: The motor will spin regardless of the radio's throttle position at a speed of `abs(throttle) - 1` multiplied by throttle range only when Mixer Transition is activated.
![Alt text](Screenshots/mixerprofile_4puls1_mix.png)
## TailSitter 'Transition Mixing':
No additional settings needed, 45deg off set will be added to target pitch angle for angle mode in the firmware.
### With aforementioned settings, your model should be able to enter fixed-wing profile without stalling.
# Automated Switching (RTH) (Optional):
### This is one of the least tested features. This feature is primarily designed for Return to Home (RTH) in the event of a failsafe.
When configured correctly, the model will use the Fixed-Wing (FW) mode to efficiently return home and then transition to Multi-Copter (MC) mode for easier landing.
To enable this feature, type following command in cli
1. In your MC mode mixer profile (e.g., mixer_profile 2), set `mixer_automated_switch` to `ON`. leave it to `OFF` if burning remaining battery capacity on the way home is acceptable.
```
mixer_profile 2or1
set mixer_automated_switch= ON
```
2. Set `mixer_switch_trans_timer` ds in cli in the MC mode mixer profile to specify the time required for your model to gain sufficient airspeed before transitioning to FW mode.
```
mixer_profile 2or1
set mixer_switch_trans_timer = 30 # 3s, 3000ms
```
3. In your FW mode mixer profile (e.g., mixer_profile 1), also set `mixer_automated_switch` to `ON`. leave it to `OFF` if automated landing in fixed-wing is acceptable.
```
mixer_profile 1or2
set mixer_automated_switch = ON
```
4. Save your settings. type `save` in cli.
If you set `mixer_automated_switch` to `OFF` for all mixer profiles (the default setting), the model will not perform automated transitions. You can always enable navigation modes after performing a manual transition.
# Notes and Experiences
## General
- VTOL model operating in multi-copter (MC) mode may encounter challenges in windy conditions. Please exercise caution when testing in such conditions.
- Make sure you can recover from a complete stall before trying the mid air transition
- It will be much safer if you can understand every line in diff all, read your diff all before maiden
## Tilting-rotor
- In some tilting motor models, you may experience roll/yaw coupled oscillations when `MIXER TRANSITION` is activated. To address this issue, you can try the following:
1. Use prop blade meets at top/rear prop direction for tilting motors to balance the effects of torque and P-factor.
2. In addition to 1. Add a little yaw mixing(about 0.2) in tilt motors.
- 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. Use the max speed or faster speed in tiling servo to reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect.
## Dedicated forward motor
- Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight

View file

@ -36,7 +36,9 @@ To run `cmake` in the latest version you will need to update from Ubuntu `18_04
Mount MS windows C drive and clone INAV Mount MS windows C drive and clone INAV
1. `cd /mnt/c` 1. `cd /mnt/c`
1. `git clone https://github.com/iNavFlight/inav.git` 2. `git clone https://github.com/iNavFlight/inav.git`
3. `git checkout 6.1.1` (to switch to a specific release tag, for this example INAV version 6.1.1)
4. `git checkout -b my-branch` (to create own branch)
You are ready! You are ready!
You now have a folder called inav in the root of C drive that you can edit in windows You now have a folder called inav in the root of C drive that you can edit in windows

127
src/main/fc/fc_core.c Executable file → Normal file
View file

@ -548,7 +548,7 @@ void tryArm(void)
if (STATE(MULTIROTOR) && turtleIsActive && !FLIGHT_MODE(TURTLE_MODE) && emergencyArmingCanOverrideArmingDisabled() && isMotorProtocolDshot()) { if (STATE(MULTIROTOR) && turtleIsActive && !FLIGHT_MODE(TURTLE_MODE) && emergencyArmingCanOverrideArmingDisabled() && isMotorProtocolDshot()) {
sendDShotCommand(DSHOT_CMD_SPIN_DIRECTION_REVERSED); sendDShotCommand(DSHOT_CMD_SPIN_DIRECTION_REVERSED);
ENABLE_ARMING_FLAG(ARMED); ENABLE_ARMING_FLAG(ARMED);
enableFlightMode(TURTLE_MODE); ENABLE_FLIGHT_MODE(TURTLE_MODE);
return; return;
} }
#endif #endif
@ -678,28 +678,21 @@ void processRx(timeUs_t currentTimeUs)
// Angle mode forced on briefly after emergency inflight rearm to help stabilise attitude (currently limited to MR) // Angle mode forced on briefly after emergency inflight rearm to help stabilise attitude (currently limited to MR)
bool emergRearmAngleEnforce = STATE(MULTIROTOR) && emergRearmStabiliseTimeout > US2MS(currentTimeUs); bool emergRearmAngleEnforce = STATE(MULTIROTOR) && emergRearmStabiliseTimeout > US2MS(currentTimeUs);
bool autoEnableAngle = failsafeRequiresAngleMode() || navigationRequiresAngleMode() || emergRearmAngleEnforce; bool autoEnableAngle = failsafeRequiresAngleMode() || navigationRequiresAngleMode() || emergRearmAngleEnforce;
bool canUseHorizonMode = true;
if (sensors(SENSOR_ACC) && (IS_RC_MODE_ACTIVE(BOXANGLE) || autoEnableAngle)) { /* Disable stabilised modes initially, will be enabled as required with priority ANGLE > HORIZON > ANGLEHOLD
// bumpless transfer to Level mode * MANUAL mode has priority over these modes except when ANGLE auto enabled */
canUseHorizonMode = false; DISABLE_FLIGHT_MODE(ANGLE_MODE);
DISABLE_FLIGHT_MODE(HORIZON_MODE);
DISABLE_FLIGHT_MODE(ANGLEHOLD_MODE);
if (!FLIGHT_MODE(ANGLE_MODE)) { if (sensors(SENSOR_ACC) && (!FLIGHT_MODE(MANUAL_MODE) || autoEnableAngle)) {
if (IS_RC_MODE_ACTIVE(BOXANGLE) || autoEnableAngle) {
ENABLE_FLIGHT_MODE(ANGLE_MODE); ENABLE_FLIGHT_MODE(ANGLE_MODE);
} } else if (IS_RC_MODE_ACTIVE(BOXHORIZON)) {
} else {
DISABLE_FLIGHT_MODE(ANGLE_MODE); // failsafe support
}
if (IS_RC_MODE_ACTIVE(BOXHORIZON) && canUseHorizonMode) {
DISABLE_FLIGHT_MODE(ANGLE_MODE);
if (!FLIGHT_MODE(HORIZON_MODE)) {
ENABLE_FLIGHT_MODE(HORIZON_MODE); ENABLE_FLIGHT_MODE(HORIZON_MODE);
} else if (STATE(AIRPLANE) && IS_RC_MODE_ACTIVE(BOXANGLEHOLD)) {
ENABLE_FLIGHT_MODE(ANGLEHOLD_MODE);
} }
} else {
DISABLE_FLIGHT_MODE(HORIZON_MODE);
} }
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
@ -710,18 +703,14 @@ void processRx(timeUs_t currentTimeUs)
/* Flaperon mode */ /* Flaperon mode */
if (IS_RC_MODE_ACTIVE(BOXFLAPERON) && STATE(FLAPERON_AVAILABLE)) { if (IS_RC_MODE_ACTIVE(BOXFLAPERON) && STATE(FLAPERON_AVAILABLE)) {
if (!FLIGHT_MODE(FLAPERON)) { ENABLE_FLIGHT_MODE(FLAPERON);
ENABLE_FLIGHT_MODE(FLAPERON);
}
} else { } else {
DISABLE_FLIGHT_MODE(FLAPERON); DISABLE_FLIGHT_MODE(FLAPERON);
} }
/* Turn assistant mode */ /* Turn assistant mode */
if (IS_RC_MODE_ACTIVE(BOXTURNASSIST)) { if (IS_RC_MODE_ACTIVE(BOXTURNASSIST)) {
if (!FLIGHT_MODE(TURN_ASSISTANT)) { ENABLE_FLIGHT_MODE(TURN_ASSISTANT);
ENABLE_FLIGHT_MODE(TURN_ASSISTANT);
}
} else { } else {
DISABLE_FLIGHT_MODE(TURN_ASSISTANT); DISABLE_FLIGHT_MODE(TURN_ASSISTANT);
} }
@ -740,9 +729,7 @@ void processRx(timeUs_t currentTimeUs)
#if defined(USE_MAG) #if defined(USE_MAG)
if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) { if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) {
if (IS_RC_MODE_ACTIVE(BOXHEADFREE) && STATE(MULTIROTOR)) { if (IS_RC_MODE_ACTIVE(BOXHEADFREE) && STATE(MULTIROTOR)) {
if (!FLIGHT_MODE(HEADFREE_MODE)) { ENABLE_FLIGHT_MODE(HEADFREE_MODE);
ENABLE_FLIGHT_MODE(HEADFREE_MODE);
}
} else { } else {
DISABLE_FLIGHT_MODE(HEADFREE_MODE); DISABLE_FLIGHT_MODE(HEADFREE_MODE);
} }
@ -760,7 +747,7 @@ void processRx(timeUs_t currentTimeUs)
} else { } else {
DISABLE_FLIGHT_MODE(MANUAL_MODE); DISABLE_FLIGHT_MODE(MANUAL_MODE);
} }
}else{ } else {
DISABLE_FLIGHT_MODE(MANUAL_MODE); DISABLE_FLIGHT_MODE(MANUAL_MODE);
} }
@ -781,52 +768,52 @@ void processRx(timeUs_t currentTimeUs)
} }
else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) {
if (throttleIsLow) { if (throttleIsLow) {
if (STATE(AIRMODE_ACTIVE)) { if (STATE(AIRMODE_ACTIVE)) {
if ((rollPitchStatus == CENTERED) || (ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY))) { if ((rollPitchStatus == CENTERED) || (ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY))) {
ENABLE_STATE(ANTI_WINDUP); ENABLE_STATE(ANTI_WINDUP);
} }
else { else {
DISABLE_STATE(ANTI_WINDUP); DISABLE_STATE(ANTI_WINDUP);
} }
} }
else { else {
DISABLE_STATE(ANTI_WINDUP); DISABLE_STATE(ANTI_WINDUP);
pidResetErrorAccumulators(); pidResetErrorAccumulators();
} }
} }
else { else {
DISABLE_STATE(ANTI_WINDUP); DISABLE_STATE(ANTI_WINDUP);
} }
} }
else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE) { else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE) {
if (throttleIsLow) { if (throttleIsLow) {
if (STATE(AIRMODE_ACTIVE)) { if (STATE(AIRMODE_ACTIVE)) {
if ((rollPitchStatus == CENTERED) && !STATE(ANTI_WINDUP_DEACTIVATED)) { if ((rollPitchStatus == CENTERED) && !STATE(ANTI_WINDUP_DEACTIVATED)) {
ENABLE_STATE(ANTI_WINDUP); ENABLE_STATE(ANTI_WINDUP);
} }
else { else {
DISABLE_STATE(ANTI_WINDUP); DISABLE_STATE(ANTI_WINDUP);
} }
} }
else { else {
DISABLE_STATE(ANTI_WINDUP); DISABLE_STATE(ANTI_WINDUP);
pidResetErrorAccumulators(); pidResetErrorAccumulators();
} }
} }
else { else {
DISABLE_STATE(ANTI_WINDUP); DISABLE_STATE(ANTI_WINDUP);
if (rollPitchStatus != CENTERED) { if (rollPitchStatus != CENTERED) {
ENABLE_STATE(ANTI_WINDUP_DEACTIVATED); ENABLE_STATE(ANTI_WINDUP_DEACTIVATED);
} }
} }
} }
else if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) { else if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) {
DISABLE_STATE(ANTI_WINDUP); DISABLE_STATE(ANTI_WINDUP);
//This case applies only to MR when Airmode management is throttle threshold activated //This case applies only to MR when Airmode management is throttle threshold activated
if (throttleIsLow && !STATE(AIRMODE_ACTIVE)) { if (throttleIsLow && !STATE(AIRMODE_ACTIVE)) {
pidResetErrorAccumulators(); pidResetErrorAccumulators();
} }
} }
//--------------------------------------------------------- //---------------------------------------------------------
if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) { if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) {
DISABLE_FLIGHT_MODE(HEADFREE_MODE); DISABLE_FLIGHT_MODE(HEADFREE_MODE);
@ -849,6 +836,8 @@ void processRx(timeUs_t currentTimeUs)
} }
} }
#endif #endif
// Sound a beeper if the flight mode state has changed
updateFlightModeChangeBeeper();
} }
// Function for loop trigger // Function for loop trigger

View file

@ -102,6 +102,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
{ .boxId = BOXMULTIFUNCTION, .boxName = "MULTI FUNCTION", .permanentId = 61 }, { .boxId = BOXMULTIFUNCTION, .boxName = "MULTI FUNCTION", .permanentId = 61 },
{ .boxId = BOXMIXERPROFILE, .boxName = "MIXER PROFILE 2", .permanentId = 62 }, { .boxId = BOXMIXERPROFILE, .boxName = "MIXER PROFILE 2", .permanentId = 62 },
{ .boxId = BOXMIXERTRANSITION, .boxName = "MIXER TRANSITION", .permanentId = 63 }, { .boxId = BOXMIXERTRANSITION, .boxName = "MIXER TRANSITION", .permanentId = 63 },
{ .boxId = BOXANGLEHOLD, .boxName = "ANGLE HOLD", .permanentId = 64 },
{ .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF } { .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF }
}; };
@ -259,7 +260,7 @@ void initActiveBoxIds(void)
ADD_ACTIVE_BOX(BOXNAVALTHOLD); ADD_ACTIVE_BOX(BOXNAVALTHOLD);
} }
if (STATE(AIRPLANE) || STATE(ROVER) || STATE(BOAT) || if (STATE(AIRPLANE) || STATE(ROVER) || STATE(BOAT) ||
platformTypeConfigured(PLATFORM_AIRPLANE) || platformTypeConfigured(PLATFORM_ROVER) || platformTypeConfigured(PLATFORM_BOAT)) { platformTypeConfigured(PLATFORM_AIRPLANE) || platformTypeConfigured(PLATFORM_ROVER) || platformTypeConfigured(PLATFORM_BOAT)) {
ADD_ACTIVE_BOX(BOXMANUAL); ADD_ACTIVE_BOX(BOXMANUAL);
} }
@ -279,6 +280,9 @@ void initActiveBoxIds(void)
if (sensors(SENSOR_BARO)) { if (sensors(SENSOR_BARO)) {
ADD_ACTIVE_BOX(BOXAUTOLEVEL); ADD_ACTIVE_BOX(BOXAUTOLEVEL);
} }
if (sensors(SENSOR_ACC)) {
ADD_ACTIVE_BOX(BOXANGLEHOLD);
}
} }
/* /*
@ -432,6 +436,7 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags)
CHECK_ACTIVE_BOX(IS_ENABLED(currentMixerProfileIndex), BOXMIXERPROFILE); CHECK_ACTIVE_BOX(IS_ENABLED(currentMixerProfileIndex), BOXMIXERPROFILE);
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION)), BOXMIXERTRANSITION); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION)), BOXMIXERTRANSITION);
#endif #endif
CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXANGLEHOLD)), BOXANGLEHOLD);
memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t)); memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t));
for (uint32_t i = 0; i < activeBoxIdCount; i++) { for (uint32_t i = 0; i < activeBoxIdCount; i++) {
if (activeBoxes[activeBoxIds[i]]) { if (activeBoxes[activeBoxIds[i]]) {

View file

@ -81,6 +81,7 @@ typedef enum {
BOXMULTIFUNCTION = 52, BOXMULTIFUNCTION = 52,
BOXMIXERPROFILE = 53, BOXMIXERPROFILE = 53,
BOXMIXERTRANSITION = 54, BOXMIXERTRANSITION = 54,
BOXANGLEHOLD = 55,
CHECKBOX_ITEM_COUNT CHECKBOX_ITEM_COUNT
} boxId_e; } boxId_e;

View file

@ -91,31 +91,16 @@ armingFlag_e isArmingDisabledReason(void)
} }
/** /**
* Enables the given flight mode. A beep is sounded if the flight mode * Called at Rx update rate. Beeper sounded if flight mode state has changed.
* has changed. Returns the new 'flightModeFlags' value.
*/ */
uint32_t enableFlightMode(flightModeFlags_e mask) void updateFlightModeChangeBeeper(void)
{ {
uint32_t oldVal = flightModeFlags; static uint32_t previousFlightModeFlags = 0;
flightModeFlags |= (mask); if (flightModeFlags != previousFlightModeFlags) {
if (flightModeFlags != oldVal)
beeperConfirmationBeeps(1); beeperConfirmationBeeps(1);
return flightModeFlags; }
} previousFlightModeFlags = flightModeFlags;
/**
* Disables the given flight mode. A beep is sounded if the flight mode
* has changed. Returns the new 'flightModeFlags' value.
*/
uint32_t disableFlightMode(flightModeFlags_e mask)
{
uint32_t oldVal = flightModeFlags;
flightModeFlags &= ~(mask);
if (flightModeFlags != oldVal)
beeperConfirmationBeeps(1);
return flightModeFlags;
} }
bool sensors(uint32_t mask) bool sensors(uint32_t mask)
@ -173,6 +158,8 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void)
if (FLIGHT_MODE(HORIZON_MODE)) if (FLIGHT_MODE(HORIZON_MODE))
return FLM_HORIZON; return FLM_HORIZON;
if (FLIGHT_MODE(ANGLEHOLD_MODE))
return FLM_ANGLEHOLD;
return STATE(AIRMODE_ACTIVE) ? FLM_ACRO_AIR : FLM_ACRO; return STATE(AIRMODE_ACTIVE) ? FLM_ACRO_AIR : FLM_ACRO;
} }

View file

@ -104,12 +104,13 @@ typedef enum {
TURN_ASSISTANT = (1 << 14), TURN_ASSISTANT = (1 << 14),
TURTLE_MODE = (1 << 15), TURTLE_MODE = (1 << 15),
SOARING_MODE = (1 << 16), SOARING_MODE = (1 << 16),
ANGLEHOLD_MODE = (1 << 17),
} flightModeFlags_e; } flightModeFlags_e;
extern uint32_t flightModeFlags; extern uint32_t flightModeFlags;
#define DISABLE_FLIGHT_MODE(mask) disableFlightMode(mask) #define DISABLE_FLIGHT_MODE(mask) (flightModeFlags &= ~(mask))
#define ENABLE_FLIGHT_MODE(mask) enableFlightMode(mask) #define ENABLE_FLIGHT_MODE(mask) (flightModeFlags |= (mask))
#define FLIGHT_MODE(mask) (flightModeFlags & (mask)) #define FLIGHT_MODE(mask) (flightModeFlags & (mask))
typedef enum { typedef enum {
@ -165,6 +166,7 @@ typedef enum {
FLM_CRUISE, FLM_CRUISE,
FLM_LAUNCH, FLM_LAUNCH,
FLM_FAILSAFE, FLM_FAILSAFE,
FLM_ANGLEHOLD,
FLM_COUNT FLM_COUNT
} flightModeForTelemetry_e; } flightModeForTelemetry_e;
@ -203,8 +205,7 @@ extern simulatorData_t simulatorData;
#endif #endif
uint32_t enableFlightMode(flightModeFlags_e mask); void updateFlightModeChangeBeeper(void);
uint32_t disableFlightMode(flightModeFlags_e mask);
bool sensors(uint32_t mask); bool sensors(uint32_t mask);
void sensorsSet(uint32_t mask); void sensorsSet(uint32_t mask);

View file

@ -192,7 +192,7 @@ tables:
enum: gpsBaudRate_e enum: gpsBaudRate_e
- name: nav_mc_althold_throttle - name: nav_mc_althold_throttle
values: ["STICK", "MID_STICK", "HOVER"] values: ["STICK", "MID_STICK", "HOVER"]
enum: navMcAltHoldThrottle_e enum: navMcAltHoldThrottle_e
- name: led_pin_pwm_mode - name: led_pin_pwm_mode
values: ["SHARED_LOW", "SHARED_HIGH", "LOW", "HIGH"] values: ["SHARED_LOW", "SHARED_HIGH", "LOW", "HIGH"]
enum: led_pin_pwm_mode_e enum: led_pin_pwm_mode_e
@ -1192,7 +1192,7 @@ groups:
min: 0 min: 0
max: 200 max: 200
- name: PG_REVERSIBLE_MOTORS_CONFIG - name: PG_REVERSIBLE_MOTORS_CONFIG
type: reversibleMotorsConfig_t type: reversibleMotorsConfig_t
@ -3598,7 +3598,7 @@ groups:
min: 1000 min: 1000
max: 5000 max: 5000
default_value: 1500 default_value: 1500
- name: osd_switch_indicator_zero_name - name: osd_switch_indicator_zero_name
description: "Character to use for OSD switch incicator 0." description: "Character to use for OSD switch incicator 0."
field: osd_switch_indicator0_name field: osd_switch_indicator0_name

View file

@ -159,6 +159,8 @@ typedef void (*pidControllerFnPtr)(pidState_t *pidState, flight_dynamics_index_t
static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn; static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn;
static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn;
static EXTENDED_FASTRAM bool levelingEnabled = false; static EXTENDED_FASTRAM bool levelingEnabled = false;
static EXTENDED_FASTRAM bool restartAngleHoldMode = true;
static EXTENDED_FASTRAM bool angleHoldIsLevel = false;
#define FIXED_WING_LEVEL_TRIM_MAX_ANGLE 10.0f // Max angle auto trimming can demand #define FIXED_WING_LEVEL_TRIM_MAX_ANGLE 10.0f // Max angle auto trimming can demand
#define FIXED_WING_LEVEL_TRIM_DIVIDER 50.0f #define FIXED_WING_LEVEL_TRIM_DIVIDER 50.0f
@ -838,7 +840,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT)
+ ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT);
if (pidProfile()->pidItermLimitPercent != 0){ if (pidProfile()->pidItermLimitPercent != 0){
float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f;
pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit);
@ -1064,9 +1066,62 @@ void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis
} }
bool isAngleHoldLevel(void)
{
return angleHoldIsLevel;
}
void updateAngleHold(float *angleTarget, uint8_t axis)
{
int8_t navAngleHoldAxis = navCheckActiveAngleHoldAxis();
if (!restartAngleHoldMode) { // set restart flag when anglehold is inactive
restartAngleHoldMode = !FLIGHT_MODE(ANGLEHOLD_MODE) && navAngleHoldAxis == -1;
}
if ((FLIGHT_MODE(ANGLEHOLD_MODE) || axis == navAngleHoldAxis) && !isFlightAxisAngleOverrideActive(axis)) {
/* angleHoldTarget stores attitude values using a zero datum when level.
* This requires angleHoldTarget pitch to be corrected for fixedWingLevelTrim so it is 0
* when the craft is level even though attitude pitch is non zero in this case.
* angleTarget pitch is corrected back to fixedWingLevelTrim datum on return from function */
static int16_t angleHoldTarget[2];
if (restartAngleHoldMode) { // set target attitude to current attitude on activation
angleHoldTarget[FD_ROLL] = attitude.raw[FD_ROLL];
angleHoldTarget[FD_PITCH] = attitude.raw[FD_PITCH] + DEGREES_TO_DECIDEGREES(fixedWingLevelTrim);
restartAngleHoldMode = false;
}
// set flag indicating anglehold is level
if (FLIGHT_MODE(ANGLEHOLD_MODE)) {
angleHoldIsLevel = angleHoldTarget[FD_ROLL] == 0 && angleHoldTarget[FD_PITCH] == 0;
} else {
angleHoldIsLevel = angleHoldTarget[navAngleHoldAxis] == 0;
}
uint16_t bankLimit = pidProfile()->max_angle_inclination[axis];
// use Nav bank angle limits if Nav active
if (navAngleHoldAxis == FD_ROLL) {
bankLimit = DEGREES_TO_DECIDEGREES(navConfig()->fw.max_bank_angle);
} else if (navAngleHoldAxis == FD_PITCH) {
bankLimit = DEGREES_TO_DECIDEGREES(navConfig()->fw.max_climb_angle);
}
int16_t levelTrim = axis == FD_PITCH ? DEGREES_TO_DECIDEGREES(fixedWingLevelTrim) : 0;
if (calculateRollPitchCenterStatus() == CENTERED) {
angleHoldTarget[axis] = ABS(angleHoldTarget[axis]) < 30 ? 0 : angleHoldTarget[axis]; // snap to level when within 3 degs of level
*angleTarget = constrain(angleHoldTarget[axis] - levelTrim, -bankLimit, bankLimit);
} else {
*angleTarget = constrain(attitude.raw[axis] + *angleTarget + levelTrim, -bankLimit, bankLimit);
angleHoldTarget[axis] = attitude.raw[axis] + levelTrim;
}
}
}
void FAST_CODE pidController(float dT) void FAST_CODE pidController(float dT)
{ {
const float dT_inv = 1.0f / dT; const float dT_inv = 1.0f / dT;
if (!pidFiltersConfigured) { if (!pidFiltersConfigured) {
@ -1115,21 +1170,30 @@ void FAST_CODE pidController(float dT)
#endif #endif
} }
// Step 3: Run control for ANGLE_MODE, HORIZON_MODE, and HEADING_LOCK // Step 3: Run control for ANGLE_MODE, HORIZON_MODE and ANGLEHOLD_MODE
const float horizonRateMagnitude = calcHorizonRateMagnitude(); const float horizonRateMagnitude = FLIGHT_MODE(HORIZON_MODE) ? calcHorizonRateMagnitude() : 0.0f;
levelingEnabled = false; levelingEnabled = false;
angleHoldIsLevel = false;
for (uint8_t axis = FD_ROLL; axis <= FD_PITCH; axis++) { for (uint8_t axis = FD_ROLL; axis <= FD_PITCH; axis++) {
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || isFlightAxisAngleOverrideActive(axis)) { if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || FLIGHT_MODE(ANGLEHOLD_MODE) || isFlightAxisAngleOverrideActive(axis)) {
//If axis angle override, get the correct angle from Logic Conditions // If axis angle override, get the correct angle from Logic Conditions
float angleTarget = getFlightAxisAngleOverride(axis, computePidLevelTarget(axis)); float angleTarget = getFlightAxisAngleOverride(axis, computePidLevelTarget(axis));
//Apply the Level PID controller if (STATE(AIRPLANE)) { // update anglehold mode
updateAngleHold(&angleTarget, axis);
}
// Apply the Level PID controller
pidLevel(angleTarget, &pidState[axis], axis, horizonRateMagnitude, dT); pidLevel(angleTarget, &pidState[axis], axis, horizonRateMagnitude, dT);
canUseFpvCameraMix = false; // FPVANGLEMIX is incompatible with ANGLE/HORIZON canUseFpvCameraMix = false; // FPVANGLEMIX is incompatible with ANGLE/HORIZON
levelingEnabled = true; levelingEnabled = true;
} else {
restartAngleHoldMode = true;
} }
} }
// Apply Turn Assistance
if ((FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance()) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) { if ((FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance()) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
float bankAngleTarget = DECIDEGREES_TO_RADIANS(pidRcCommandToAngle(rcCommand[FD_ROLL], pidProfile()->max_angle_inclination[FD_ROLL])); float bankAngleTarget = DECIDEGREES_TO_RADIANS(pidRcCommandToAngle(rcCommand[FD_ROLL], pidProfile()->max_angle_inclination[FD_ROLL]));
float pitchAngleTarget = DECIDEGREES_TO_RADIANS(pidRcCommandToAngle(rcCommand[FD_PITCH], pidProfile()->max_angle_inclination[FD_PITCH])); float pitchAngleTarget = DECIDEGREES_TO_RADIANS(pidRcCommandToAngle(rcCommand[FD_PITCH], pidProfile()->max_angle_inclination[FD_PITCH]));
@ -1137,6 +1201,7 @@ void FAST_CODE pidController(float dT)
canUseFpvCameraMix = false; // FPVANGLEMIX is incompatible with TURN_ASSISTANT canUseFpvCameraMix = false; // FPVANGLEMIX is incompatible with TURN_ASSISTANT
} }
// Apply FPV camera mix
if (canUseFpvCameraMix && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && currentControlRateProfile->misc.fpvCamAngleDegrees && STATE(MULTIROTOR)) { if (canUseFpvCameraMix && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && currentControlRateProfile->misc.fpvCamAngleDegrees && STATE(MULTIROTOR)) {
pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees); pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees);
} }
@ -1272,7 +1337,7 @@ bool isFixedWingLevelTrimActive(void)
return IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && !areSticksDeflected() && return IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && !areSticksDeflected() &&
(FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) &&
!FLIGHT_MODE(SOARING_MODE) && !FLIGHT_MODE(MANUAL_MODE) && !FLIGHT_MODE(SOARING_MODE) && !FLIGHT_MODE(MANUAL_MODE) &&
!navigationIsControllingAltitude(); !navigationIsControllingAltitude() && !(navCheckActiveAngleHoldAxis() == FD_PITCH && !angleHoldIsLevel);
} }
void updateFixedWingLevelTrim(timeUs_t currentTimeUs) void updateFixedWingLevelTrim(timeUs_t currentTimeUs)

View file

@ -220,3 +220,4 @@ pidType_e pidIndexGetType(pidIndex_e pidIndex);
bool isFixedWingLevelTrimActive(void); bool isFixedWingLevelTrimActive(void);
void updateFixedWingLevelTrim(timeUs_t currentTimeUs); void updateFixedWingLevelTrim(timeUs_t currentTimeUs);
float getFixedWingLevelTrim(void); float getFixedWingLevelTrim(void);
bool isAngleHoldLevel(void);

View file

@ -1734,7 +1734,7 @@ static bool osdDrawSingleElement(uint8_t item)
tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow packs below 100Ah tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow packs below 100Ah
buff[5] = SYM_MAH; buff[5] = SYM_MAH;
buff[6] = '\0'; buff[6] = '\0';
} else } else
#endif #endif
{ {
if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits, false)) { if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits, false)) {
@ -1776,7 +1776,7 @@ static bool osdDrawSingleElement(uint8_t item)
buff[5] = SYM_MAH; buff[5] = SYM_MAH;
buff[6] = '\0'; buff[6] = '\0';
unitsDrawn = true; unitsDrawn = true;
} else } else
#endif #endif
{ {
if (osdFormatCentiNumber(buff, getBatteryRemainingCapacity() * 100, 1000, 0, (mah_digits - 2), mah_digits, false)) { if (osdFormatCentiNumber(buff, getBatteryRemainingCapacity() * 100, 1000, 0, (mah_digits - 2), mah_digits, false)) {
@ -2276,7 +2276,7 @@ static bool osdDrawSingleElement(uint8_t item)
p = " WP "; p = " WP ";
else if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && navigationRequiresAngleMode()) { else if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && navigationRequiresAngleMode()) {
// If navigationRequiresAngleMode() returns false when ALTHOLD is active, // If navigationRequiresAngleMode() returns false when ALTHOLD is active,
// it means it can be combined with ANGLE, HORIZON, ACRO, etc... // it means it can be combined with ANGLE, HORIZON, ANGLEHOLD, ACRO, etc...
// and its display is handled by OSD_MESSAGES rather than OSD_FLYMODE. // and its display is handled by OSD_MESSAGES rather than OSD_FLYMODE.
p = " AH "; p = " AH ";
} }
@ -2284,6 +2284,8 @@ static bool osdDrawSingleElement(uint8_t item)
p = "ANGL"; p = "ANGL";
else if (FLIGHT_MODE(HORIZON_MODE)) else if (FLIGHT_MODE(HORIZON_MODE))
p = "HOR "; p = "HOR ";
else if (FLIGHT_MODE(ANGLEHOLD_MODE))
p = "ANGH";
displayWrite(osdDisplayPort, elemPosX, elemPosY, p); displayWrite(osdDisplayPort, elemPosX, elemPosY, p);
return true; return true;
@ -5194,10 +5196,9 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
} }
} else { } else {
if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) { if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) {
// ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO // ALTHOLD might be enabled alongside ANGLE/HORIZON/ANGLEHOLD/ACRO
// when it doesn't require ANGLE mode (required only in FW // when it doesn't require ANGLE mode (required only in FW
// right now). If if requires ANGLE, its display is handled // right now). If it requires ANGLE, its display is handled by OSD_FLYMODE.
// by OSD_FLYMODE.
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD); messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD);
} }
if (STATE(MULTIROTOR) && FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { if (STATE(MULTIROTOR) && FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) {
@ -5234,6 +5235,16 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
if (STATE(LANDING_DETECTED)) { if (STATE(LANDING_DETECTED)) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_LANDED); messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_LANDED);
} }
if (IS_RC_MODE_ACTIVE(BOXANGLEHOLD)) {
int8_t navAngleHoldAxis = navCheckActiveAngleHoldAxis();
if (isAngleHoldLevel()) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ANGLEHOLD_LEVEL);
} else if (navAngleHoldAxis == FD_ROLL) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ANGLEHOLD_ROLL);
} else if (navAngleHoldAxis == FD_PITCH) {
messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ANGLEHOLD_PITCH);
}
}
} }
} }
} else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) { } else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) {

View file

@ -118,6 +118,9 @@
#define OSD_MSG_UNABLE_ARM "UNABLE TO ARM" #define OSD_MSG_UNABLE_ARM "UNABLE TO ARM"
#define OSD_MSG_SAVING_SETTNGS "** SAVING SETTINGS **" #define OSD_MSG_SAVING_SETTNGS "** SAVING SETTINGS **"
#define OSD_MSG_SETTINGS_SAVED "** SETTINGS SAVED **" #define OSD_MSG_SETTINGS_SAVED "** SETTINGS SAVED **"
#define OSD_MSG_ANGLEHOLD_ROLL "(ANGLEHOLD ROLL)"
#define OSD_MSG_ANGLEHOLD_PITCH "(ANGLEHOLD PITCH)"
#define OSD_MSG_ANGLEHOLD_LEVEL "(ANGLEHOLD LEVEL)"
#ifdef USE_DEV_TOOLS #ifdef USE_DEV_TOOLS
#define OSD_MSG_GRD_TEST_MODE "GRD TEST > MOTORS DISABLED" #define OSD_MSG_GRD_TEST_MODE "GRD TEST > MOTORS DISABLED"
@ -413,7 +416,7 @@ typedef struct osdConfig_s {
#ifdef USE_WIND_ESTIMATOR #ifdef USE_WIND_ESTIMATOR
bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance
#endif #endif
uint8_t coordinate_digits; uint8_t coordinate_digits;
bool osd_failsafe_switch_layout; bool osd_failsafe_switch_layout;
uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE

View file

@ -300,6 +300,7 @@ static void djiPackBoxModeBitmask(boxBitmask_t * flightModeBitmask)
case FLM_ALTITUDE_HOLD: case FLM_ALTITUDE_HOLD:
case FLM_POSITION_HOLD: case FLM_POSITION_HOLD:
case FLM_MISSION: case FLM_MISSION:
case FLM_ANGLEHOLD:
default: default:
// Unsupported ATM, keep at ANGLE // Unsupported ATM, keep at ANGLE
bitArraySet(flightModeBitmask->bits, 1); // DJI: 1 << 1 : ANGLE bitArraySet(flightModeBitmask->bits, 1); // DJI: 1 << 1 : ANGLE

View file

@ -3905,9 +3905,7 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
/* Soaring mode, disables altitude control in Position hold and Course hold modes. /* Soaring mode, disables altitude control in Position hold and Course hold modes.
* Pitch allowed to freefloat within defined Angle mode deadband */ * Pitch allowed to freefloat within defined Angle mode deadband */
if (IS_RC_MODE_ACTIVE(BOXSOARING) && (FLIGHT_MODE(NAV_POSHOLD_MODE) || FLIGHT_MODE(NAV_COURSE_HOLD_MODE))) { if (IS_RC_MODE_ACTIVE(BOXSOARING) && (FLIGHT_MODE(NAV_POSHOLD_MODE) || FLIGHT_MODE(NAV_COURSE_HOLD_MODE))) {
if (!FLIGHT_MODE(SOARING_MODE)) { ENABLE_FLIGHT_MODE(SOARING_MODE);
ENABLE_FLIGHT_MODE(SOARING_MODE);
}
} else { } else {
DISABLE_FLIGHT_MODE(SOARING_MODE); DISABLE_FLIGHT_MODE(SOARING_MODE);
} }
@ -4582,3 +4580,21 @@ int32_t navigationGetHeadingError(void)
{ {
return wrap_18000(posControl.desiredState.yaw - posControl.actualState.cog); return wrap_18000(posControl.desiredState.yaw - posControl.actualState.cog);
} }
int8_t navCheckActiveAngleHoldAxis(void)
{
int8_t activeAxis = -1;
if (IS_RC_MODE_ACTIVE(BOXANGLEHOLD)) {
navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();
bool altholdActive = stateFlags & NAV_REQUIRE_ANGLE_FW && !(stateFlags & NAV_REQUIRE_ANGLE);
if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && !FLIGHT_MODE(NAV_ALTHOLD_MODE)) {
activeAxis = FD_PITCH;
} else if (altholdActive) {
activeAxis = FD_ROLL;
}
}
return activeAxis;
}

View file

@ -631,6 +631,8 @@ bool isEstimatedAglTrusted(void);
void checkManualEmergencyLandingControl(bool forcedActivation); void checkManualEmergencyLandingControl(bool forcedActivation);
float updateBaroAltitudeRate(float newBaroAltRate, bool updateValue); float updateBaroAltitudeRate(float newBaroAltRate, bool updateValue);
int8_t navCheckActiveAngleHoldAxis(void);
/* Returns the heading recorded when home position was acquired. /* Returns the heading recorded when home position was acquired.
* Note that the navigation system uses deg*100 as unit and angles * Note that the navigation system uses deg*100 as unit and angles
* are in the [0, 360 * 100) interval. * are in the [0, 360 * 100) interval.

View file

@ -486,7 +486,6 @@ static int logicConditionCompute(
return operandA; return operandA;
break; break;
#endif #endif
#ifdef USE_GPS_FIX_ESTIMATION #ifdef USE_GPS_FIX_ESTIMATION
case LOGIC_CONDITION_DISABLE_GPS_FIX: case LOGIC_CONDITION_DISABLE_GPS_FIX:
if (operandA > 0) { if (operandA > 0) {
@ -877,13 +876,18 @@ static int logicConditionGetFlightModeOperandValue(int operand) {
return (bool) FLIGHT_MODE(HORIZON_MODE); return (bool) FLIGHT_MODE(HORIZON_MODE);
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLEHOLD:
return (bool) FLIGHT_MODE(ANGLEHOLD_MODE);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR: case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR:
return (bool) FLIGHT_MODE(AIRMODE_ACTIVE); return (bool) FLIGHT_MODE(AIRMODE_ACTIVE);
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO: case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO:
return (((bool) FLIGHT_MODE(ANGLE_MODE) || (bool) FLIGHT_MODE(HORIZON_MODE) || (bool) FLIGHT_MODE(MANUAL_MODE) || (bool) FLIGHT_MODE(NAV_RTH_MODE) || return (((bool) FLIGHT_MODE(ANGLE_MODE) || (bool) FLIGHT_MODE(HORIZON_MODE) || (bool) FLIGHT_MODE(ANGLEHOLD_MODE) ||
(bool) FLIGHT_MODE(NAV_POSHOLD_MODE) || (bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) || (bool) FLIGHT_MODE(NAV_WP_MODE)) == false); (bool) FLIGHT_MODE(MANUAL_MODE) || (bool) FLIGHT_MODE(NAV_RTH_MODE) || (bool) FLIGHT_MODE(NAV_POSHOLD_MODE) ||
(bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) || (bool) FLIGHT_MODE(NAV_WP_MODE)) == false);
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1: case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1:

View file

@ -159,6 +159,7 @@ typedef enum {
LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4, // 13 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4, // 13
LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO, // 14 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO, // 14
LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION, // 15 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION, // 15
LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLEHOLD, // 16
} logicFlightModeOperands_e; } logicFlightModeOperands_e;
typedef enum { typedef enum {

View file

@ -0,0 +1 @@
target_stm32h743xi(SDMODELH7V1)

View file

@ -0,0 +1,40 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "fc/fc_msp_box.h"
#include "fc/config.h"
#include "io/piniobox.h"
#include "drivers/serial.h"
#include "io/serial.h"
void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].msp_baudrateIndex = BAUD_115200;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].msp_baudrateIndex = BAUD_115200;
}

View file

@ -0,0 +1,44 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/bus.h"
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/pinio.h"
#include "drivers/sensor.h"
timerHardware_t timerHardware[] = {
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(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 2), // S3
DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 3), // S4
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 4), // S5
DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 5), // S6
DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 6), // S7
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 7), // S8
DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 9), // LED_2812
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);

View file

@ -0,0 +1,182 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "SMH71"
#define USBD_PRODUCT_STRING "SDMODELH7V1"
#define USE_TARGET_CONFIG
#define LED0 PC2
#define BEEPER PC13
#define BEEPER_INVERTED
// *************** IMU generic ***********************
// *************** SPI1 ****************
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define USE_FLASHFS
#define USE_FLASH_W25N01G
#define W25N01G_SPI_BUS BUS_SPI1
#define W25N01G_CS_PIN PA4
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
// *************** SPI2 ***********************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
// *************** SPI4 ***************
#define USE_SPI_DEVICE_4
#define SPI4_SCK_PIN PE2
#define SPI4_MISO_PIN PE5
#define SPI4_MOSI_PIN PE6
//MPU6000
#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW270_DEG
#define MPU6000_SPI_BUS BUS_SPI4
#define MPU6000_CS_PIN PE4
//BMI270
#define USE_IMU_BMI270
#define BMI270_SPI_BUS BUS_SPI4
#define BMI270_CS_PIN PE4
#define IMU_BMI270_ALIGN CW0_DEG
#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI2
#define MAX7456_CS_PIN PB12
// *************** I2C /Baro/Mag *********************
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB6
#define I2C1_SDA PB7
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_DPS310
#define USE_BARO_SPL06
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110
#define USE_MAG_LIS3MDL
#define USE_MAG_VCM5883
#define TEMPERATURE_I2C_BUS BUS_I2C1
#define PITOT_I2C_BUS BUS_I2C1
#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS BUS_I2C1
// *************** UART *****************************
#define USE_VCP
#define USE_UART1
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define USE_UART2
#define UART2_TX_PIN PD5
#define UART2_RX_PIN PD6
#define USE_UART3
#define UART3_TX_PIN PD8
#define UART3_RX_PIN PD9
#define USE_UART4
#define UART4_TX_PIN PD1
#define UART4_RX_PIN PD0
#define USE_UART6
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define USE_UART7
#define UART7_RX_PIN PE7
#define SERIAL_PORT_COUNT 7
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC_CHANNEL_1_PIN PC0
#define ADC_CHANNEL_2_PIN PC5
#define ADC_CHANNEL_3_PIN PC1
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
#define RSSI_ADC_CHANNEL ADC_CHN_2
// *************** PINIO ***************************
#define USE_PINIO
#define USE_PINIOBOX
#define PINIO1_PIN PE13
#define PINIO2_PIN PB11
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
#define PINIO2_FLAGS PINIO_FLAGS_INVERTED
// *************** LEDSTRIP ************************
#define USE_LED_STRIP
#define WS2811_PIN PD12
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
#define CURRENT_METER_SCALE 250
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define MAX_PWM_OUTPUT_PORTS 8
#define USE_DSHOT
#define USE_ESC_SENSOR

View file

@ -352,6 +352,8 @@ static void crsfFrameFlightMode(sbuf_t *dst)
flightMode = "ANGL"; flightMode = "ANGL";
} else if (FLIGHT_MODE(HORIZON_MODE)) { } else if (FLIGHT_MODE(HORIZON_MODE)) {
flightMode = "HOR"; flightMode = "HOR";
} else if (FLIGHT_MODE(ANGLEHOLD_MODE)) {
flightMode = "ANGH";
} }
#ifdef USE_GPS #ifdef USE_GPS
} else if (feature(FEATURE_GPS) && navConfig()->general.flags.extra_arming_safety && (!STATE(GPS_FIX) || !STATE(GPS_FIX_HOME))) { } else if (feature(FEATURE_GPS) && navConfig()->general.flags.extra_arming_safety && (!STATE(GPS_FIX) || !STATE(GPS_FIX_HOME))) {

View file

@ -191,6 +191,7 @@ static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
case FLM_ACRO_AIR: return COPTER_MODE_ACRO; case FLM_ACRO_AIR: return COPTER_MODE_ACRO;
case FLM_ANGLE: return COPTER_MODE_STABILIZE; case FLM_ANGLE: return COPTER_MODE_STABILIZE;
case FLM_HORIZON: return COPTER_MODE_STABILIZE; case FLM_HORIZON: return COPTER_MODE_STABILIZE;
case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE;
case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD; case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD;
case FLM_POSITION_HOLD: return COPTER_MODE_POSHOLD; case FLM_POSITION_HOLD: return COPTER_MODE_POSHOLD;
case FLM_RTH: return COPTER_MODE_RTL; case FLM_RTH: return COPTER_MODE_RTL;
@ -220,6 +221,7 @@ static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
case FLM_ACRO_AIR: return PLANE_MODE_ACRO; case FLM_ACRO_AIR: return PLANE_MODE_ACRO;
case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A; case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A;
case FLM_HORIZON: return PLANE_MODE_STABILIZE; case FLM_HORIZON: return PLANE_MODE_STABILIZE;
case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE;
case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B; case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B;
case FLM_POSITION_HOLD: return PLANE_MODE_LOITER; case FLM_POSITION_HOLD: return PLANE_MODE_LOITER;
case FLM_RTH: return PLANE_MODE_RTL; case FLM_RTH: return PLANE_MODE_RTL;
@ -670,7 +672,7 @@ void mavlinkSendHUDAndHeartbeat(void)
// heading Current heading in degrees, in compass units (0..360, 0=north) // heading Current heading in degrees, in compass units (0..360, 0=north)
DECIDEGREES_TO_DEGREES(attitude.values.yaw), DECIDEGREES_TO_DEGREES(attitude.values.yaw),
// throttle Current throttle setting in integer percent, 0 to 100 // throttle Current throttle setting in integer percent, 0 to 100
thr, thr,
// alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate) // alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
mavAltitude, mavAltitude,
// climb Current climb rate in meters/second // climb Current climb rate in meters/second
@ -1110,9 +1112,9 @@ void handleMAVLinkTelemetry(timeUs_t currentTimeUs)
if ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) { if ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) {
// Only process scheduled data if we didn't serve any incoming request this cycle // Only process scheduled data if we didn't serve any incoming request this cycle
if (!incomingRequestServed || if (!incomingRequestServed ||
( (
(rxConfig()->receiverType == RX_TYPE_SERIAL) && (rxConfig()->receiverType == RX_TYPE_SERIAL) &&
(rxConfig()->serialrx_provider == SERIALRX_MAVLINK) && (rxConfig()->serialrx_provider == SERIALRX_MAVLINK) &&
!tristateWithDefaultOnIsActive(rxConfig()->halfDuplex) !tristateWithDefaultOnIsActive(rxConfig()->halfDuplex)
) )

View file

@ -122,7 +122,7 @@ static uint8_t simModuleState = SIM_MODULE_NOT_DETECTED;
static int simRssi; static int simRssi;
static uint8_t accEvent = ACC_EVENT_NONE; static uint8_t accEvent = ACC_EVENT_NONE;
static char* accEventDescriptions[] = { "", "HIT! ", "DROP ", "HIT " }; static char* accEventDescriptions[] = { "", "HIT! ", "DROP ", "HIT " };
static char* modeDescriptions[] = { "MAN", "ACR", "AIR", "ANG", "HOR", "ALH", "POS", "RTH", "WP", "CRS", "LAU", "FS" }; static char* modeDescriptions[] = { "MAN", "ACR", "AIR", "ANG", "HOR", "ALH", "POS", "RTH", "WP", "CRS", "LAU", "FS", "ANH" };
static const char gpsFixIndicators[] = { '!', '*', ' ' }; static const char gpsFixIndicators[] = { '!', '*', ' ' };
static bool checkGroundStationNumber(uint8_t* rv) static bool checkGroundStationNumber(uint8_t* rv)