diff --git a/.vscode/tasks.json b/.vscode/tasks.json index 3ca90b787d..7be2cd3d17 100755 --- a/.vscode/tasks.json +++ b/.vscode/tasks.json @@ -4,9 +4,9 @@ "version": "2.0.0", "tasks": [ { - "label": "Build Matek F722-SE", + "label": "Build AOCODARCH7DUAL", "type": "shell", - "command": "make MATEKF722SE", + "command": "make AOCODARCH7DUAL", "group": "build", "problemMatcher": [], "options": { @@ -14,9 +14,9 @@ } }, { - "label": "Build Matek F722", + "label": "Build AOCODARCH7DUAL", "type": "shell", - "command": "make MATEKF722", + "command": "make AOCODARCH7DUAL", "group": { "kind": "build", "isDefault": true diff --git a/build_docs.sh b/build_docs.sh index 70c2cc45cf..9711d8775c 100755 --- a/build_docs.sh +++ b/build_docs.sh @@ -21,7 +21,6 @@ doc_files=( 'Buzzer.md' 'Sonar.md' 'Profiles.md' - 'Modes.md' 'Inflight Adjustments.md' 'Controls.md' 'Gtune.md' @@ -49,7 +48,7 @@ if which gimli >/dev/null; then done rm -f ${filename}.pdf gimli -f ${filename}.md -stylesheet override.css \ - -w '--toc --title "Cleanflight Manual" --footer-right "[page]" --toc-depth 1' + -w '--toc --title "INAV Manual" --footer-right "[page]" --toc-depth 1' rm ${filename}.md popd >/dev/null else diff --git a/cmake/arm-none-eabi-checks.cmake b/cmake/arm-none-eabi-checks.cmake index 200065fdd4..f31a26c3e3 100644 --- a/cmake/arm-none-eabi-checks.cmake +++ b/cmake/arm-none-eabi-checks.cmake @@ -47,7 +47,7 @@ function(arm_none_eabi_gcc_install) host_uname_machine(machine) if(machine STREQUAL "x86_64" OR machine STREQUAL "amd64") set(dist ${arm_none_eabi_darwin_amd64}) - elseif(machine STREQUAL "aarch64") + elseif(machine STREQUAL "aarch64" OR machine STREQUAL "arm64") set(dist ${arm_none_eabi_darwin_aarch64}) else() message("-- no precompiled ${arm_none_eabi_triplet} toolchain for machine ${machine}") diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake index 78697f98a9..ee43aa9a93 100644 --- a/cmake/sitl.cmake +++ b/cmake/sitl.cmake @@ -34,7 +34,7 @@ set(SITL_LINK_OPTIONS -Wl,-L${STM32_LINKER_DIR} ) -if(${WIN32} OR ${CYGWIN}) +if(${CYGWIN}) set(SITL_LINK_OPTIONS ${SITL_LINK_OPTIONS} "-static-libgcc") endif() @@ -131,7 +131,7 @@ function (target_sitl name) target_link_options(${exe_target} PRIVATE -T${script_path}) endif() - if(${WIN32} OR ${CYGWIN}) + if(${CYGWIN}) set(exe_filename ${CMAKE_BINARY_DIR}/${binary_name}.exe) else() set(exe_filename ${CMAKE_BINARY_DIR}/${binary_name}) diff --git a/docs/API/MSP_extensions.md b/docs/API/MSP_extensions.md index 357c6239e8..2ac8dd989f 100644 --- a/docs/API/MSP_extensions.md +++ b/docs/API/MSP_extensions.md @@ -23,7 +23,7 @@ Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the | Data | Type | Notes | |------|------|-------| -| permanentId | uint8 | See Modes.md for a definition of the permanent ids | +| permanentId | uint8 | See [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for a definition of the permanent ids | | auxChannelIndex | uint8 | The Aux switch number (indexed from 0) | | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | @@ -45,7 +45,7 @@ sending this message for all auxiliary slots. | Data | Type | Notes | |------|------|-------| | sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 | -| permanentId | uint8 | See Modes.md for a definition of the permanent ids | +| permanentId | uint8 | See [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for a definition of the permanent ids | | auxChannelIndex | uint8 | The Aux channel number (indexed from 0) | | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | @@ -157,5 +157,5 @@ INAV. See also -------- -Modes.md describes the user visible implementation for the INAV +[The wiki](https://github.com/iNavFlight/inav/wiki/Modes) describes the user visible implementation for the INAV modes extension. diff --git a/docs/ESC and servo outputs.md b/docs/ESC and servo outputs.md index 64354f33ed..eba8187ca5 100644 --- a/docs/ESC and servo outputs.md +++ b/docs/ESC and servo outputs.md @@ -13,7 +13,7 @@ INAV support the following ESC protocols: ESC protocol can be selected in Configurator. No special configuration is required. -Check ESC documentation of the list of protocols that it is supporting. +Check the ESC documentation for the list of protocols that are supported. ## Servo outputs diff --git a/docs/Fixed Wing Landing.md b/docs/Fixed Wing Landing.md index 4ccb324953..c89a5ee207 100644 --- a/docs/Fixed Wing Landing.md +++ b/docs/Fixed Wing Landing.md @@ -5,6 +5,8 @@ INAV supports advanced automatic landings for fixed wing aircraft from version 7.1. The procedure is based on landings for man-carrying aircraft, so that safe landings at a specific location are possible. Supported are landings at safehome after "Return to Home" or at a defined LAND waypoint for missions. +Every landing locations can be defined with a target point and 2 different approach headings (colinear to the landing strips) with exclusive direction or opposite directions allowed. +This enables up to 4 different approach directions, based on the landing site and surrounding area. ## General procedure: @@ -34,7 +36,7 @@ The following graphics illustrate the process: ### The following parameters are set for each landing site (Safefome/LAND waypoint): -All settings can also be conveniently made in the Configurator via Missionplanner. +All settings can also be conveniently made in the Configurator via Mission Control. CLI command `fwapproach`: `fwapproach ` @@ -54,7 +56,7 @@ This means that practically 4 landing directions can be saved. > [!CAUTION] > The Configuator automatically determines the ground altitude based on databases on the Internet, which may be inaccurate. Please always compare with the measured GPS altitude at the landing site to avoid crashes. -### Global paramters +### Global parameters All settings are available via “Advanced Tuning” in the Configurator. @@ -80,6 +82,23 @@ In degrees. Min: 0, Max: 45, Default: 0 * `nav_fw_land_max_tailwind`: Max. tailwind if no landing direction with downwind is available. Wind strengths below this value are ignored (error tolerance in the wind measurement). Landing then takes place in the main direction. If, for example, 90 degrees is configured, landing takes place in this direction, NOT in 270 degrees (see above). In cm/s. Min: 0; Max: 3000, Default: 140 +### General paramters and tuning tips + +* `nav_fw_wp_tracking_accuracy`: Its highly recommended that this parameter is used and tuned well. Only with WP-Tracking enabled, the Aircraft will try to precisely align with the runway during approach. +If WP-Tracking is not used, the Plane will head straight to the landiung location without flying in line with the intended landing strip. Wind can intensively alter the final landing heading. + +* `nav_fw_pitch2thr`: The navigation throttle modifier has to be tuned well to allow stable navigation during climbs and descents to prevent a stall. Make sure your plane maintains Ground or Airspeed, when climbing in any navigation mode. +The Craft should not get slower and not speed ub significantly during a navigation climb, if P2T is tuned properly. + +* `nav_wp_radius`: This parameter might be too high if you have set up your craft with INAV 6 or INAV 7. With a too high value, the turning points for the Crosswind-Leg and Final Approach are hit too early and make it difficult for the plane to align to the runway or cut short the approach. +Make sure this parameter is not set greater than 1000 (cm). The better your craft and navigation system is tuned, the lower this value can be. We recommend to start with 1000 for flying wings and 800 for a Plane with Tail. + +* Test your Navigation-Tuning: A better Navigation-Tune will reward you with smoother and more reliable landings. To test your nav systems limit, we recommend to create a waypoint missions with many 90° turn angles with shorter and shorter tracks. +With this Method, you can find out how well your plane can follow a navigation path and how long it takes to align to a waypoint track. A well tuned plane should be able to pull of a WP Mission that looks like this, where the distance between WP6 and WP7 si recommended to be the minimum approach length: + +![Test Waypoint Track](https://github.com/iNavFlight/inav/assets/33039058/a929cd0c-80b1-42d6-815d-89a90e9daa1b) + + ## Waypoint missions Only one landing waypoint per mission can be active and saved and the landing waypoint must be the last waypoint of the mission. @@ -87,7 +106,7 @@ If the altitude of the waypoint and the "Approach Altitude" are different, the a ## Logic Conditions -The current landing state can be retrieved via ID 41 in "Flight" (FW Land State). This allows additional actions to be executed according to the landing phases, e.g. deplyoment of the landing flaps. +The current landing state can be retrieved via ID 41 in "Flight" (FW Land State). This allows additional actions to be executed according to the landing phases, e.g. deployment of the landing flaps. | Returned value | State | | --- | --- | diff --git a/docs/Getting Started.md b/docs/Getting Started.md index 2faa8e3323..f49ca32cc4 100644 --- a/docs/Getting Started.md +++ b/docs/Getting Started.md @@ -70,7 +70,7 @@ Now, there are two ways to [configure CF](Configuration.md); via the Configurat * Verify the range of each channel goes from ~1000 to ~2000. See also [controls](Controls.md). and `rx_min_usec` and `rx_max_usec`. * You can also set EXPO here instead of your Tx. * Click Save! -* Modes tab: Setup the desired modes. See the [modes](Modes.md) chapter for what each mode does, but for the beginning you mainly need HORIZON, if any. +* Modes tab: Setup the desired modes. See the [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for what each mode does. * Before finishing this section, you should calibrate the ESCs, install the FC to the frame, and connect the RSSI cable, buzzer and battery if you have chosen to use those. diff --git a/docs/OSD.md b/docs/OSD.md index b3526d0d76..d57da7e25f 100644 --- a/docs/OSD.md +++ b/docs/OSD.md @@ -19,155 +19,156 @@ Not all OSDs are created equally. This table shows the differences between the d ## OSD Elements Here are the OSD Elements provided by INAV. -| ID | Element | Added | -|-----|--------------------------------------------------|--------| -| 0 | OSD_RSSI_VALUE | 1.0.0 | -| 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 | -| 2 | OSD_CROSSHAIRS | 1.0.0 | -| 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 | -| 4 | OSD_HORIZON_SIDEBARS | 1.0.0 | -| 5 | OSD_ONTIME | 1.0.0 | -| 6 | OSD_FLYTIME | 1.0.0 | -| 7 | OSD_FLYMODE | 1.0.0 | -| 8 | OSD_CRAFT_NAME | 1.0.0 | -| 9 | OSD_THROTTLE_POS | 1.0.0 | -| 10 | OSD_VTX_CHANNEL | 1.0.0 | -| 11 | OSD_CURRENT_DRAW | 1.0.0 | -| 12 | OSD_MAH_DRAWN | 1.0.0 | -| 13 | OSD_GPS_SPEED | 1.0.0 | -| 14 | OSD_GPS_SATS | 1.0.0 | -| 15 | OSD_ALTITUDE | 1.0.0 | -| 16 | OSD_ROLL_PIDS | 1.6.0 | -| 17 | OSD_PITCH_PIDS | 1.6.0 | -| 18 | OSD_YAW_PIDS | 1.6.0 | -| 19 | OSD_POWER | 1.6.0 | -| 20 | OSD_GPS_LON | 1.6.0 | -| 21 | OSD_GPS_LAT | 1.6.0 | -| 22 | OSD_HOME_DIR | 1.6.0 | -| 23 | OSD_HOME_DIST | 1.6.0 | -| 24 | OSD_HEADING | 1.6.0 | -| 25 | OSD_VARIO | 1.6.0 | -| 26 | OSD_VARIO_NUM | 1.6.0 | -| 27 | OSD_AIR_SPEED | 1.7.3 | -| 28 | OSD_ONTIME_FLYTIME | 1.8.0 | -| 29 | OSD_RTC_TIME | 1.8.0 | -| 30 | OSD_MESSAGES | 1.8.0 | -| 31 | OSD_GPS_HDOP | 1.8.0 | -| 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 | -| 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 | -| 34 | OSD_HEADING_GRAPH | 1.8.0 | -| 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 | -| 36 | OSD_WH_DRAWN | 1.9.0 | -| 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 | -| 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 | -| 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 | -| 40 | OSD_TRIP_DIST | 1.9.1 | -| 41 | OSD_ATTITUDE_PITCH | 2.0.0 | -| 42 | OSD_ATTITUDE_ROLL | 2.0.0 | -| 43 | OSD_MAP_NORTH | 2.0.0 | -| 44 | OSD_MAP_TAKEOFF | 2.0.0 | -| 45 | OSD_RADAR | 2.0.0 | -| 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 | -| 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 | -| 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 | -| 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 | -| 50 | OSD_HOME_HEADING_ERROR | 2.0.0 | -| 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 | -| 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 | -| 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 | -| 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 | -| 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 | -| 56 | OSD_LEVEL_PIDS | 2.0.0 | -| 57 | OSD_POS_XY_PIDS | 2.0.0 | -| 58 | OSD_POS_Z_PIDS | 2.0.0 | -| 59 | OSD_VEL_XY_PIDS | 2.0.0 | -| 60 | OSD_VEL_Z_PIDS | 2.0.0 | -| 61 | OSD_HEADING_P | 2.0.0 | -| 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 | -| 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 | -| 64 | OSD_RC_EXPO | 2.0.0 | -| 65 | OSD_RC_YAW_EXPO | 2.0.0 | -| 66 | OSD_THROTTLE_EXPO | 2.0.0 | -| 67 | OSD_PITCH_RATE | 2.0.0 | -| 68 | OSD_ROLL_RATE | 2.0.0 | -| 69 | OSD_YAW_RATE | 2.0.0 | -| 70 | OSD_MANUAL_RC_EXPO | 2.0.0 | -| 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 | -| 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 | -| 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 | -| 74 | OSD_MANUAL_YAW_RATE | 2.0.0 | -| 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 | -| 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 | -| 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 | -| 78 | OSD_DEBUG | 2.0.0 | -| 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 | -| 80 | OSD_FW_POS_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 | -| 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 | -| 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 | -| 85 | OSD_3D_SPEED | 2.1.0 | -| 86 | OSD_IMU_TEMPERATURE | 2.1.0 | -| 87 | OSD_BARO_TEMPERATURE | 2.1.0 | -| 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 | -| 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 | -| 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 | -| 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 | -| 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 | -| 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 | -| 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 | -| 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 | -| 96 | OSD_ALTITUDE_MSL | 2.1.0 | -| 97 | OSD_PLUS_CODE | 2.1.0 | -| 98 | OSD_MAP_SCALE | 2.2.0 | -| 99 | OSD_MAP_REFERENCE | 2.2.0 | -| 100 | OSD_GFORCE | 2.2.0 | -| 101 | OSD_GFORCE_X | 2.2.0 | -| 102 | OSD_GFORCE_Y | 2.2.0 | -| 103 | OSD_GFORCE_Z | 2.2.0 | -| 104 | OSD_RC_SOURCE | 2.2.0 | -| 105 | OSD_VTX_POWER | 2.2.0 | -| 106 | OSD_ESC_RPM | 2.3.0 | -| 107 | OSD_ESC_TEMPERATURE | 2.5.0 | -| 108 | OSD_AZIMUTH | 2.6.0 | -| 109 | OSD_CRSF_RSSI_DBM | 2.6.0 | -| 110 | OSD_CRSF_LQ | 2.6.0 | -| 111 | OSD_CRSF_SNR_DB | 2.6.0 | -| 112 | OSD_CRSF_TX_POWER | 2.6.0 | -| 113 | OSD_GVAR_0 | 2.6.0 | -| 114 | OSD_GVAR_1 | 2.6.0 | -| 115 | OSD_GVAR_2 | 2.6.0 | -| 116 | OSD_GVAR_3 | 2.6.0 | -| 117 | OSD_TPA | 2.6.0 | -| 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 | -| 119 | OSD_VERSION | 3.0.0 | -| 120 | OSD_RANGEFINDER | 3.0.0 | -| 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 | -| 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 | -| 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 | -| 124 | OSD_GLIDESLOPE | 3.0.1 | -| 125 | OSD_GPS_MAX_SPEED | 4.0.0 | -| 126 | OSD_3D_MAX_SPEED | 4.0.0 | -| 127 | OSD_AIR_MAX_SPEED | 4.0.0 | -| 128 | OSD_ACTIVE_PROFILE | 4.0.0 | -| 129 | OSD_MISSION | 4.0.0 | -| 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 | -| 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 | -| 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 | -| 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 | -| 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 | -| 135 | OSD_FW_LEVEL_TRIM | 5.0.0 | -| 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 | -| 137 | OSD_GLIDE_RANGE | 6.0.0 | -| 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 | -| 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 | -| 140 | OSD_GROUND_COURSE | 6.0.0 | -| 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 | -| 142 | OSD_PILOT_NAME | 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 | +| ID | Element | Added | Notes | +|-----|--------------------------------------------------|--------|-------| +| 0 | OSD_RSSI_VALUE | 1.0.0 | | +| 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 | | +| 2 | OSD_CROSSHAIRS | 1.0.0 | | +| 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 | | +| 4 | OSD_HORIZON_SIDEBARS | 1.0.0 | | +| 5 | OSD_ONTIME | 1.0.0 | | +| 6 | OSD_FLYTIME | 1.0.0 | | +| 7 | OSD_FLYMODE | 1.0.0 | | +| 8 | OSD_CRAFT_NAME | 1.0.0 | | +| 9 | OSD_THROTTLE_POS | 1.0.0 | | +| 10 | OSD_VTX_CHANNEL | 1.0.0 | | +| 11 | OSD_CURRENT_DRAW | 1.0.0 | | +| 12 | OSD_MAH_DRAWN | 1.0.0 | | +| 13 | OSD_GPS_SPEED | 1.0.0 | | +| 14 | OSD_GPS_SATS | 1.0.0 | | +| 15 | OSD_ALTITUDE | 1.0.0 | | +| 16 | OSD_ROLL_PIDS | 1.6.0 | | +| 17 | OSD_PITCH_PIDS | 1.6.0 | | +| 18 | OSD_YAW_PIDS | 1.6.0 | | +| 19 | OSD_POWER | 1.6.0 | | +| 20 | OSD_GPS_LON | 1.6.0 | | +| 21 | OSD_GPS_LAT | 1.6.0 | | +| 22 | OSD_HOME_DIR | 1.6.0 | | +| 23 | OSD_HOME_DIST | 1.6.0 | | +| 24 | OSD_HEADING | 1.6.0 | | +| 25 | OSD_VARIO | 1.6.0 | | +| 26 | OSD_VARIO_NUM | 1.6.0 | | +| 27 | OSD_AIR_SPEED | 1.7.3 | | +| 28 | OSD_ONTIME_FLYTIME | 1.8.0 | | +| 29 | OSD_RTC_TIME | 1.8.0 | | +| 30 | OSD_MESSAGES | 1.8.0 | | +| 31 | OSD_GPS_HDOP | 1.8.0 | | +| 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 | | +| 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 | | +| 34 | OSD_HEADING_GRAPH | 1.8.0 | | +| 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 | | +| 36 | OSD_WH_DRAWN | 1.9.0 | | +| 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 | | +| 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 | | +| 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 | | +| 40 | OSD_TRIP_DIST | 1.9.1 | | +| 41 | OSD_ATTITUDE_PITCH | 2.0.0 | | +| 42 | OSD_ATTITUDE_ROLL | 2.0.0 | | +| 43 | OSD_MAP_NORTH | 2.0.0 | | +| 44 | OSD_MAP_TAKEOFF | 2.0.0 | | +| 45 | OSD_RADAR | 2.0.0 | | +| 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 | | +| 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 | | +| 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 | | +| 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 | | +| 50 | OSD_HOME_HEADING_ERROR | 2.0.0 | | +| 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 | | +| 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 | | +| 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 | | +| 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 | | +| 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 | | +| 56 | OSD_LEVEL_PIDS | 2.0.0 | | +| 57 | OSD_POS_XY_PIDS | 2.0.0 | | +| 58 | OSD_POS_Z_PIDS | 2.0.0 | | +| 59 | OSD_VEL_XY_PIDS | 2.0.0 | | +| 60 | OSD_VEL_Z_PIDS | 2.0.0 | | +| 61 | OSD_HEADING_P | 2.0.0 | | +| 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 | | +| 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 | | +| 64 | OSD_RC_EXPO | 2.0.0 | | +| 65 | OSD_RC_YAW_EXPO | 2.0.0 | | +| 66 | OSD_THROTTLE_EXPO | 2.0.0 | | +| 67 | OSD_PITCH_RATE | 2.0.0 | | +| 68 | OSD_ROLL_RATE | 2.0.0 | | +| 69 | OSD_YAW_RATE | 2.0.0 | | +| 70 | OSD_MANUAL_RC_EXPO | 2.0.0 | | +| 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 | | +| 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 | | +| 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 | | +| 74 | OSD_MANUAL_YAW_RATE | 2.0.0 | | +| 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 | | +| 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 | | +| 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 | | +| 78 | OSD_DEBUG | 2.0.0 | | +| 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 | | +| 80 | OSD_FW_POS_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 | | +| 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 | | +| 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 | | +| 85 | OSD_3D_SPEED | 2.1.0 | | +| 86 | OSD_IMU_TEMPERATURE | 2.1.0 | | +| 87 | OSD_BARO_TEMPERATURE | 2.1.0 | | +| 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 | | +| 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 | | +| 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 | | +| 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 | | +| 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 | | +| 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 | | +| 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 | | +| 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 | | +| 96 | OSD_ALTITUDE_MSL | 2.1.0 | | +| 97 | OSD_PLUS_CODE | 2.1.0 | | +| 98 | OSD_MAP_SCALE | 2.2.0 | | +| 99 | OSD_MAP_REFERENCE | 2.2.0 | | +| 100 | OSD_GFORCE | 2.2.0 | | +| 101 | OSD_GFORCE_X | 2.2.0 | | +| 102 | OSD_GFORCE_Y | 2.2.0 | | +| 103 | OSD_GFORCE_Z | 2.2.0 | | +| 104 | OSD_RC_SOURCE | 2.2.0 | | +| 105 | OSD_VTX_POWER | 2.2.0 | | +| 106 | OSD_ESC_RPM | 2.3.0 | | +| 107 | OSD_ESC_TEMPERATURE | 2.5.0 | | +| 108 | OSD_AZIMUTH | 2.6.0 | | +| 109 | OSD_CRSF_RSSI_DBM | 2.6.0 | | +| 110 | OSD_CRSF_LQ | 2.6.0 | | +| 111 | OSD_CRSF_SNR_DB | 2.6.0 | | +| 112 | OSD_CRSF_TX_POWER | 2.6.0 | | +| 113 | OSD_GVAR_0 | 2.6.0 | | +| 114 | OSD_GVAR_1 | 2.6.0 | | +| 115 | OSD_GVAR_2 | 2.6.0 | | +| 116 | OSD_GVAR_3 | 2.6.0 | | +| 117 | OSD_TPA | 2.6.0 | | +| 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 | | +| 119 | OSD_VERSION | 3.0.0 | | +| 120 | OSD_RANGEFINDER | 3.0.0 | | +| 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 | | +| 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 | | +| 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 | | +| 124 | OSD_GLIDESLOPE | 3.0.1 | | +| 125 | OSD_GPS_MAX_SPEED | 4.0.0 | | +| 126 | OSD_3D_MAX_SPEED | 4.0.0 | | +| 127 | OSD_AIR_MAX_SPEED | 4.0.0 | | +| 128 | OSD_ACTIVE_PROFILE | 4.0.0 | | +| 129 | OSD_MISSION | 4.0.0 | | +| 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 | | +| 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 | | +| 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 | | +| 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 | | +| 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 | | +| 135 | OSD_FW_LEVEL_TRIM | 5.0.0 | | +| 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 | | +| 137 | OSD_GLIDE_RANGE | 6.0.0 | | +| 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 | | +| 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 | | +| 140 | OSD_GROUND_COURSE | 6.0.0 | | +| 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 | | +| 142 | OSD_PILOT_NAME | 6.0.0 | | +| 143 | OSD_PAN_SERVO_CENTRED | 6.0.0 | | +| 144 | OSD_MULTI_FUNCTION | 7.0.0 | | +| 145 | OSD_ODOMETER | 7.0.0 | For this to work correctly, stats must be enabled (`set stats=ON`). Otherwise, this will show the total flight distance. | +| 146 | OSD_PILOT_LOGO | 7.0.0 | | +| 147 | OSD_BLACKBOX | 8.0.0 | The element will be hidden unless blackbox recording is attempted. | # Pilot Logos @@ -192,3 +193,43 @@ This is an example of the arming screen with the pilot logo enabled. This is usi 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) + +# Post Flight Statistics +The post flight statistcs are set in the firmware. Statistics are only hidden if the supporting hardware is not present. Due to size contraints. The post flight statistics are spread over 2 pages on analogue systems. + +## Statistics shown +| Statistic | Requirement | Page | | +|-------------------------------|-----------------------|-------|-| +| Flight Time | | 1 | The total time from arm to disarm. | +| Flight Distance | | 1 | | +| Maximum Distance From Home | GPS | 1 | | +| Maximum Speed | GPS | 1 | | +| Average Speed | GPS | 1 | | +| Maximum Altitude | Baro/GPS | 1 | | +| Minimum Average Cell Voltage | | 1 | | +| Minimum Pack Voltage | | 1 | | +| Maximum Current | Current Sensor | 1 | | +| Maximum Power | Current Sensor | 1 | | +| Energy Used (Flight) | Current Sensor | 1 | | +| Energy Used (Battery Total) | Current Sensor | 1 | This data is not reset on arming. | +| Average Efficiency | Current Sensor & GPS | 1 | | +| Minimum RSSI | | 2 | | +| Minimum LQ | CRSF | 2 | | +| Minmum dBm | CRSF | 2 | | +| Minimum Satellites | GPS | 2 | | +| Maximum Satellites | GPS | 2 | | +| Minimum ESC Temperature | ESC Telemetry | 2 | | +| Maximum ESC Temperature | ESC Telemetry | 2 | | +| Maximum G-Force | | 2 | | +| Minimum Z axis G-Force | | 2 | | +| Maximum Z axis G-Force | | 2 | | +| Blackbox file number | Blackbox recording | 2 | | +| Disarm method | | 1 & 2 | | +| Settings save status | | 1 & 2 | Shows a message if the settings are being saved or have been saved on disarm. | + +## Configuration +There are a couple of settings that allow you to adjust parts of the post flights statistics. + +- `osd_stats_page_auto_swap_time` allows you to specify how long each stats page is displayed [seconds]. Reverts to manual control when Roll stick used to change pages. Disabled when set to 0. +- `osd_stats_energy_unit` allows you to choose the unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour). Default is MAH. +- `osd_stats_show_metric_efficiency` if you use non-metric units on your OSD. Enabling this option will also show the efficiency in metric. diff --git a/docs/Rangefinder.md b/docs/Rangefinder.md index b7910b0fa6..095a6f0df3 100644 --- a/docs/Rangefinder.md +++ b/docs/Rangefinder.md @@ -20,6 +20,7 @@ Following rangefinders are supported: * UIB - experimental * MSP - experimental * TOF10120 - small & lightweight laser range sensor, usable up to 200cm +* TERARANGER EVO - 30cm to 600cm, depends on version https://www.terabee.com/sensors-modules/lidar-tof-range-finders/#individual-distance-measurement-sensors ## Connections diff --git a/docs/Safety.md b/docs/Safety.md index e0b969a78a..ea21424391 100644 --- a/docs/Safety.md +++ b/docs/Safety.md @@ -6,7 +6,7 @@ As many can attest, multirotors and RC models in general can be very dangerous, ## Before Installing -Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](Modes.md) +Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](https://github.com/iNavFlight/inav/wiki/Modes) pages for further important information. You are highly advised to use the Receiver tab in the INAV Configurator, making sure your Rx channel diff --git a/docs/Servo.md b/docs/Servo.md index 42acfaa3c9..d3322b02f0 100644 --- a/docs/Servo.md +++ b/docs/Servo.md @@ -1,6 +1,6 @@ # Servo configuration -Servos can be configured from the graphical user interface's `Servos` tab. +Servos can be configured from the graphical user interface's `Outputs` tab. * MID: middle/neutral point of the servo * MIN: the minimum value that can be sent to the servo is MIN * Rate diff --git a/docs/Settings.md b/docs/Settings.md index 79278af68f..7ed9437ced 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -104,7 +104,7 @@ Specifies the type of the software LPF of the acc signals. BIQUAD gives better f ### acc_notch_cutoff -_// TODO_ +Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz) | Default | Min | Max | | --- | --- | --- | @@ -114,7 +114,7 @@ _// TODO_ ### acc_notch_hz -_// TODO_ +Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is center frequency (Hz) | Default | Min | Max | | --- | --- | --- | @@ -394,7 +394,7 @@ Defines the deadband of throttle during alt_hold [r/c points] ### antigravity_accelerator -_// TODO_ +Multiplier for Antigravity gain. The bigger is the difference between actual and filtered throttle input, the bigger Antigravity gain | Default | Min | Max | | --- | --- | --- | @@ -552,16 +552,6 @@ Blackbox logging rate numerator. Use num/denom settings to decide if a frame sho --- -### control_deadband - -Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered. - -| Default | Min | Max | -| --- | --- | --- | -| 10 | 2 | 250 | - ---- - ### controlrate_profile Control rate profile to switch to when the battery profile is selected, 0 to disable and keep the currently selected control rate profile @@ -572,16 +562,6 @@ Control rate profile to switch to when the battery profile is selected, 0 to dis --- -### cpu_underclock - -This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz - -| Default | Min | Max | -| --- | --- | --- | -| OFF | OFF | ON | - ---- - ### cruise_power Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit @@ -634,7 +614,7 @@ ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the ### d_boost_gyro_delta_lpf_hz -_// TODO_ +Cutoff frequency for the low pass filter applied to the gyro delta signal used for D-term boost. Lower value will produce a smoother D-term boost signal, but it will be more delayed. | Default | Min | Max | | --- | --- | --- | @@ -644,7 +624,7 @@ _// TODO_ ### d_boost_max -_// TODO_ +D-term multiplier when rapid external conditions are detected. Lower values give sharper response to stick input, higher values give smoother response by scaling D-gains up. | Default | Min | Max | | --- | --- | --- | @@ -654,7 +634,7 @@ _// TODO_ ### d_boost_max_at_acceleration -_// TODO_ +Acceleration threshold for D-term multiplier. When acceleration is above this value, D-term multiplier is set to `d_boost_max` | Default | Min | Max | | --- | --- | --- | @@ -664,7 +644,7 @@ _// TODO_ ### d_boost_min -_// TODO_ +D-term multiplier when pilot provides rapid stick input. Lower values give sharper response to stick input, higher values give smoother response. | Default | Min | Max | | --- | --- | --- | @@ -678,7 +658,7 @@ These are values (in us) by how much RC input can be different before it's consi | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 32 | +| 2 | 0 | 32 | --- @@ -692,9 +672,9 @@ Defines debug values exposed in debug variables (developer / debugging setting) --- -### disarm_kill_switch +### disarm_always -Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. +Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. | Default | Min | Max | | --- | --- | --- | @@ -772,16 +752,6 @@ Re-purpose the craft name field for messages. --- -### dji_workarounds - -Enables workarounds for different versions of MSP protocol used - -| Default | Min | Max | -| --- | --- | --- | -| 1 | 0 | 255 | - ---- - ### dshot_beeper_enabled Whether using DShot motors as beepers is enabled @@ -962,6 +932,16 @@ EzTune response --- +### ez_snappiness + +EzTune snappiness + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 100 | + +--- + ### ez_stability EzTune stability @@ -1164,7 +1144,7 @@ Defines throw range in us for both ailerons that will be passed to servo mixer v ### fpv_mix_degrees -_// TODO_ +The tilt angle of the FPV camera in degrees, used by the FPV ANGLE MIX mode | Default | Min | Max | | --- | --- | --- | @@ -1592,16 +1572,6 @@ Gyro processing anti-aliasing filter cutoff frequency. In normal operation this --- -### gyro_anti_aliasing_lpf_type - -Specifies the type of the software LPF of the gyro signals. - -| Default | Min | Max | -| --- | --- | --- | -| PT1 | | | - ---- - ### gyro_dyn_lpf_curve_expo Expo value for the throttle-to-frequency mapping for Dynamic LPF @@ -1632,16 +1602,6 @@ Minimum frequency of the gyro Dynamic LPF --- -### gyro_hardware_lpf - -Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first. - -| Default | Min | Max | -| --- | --- | --- | -| 256HZ | | | - ---- - ### gyro_main_lpf_hz Software based gyro main lowpass filter. Value is cutoff frequency (Hz) @@ -1652,19 +1612,9 @@ Software based gyro main lowpass filter. Value is cutoff frequency (Hz) --- -### gyro_main_lpf_type - -Defines the type of the main gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. - -| Default | Min | Max | -| --- | --- | --- | -| BIQUAD | | | - ---- - ### gyro_to_use -_// TODO_ +On multi-gyro targets, allows to choose which gyro to use. 0 = first gyro, 1 = second gyro | Default | Min | Max | | --- | --- | --- | @@ -1872,16 +1822,6 @@ _// TODO_ --- -### inav_use_gps_velned - -Defined if INAV should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF INAV will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. - -| Default | Min | Max | -| --- | --- | --- | -| ON | OFF | ON | - ---- - ### inav_w_acc_bias Weight for accelerometer drift estimation @@ -1894,7 +1834,7 @@ Weight for accelerometer drift estimation ### inav_w_xy_flow_p -_// TODO_ +Weight of optical flow measurements in estimated UAV position. | Default | Min | Max | | --- | --- | --- | @@ -1904,7 +1844,7 @@ _// TODO_ ### inav_w_xy_flow_v -_// TODO_ +Weight of optical flow measurements in estimated UAV speed. | Default | Min | Max | | --- | --- | --- | @@ -1984,7 +1924,7 @@ Decay coefficient for estimated climb rate when baro/GPS reference for altitude ### inav_w_z_surface_p -_// TODO_ +Weight of rangefinder measurements in estimated altitude. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled | Default | Min | Max | | --- | --- | --- | @@ -1994,7 +1934,7 @@ _// TODO_ ### inav_w_z_surface_v -_// TODO_ +Weight of rangefinder measurements in estimated climb rate. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled | Default | Min | Max | | --- | --- | --- | @@ -2042,16 +1982,6 @@ PWM mode of LED pin. --- -### ledstrip_visual_beeper - -_// TODO_ - -| Default | Min | Max | -| --- | --- | --- | -| OFF | OFF | ON | - ---- - ### limit_attn_filter_cutoff Throttle attenuation PI control output filter cutoff frequency @@ -2354,7 +2284,7 @@ Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% ### mavlink_ext_status_rate -_// TODO_ +Rate of the extended status message for MAVLink telemetry | Default | Min | Max | | --- | --- | --- | @@ -2364,7 +2294,7 @@ _// TODO_ ### mavlink_extra1_rate -_// TODO_ +Rate of the extra1 message for MAVLink telemetry | Default | Min | Max | | --- | --- | --- | @@ -2374,7 +2304,7 @@ _// TODO_ ### mavlink_extra2_rate -_// TODO_ +Rate of the extra2 message for MAVLink telemetry | Default | Min | Max | | --- | --- | --- | @@ -2384,7 +2314,7 @@ _// TODO_ ### mavlink_extra3_rate -_// TODO_ +Rate of the extra3 message for MAVLink telemetry | Default | Min | Max | | --- | --- | --- | @@ -2394,7 +2324,7 @@ _// TODO_ ### mavlink_pos_rate -_// TODO_ +Rate of the position message for MAVLink telemetry | Default | Min | Max | | --- | --- | --- | @@ -2404,7 +2334,7 @@ _// TODO_ ### mavlink_rc_chan_rate -_// TODO_ +Rate of the RC channels message for MAVLink telemetry | Default | Min | Max | | --- | --- | --- | @@ -2452,16 +2382,6 @@ These are min/max values (in us) which, when a channel is smaller (min) or large --- -### max_throttle - -This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000. - -| Default | Min | Max | -| --- | --- | --- | -| 1850 | PWM_RANGE_MIN | PWM_RANGE_MAX | - ---- - ### mc_cd_lpf_hz Cutoff frequency for Control Derivative. This controls the cutoff for the LPF that is applied to the CD (Feed Forward) signal to the PID controller. Lower value will produce a smoother CD gain to the controller, but it will be more delayed. Higher values will produce CD gain that may have more noise in the signal depending on your RC link but wil be less delayed. @@ -2584,7 +2504,7 @@ Multicopter rate stabilisation I-gain for YAW ### mc_iterm_relax -_// TODO_ +Iterm relax type. When enabled, Iterm will be relaxed when stick is centered. This will help to reduce bounceback and followthrough on multirotors. It is recommended to enable this feature on all multirotors. | Default | Min | Max | | --- | --- | --- | @@ -2594,7 +2514,7 @@ _// TODO_ ### mc_iterm_relax_cutoff -_// TODO_ +Iterm relax cutoff frequency. | Default | Min | Max | | --- | --- | --- | @@ -3004,11 +2924,11 @@ Max. tailwind (in cm/s) if no landing direction with downwind is available ### nav_fw_launch_accel -Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s +Forward acceleration threshold for bungee launch or throw launch [cm/s/s], 1G = 981 cm/s/s | Default | Min | Max | | --- | --- | --- | -| 1863 | 1000 | 20000 | +| 1863 | 1500 | 20000 | --- @@ -3162,6 +3082,16 @@ Forward velocity threshold for swing-launch detection [cm/s] --- +### nav_fw_launch_wiggle_to_wake_idle + +Trigger the idle throttle by wiggling the plane. 0 = disabled. 1 and 2 signify 1 or 2 yaw wiggles to activate. 1 wiggle has a higher detection point, for airplanes without a tail. 2 wiggles has a lower detection point, but requires the repeated action. This is intended for larger models and airplanes with tails. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 2 | + +--- + ### nav_fw_loiter_radius PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] @@ -3714,7 +3644,7 @@ A point (in percent of both target and current horizontal velocity) where nav_mc ### nav_mc_vel_xy_dterm_lpf_hz -_// TODO_ +D-term low pass filter cutoff frequency for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating. | Default | Min | Max | | --- | --- | --- | @@ -3724,7 +3654,7 @@ _// TODO_ ### nav_mc_vel_xy_ff -_// TODO_ +FF gain of Position-Rate (Velocity to Acceleration) | Default | Min | Max | | --- | --- | --- | @@ -3794,7 +3724,7 @@ When ON, NAV engine will slow down when switching to the next waypoint. This pri ### nav_min_ground_speed -Minimum ground speed for navigation flight modes [m/s]. Default 7 m/s. +Minimum ground speed for navigation flight modes [m/s]. Currently, this only affects fixed wing. Default 7 m/s. | Default | Min | Max | | --- | --- | --- | @@ -4094,7 +4024,7 @@ Selection of OPFLOW hardware. ### opflow_scale -_// TODO_ +Optical flow module scale factor | Default | Min | Max | | --- | --- | --- | @@ -4314,7 +4244,7 @@ Set the camera uptilt for the FPV camera in degres, positive is up, negative is ### osd_coordinate_digits -_// TODO_ +Number of digits for the coordinates displayed in the OSD [8-11]. | Default | Min | Max | | --- | --- | --- | @@ -4402,6 +4332,16 @@ Use wind estimation for remaining flight time/distance estimation --- +### osd_estimations_wind_mps + +Wind speed estimation in m/s + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### osd_failsafe_switch_layout If enabled the OSD automatically switches to the first layout during failsafe @@ -4664,7 +4604,7 @@ PWM value for UP key ### osd_left_sidebar_scroll -_// TODO_ +Scroll type for the left sidebar | Default | Min | Max | | --- | --- | --- | @@ -4794,7 +4734,7 @@ Number of leading digits removed from plus code. Removing 2, 4 and 6 digits requ ### osd_right_sidebar_scroll -_// TODO_ +Scroll type for the right sidebar | Default | Min | Max | | --- | --- | --- | @@ -4884,7 +4824,7 @@ Sidebar horizontal offset from default position. Positive values move the sideba ### osd_sidebar_scroll_arrows -_// TODO_ +Show arrows for scrolling the sidebars | Default | Min | Max | | --- | --- | --- | @@ -4922,16 +4862,6 @@ Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt --- -### osd_stats_min_voltage_unit - -Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD stats. - -| Default | Min | Max | -| --- | --- | --- | -| BATTERY | | | - ---- - ### osd_stats_page_auto_swap_time Auto swap display time interval between disarm stats pages (seconds). Reverts to manual control when Roll stick used to change pages. Disabled when set to 0. @@ -4942,6 +4872,16 @@ Auto swap display time interval between disarm stats pages (seconds). Reverts to --- +### osd_stats_show_metric_efficiency + +Enabling this option will show metric efficiency statistics on the post flight stats screen. In addition to the efficiency statistics in your chosen units. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### osd_switch_indicator_one_channel RC Channel to use for OSD switch indicator 1. @@ -5122,26 +5062,6 @@ Allows to set type of PID controller used in control loop. Possible values: `NON --- -### pidsum_limit - -A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help - -| Default | Min | Max | -| --- | --- | --- | -| 500 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | - ---- - -### pidsum_limit_yaw - -A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help - -| Default | Min | Max | -| --- | --- | --- | -| 350 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | - ---- - ### pilot_name Pilot name @@ -5214,7 +5134,7 @@ Selection of pitot hardware. ### pitot_lpf_milli_hz -_// TODO_ +Pitot tube lowpass filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay | Default | Min | Max | | --- | --- | --- | @@ -5224,7 +5144,7 @@ _// TODO_ ### pitot_scale -_// TODO_ +Pitot tube scale factor | Default | Min | Max | | --- | --- | --- | @@ -5594,7 +5514,7 @@ Used to control when safehomes will be used. Possible values are `OFF`, `RTH` an ### sbus_sync_interval -_// TODO_ +SBUS sync interval in us. Default value is 3000us. Lower values may cause issues with some receivers. | Default | Min | Max | | --- | --- | --- | @@ -6214,7 +6134,7 @@ Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use th ### vtx_pit_mode_chan -_// TODO_ +Pit mode channel. | Default | Min | Max | | --- | --- | --- | @@ -6278,7 +6198,7 @@ These are values (in us) by how much RC input can be different before it's consi | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 100 | +| 2 | 0 | 100 | --- diff --git a/docs/boards/MAMBAH743_2022B.md b/docs/boards/MAMBAH743_2022B.md index 688c630cb8..d3d91e14c1 100644 --- a/docs/boards/MAMBAH743_2022B.md +++ b/docs/boards/MAMBAH743_2022B.md @@ -2,4 +2,8 @@ Contrary to what the documentation suggests, VTX power is actually on USER2. +# Dual Gyros + +INAV 7.1 changed the default gyro of the board from the gyro on SPI4 back to the one on SPI1. A new tagrt ```MAMBAH743_2022B_GYRO2``` was added to use gyro on SPI4, in case you suspect an issue with the gyro on SPI1, you can switch to the gyro on SPI4 by using the new target. + diff --git a/docs/development/Blackbox Internals.md b/docs/development/Blackbox Internals.md index bf7991c704..5e82979bca 100644 --- a/docs/development/Blackbox Internals.md +++ b/docs/development/Blackbox Internals.md @@ -566,7 +566,6 @@ The log end marker is an optional Event ("E") frame of type 0xFF whose payload i
  • Sticks
  • Switch_3D
  • Switch
  • -
  • Killswitch
  • Failsafe
  • Navigation
  • diff --git a/docs/development/Building in Docker.md b/docs/development/Building in Docker.md index 575614a95d..fe3723359f 100755 --- a/docs/development/Building in Docker.md +++ b/docs/development/Building in Docker.md @@ -1,5 +1,7 @@ # Building with Docker +> **On Windows building with this method is not advised and should be used only if Windows Linux Subsystem can not be used. In all other cases all Windows users should be using Linux Subsystem (WSL) instead** + Building with [Docker](https://www.docker.com/) is remarkably easy: an isolated container will hold all the needed compilation tools so that they won't interfere with your system and you won't need to install and manage them by yourself. You'll only need to have Docker itself [installed](https://docs.docker.com/install/). The first time that you'll run a build it will take a little more time than following executions since it will be building its base image first. Once this initial process is completed, the firmware will be always built immediately. diff --git a/docs/development/Building in Vagrant.md b/docs/development/Building in Vagrant.md index 99d479b7c1..c931f2ffcc 100644 --- a/docs/development/Building in Vagrant.md +++ b/docs/development/Building in Vagrant.md @@ -1,5 +1,7 @@ # Building with Vagrant +> **On Windows building with this method is not advised and should be used only if Windows Linux Subsystem can not be used. In all other cases all Windows users should be using Linux Subsystem (WSL) instead** + Setting up build environment with Vagrant is remarkably simple, but you still need to have some basic knowlage of your OS. ## Installing Vagrant diff --git a/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md index 9cee0ede25..217b0a05a4 100644 --- a/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md @@ -1,6 +1,6 @@ -# Building in Windows 10 with Linux subsystem [Recommended] +# Building in Windows 10/11 with Linux subsystem (WSL) [Recommended] -Linux subsystem for Windows 10 is probably the simplest way of building INAV under Windows 10. +Linux subsystem for Windows (WSL) 10/11 is probably the simplest way of building INAV under Windows. ## Setting up the environment @@ -9,7 +9,6 @@ run `windows features` enable `windows subsytem for linux` reboot - Install Ubuntu: 1. Go to Microsoft store https://www.microsoft.com/en-gb/store/b/home 1. Search and install most recent Ubuntu LTS version @@ -56,12 +55,12 @@ You can fix this with by remounting the drive using the following commands 1. `sudo umount /mnt/c` 2. `sudo mount -t drvfs C: /mnt/c -o metadata` -## Building (example): +## Building with Make (example): -For detailed build instrusctions see [Building in Linux](Building%20in%20Linux.md) +For detailed build instructions see [Building in Linux](Building%20in%20Linux.md) Launch Ubuntu: -Click Windows Start button then scroll and lauch "Ubuntu" +Click Windows Start button then scroll and launch "Ubuntu" Building from Ubuntu command line @@ -80,6 +79,39 @@ cd build make MATEKF722 ``` +## Building with Ninja (example): + +[Ninja](https://ninja-build.org/) is a popular cross-platform tool. It is both lightweight and executes parallel builds by default. It is advantageous to use this over the old _make_ method. There are detailed instructions for building with Ninja in [Building in Linux](Building%20in%20Linux.md#building-with-ninja). + +Launch Ubuntu: +Click Windows Start button. Then scroll and launch **Ubuntu**. + +> [!TIP] +> Before using Ninja, you will need to install it. From the Ubuntu command prompt type `sudo apt-get install ninja-build -y` and press enter. + +Building from the command line: + +First, change to the INAV directory with +```cd /mnt/c/inav``` + +Before building, you will need to prepare the build environment. You only need to do this once, unless you reinstall WSL or cmake. + +``` +mkdir build +cd build +cmake -GNinja .. +``` + +From then on, you can build your target by calling the following from inside the build directory. +``` +ninja MATEKF722 +``` + +If you want to build multiple targets. You can use: +``` +ninja MATEKF722 MATEKF405SE SPEEDYBEEF405 +``` + ## Updating the documents ``` cd /mnt/c/inav diff --git a/docs/development/Building in Windows 10 or 11 with MSYS2.md b/docs/development/Building in Windows 10 or 11 with MSYS2.md index 2d7f967b50..bc55be7410 100644 --- a/docs/development/Building in Windows 10 or 11 with MSYS2.md +++ b/docs/development/Building in Windows 10 or 11 with MSYS2.md @@ -1,4 +1,7 @@ # Building in Windows with MSYS2 + +> **Building with this method is not advised and should be used only if Windows Linux Subsystem can not be used. In all other cases all Windows users should be using Linux Subsystem (WSL) instead** + - This environment does not require installing WSL, which may not be available or would get in the way of other virtualization and/or anti-cheat software - It is also much faster to install and get set up because of its small size(~3.65 GB total after building hex file as of 6.0.0) ## Setting up the environment diff --git a/docs/development/Building in Windows light.md b/docs/development/[Deprecated] Building in Windows light.md similarity index 96% rename from docs/development/Building in Windows light.md rename to docs/development/[Deprecated] Building in Windows light.md index e05b2c92f3..de4659e745 100644 --- a/docs/development/Building in Windows light.md +++ b/docs/development/[Deprecated] Building in Windows light.md @@ -1,4 +1,8 @@ # Building in windows light [Deprecated] + +> **Building with this method is deprecated and not advised. All Windows users should be using +Linux Subsystem (WSL) instead** + no cygwin and no path changes ## Install Git for windows diff --git a/docs/development/serial_printf_debugging.md b/docs/development/serial_printf_debugging.md index 3804c948e9..590bdb7e6b 100644 --- a/docs/development/serial_printf_debugging.md +++ b/docs/development/serial_printf_debugging.md @@ -98,10 +98,13 @@ LOG_BUF_DEBUG(TEMPERATURE, &tstruct, sizeof(tstruct)); Log messages are transmitted through the `FUNCTION_LOG` serial port as MSP messages (`MSP_DEBUGMSG`). It is possible to use any serial terminal to display these messages, however it is advisable to use an application that understands `MSP_DEBUGMSG` in order to maintain readability (in a raw serial terminal the MSP message envelope may result in the display of strange characters). `MSP_DEBUGMSG` aware applications include: -* [msp-tool](https://github.com/fiam/msp-tool) -* [mwp](https://github.com/stronnag/mwptools) * [dbg-tool](https://codeberg.org/stronnag/dbg-tool) * [INAV Configurator](https://github.com/iNavFlight/inav-configurator) +* [mwp](https://github.com/stronnag/mwptools) + +In addtion: + +* [msp-tool](https://github.com/fiam/msp-tool) is obsolete and has limited OS support. For example, with the final lines of `src/main/fc/fc_init.c` set to: @@ -121,10 +124,16 @@ set log_topics = 4294967295 The output will be formatted as follows: ``` -# msp-tool -[DEBUG] [ 3.967] Init is complete +# dbg-tool +[dbg-tool] 12:46:49.909079 DBG: [ 3.967] Init is complete + # mwp (stderr log file) 2020-02-02T19:09:02+0000 DEBUG:[ 3.968] Init is complete + +# msp-tool +[DEBUG] [ 3.967] Init is complete ``` -The numeric value in square brackets is the FC uptime in seconds. +For the Configurator, debug messages are shown in the developer console log. + +Note: The numeric value in square brackets is the FC uptime in seconds. diff --git a/docs/policies/NEW_HARDWARE_POLICY.md b/docs/policies/NEW_HARDWARE_POLICY.md index 1e97413480..f11601b838 100644 --- a/docs/policies/NEW_HARDWARE_POLICY.md +++ b/docs/policies/NEW_HARDWARE_POLICY.md @@ -23,8 +23,8 @@ New targets are accepted into INAV code if any of the following conditions is sa 3. The new target must meet the following minimal requirements: * On-board sensors include at least the IMU (gyroscope + accelerometer) - * At least 2 hardware serial ports are available with both TX and RX pins - * At least 512K of firmware flash memory and at least of 64K of RAM available + * At least 3 hardware serial ports are available with both TX and RX pads. 2 serial ports may be accepted if there is an onboard serial RX. + * At least 512K of firmware flash memory and at least of 128K of RAM available * At least one I2C bus broken out (SCL and SDA pins) and not shared with other functions ## New hardware support diff --git a/readme.md b/readme.md index 724f1a88c1..a70c42d4c8 100644 --- a/readme.md +++ b/readme.md @@ -1,6 +1,6 @@ # INAV - navigation capable flight controller -# PSA +# F411 PSA > INAV no longer accepts targets based on STM32 F411 MCU. @@ -8,28 +8,50 @@ ![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png) +# PosHold, Navigation and RTH without compass PSA + +Attention all drone pilots and enthusiasts, + +Are you ready to take your flights to new heights with INAV 7.1? We've got some important information to share with you. + +INAV 7.1 brings an exciting update to navigation capabilities. Now, you can soar through the skies, navigate waypoints, and even return to home without relying on a compass. Yes, you heard that right! But before you launch into the air, there's something crucial to consider. + +While INAV 7.1 may not require a compass for basic navigation functions, we strongly advise you to install one for optimal flight performance. Here's why: + +🛰️ Better Flight Precision: A compass provides essential data for accurate navigation, ensuring smoother and more precise flight paths. + +🌐 Enhanced Reliability: With a compass onboard, your drone can maintain stability even in challenging environments, low speeds and strong wind. + +🚀 Minimize Risks: Although INAV 7.1 can get you where you need to go without a compass, flying without one may result in a bumpier ride and increased risk of drift or inaccurate positioning. + +Remember, safety and efficiency are paramount when operating drones. By installing a compass, you're not just enhancing your flight experience, but also prioritizing safety for yourself and those around you. + +So, before you take off on your next adventure, make sure to equip your drone with a compass. It's the smart choice for smoother flights and better navigation. + +Fly safe, fly smart with INAV 7.1 and a compass by your side! + # INAV Community * [INAV Discord Server](https://discord.gg/peg2hhbYwN) * [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial) -* [INAV Official on Telegram](https://t.me/INAVFlight) ## Features -* Runs on the most popular F4, F7 and H7 flight controllers +* Runs on the most popular F4, AT32, F7 and H7 flight controllers * On Screen Display (OSD) - both character and pixel style * DJI OSD integration: all elements, system messages and warnings * Outstanding performance out of the box * Position Hold, Altitude Hold, Return To Home and Waypoint Missions * Excellent support for fixed wing UAVs: airplanes, flying wings +* Blackbox flight recorder logging +* Advanced gyro filtering * Fully configurable mixer that allows to run any hardware you want: multirotor, fixed wing, rovers, boats and other experimental devices * Multiple sensor support: GPS, Pitot tube, sonar, lidar, temperature, ESC with BlHeli_32 telemetry +* Logic Conditions, Global Functions and Global Variables: you can program INAV with a GUI * SmartAudio and IRC Tramp VTX support -* Blackbox flight recorder logging * Telemetry: SmartPort, FPort, MAVlink, LTM, CRSF * Multi-color RGB LED Strip support -* Advanced gyro filtering -* Logic Conditions, Global Functions and Global Variables: you can program INAV with a GUI +* On Screen Display (OSD) - both character and pixel style * And many more! For a list of features, changes and some discussion please review consult the releases [page](https://github.com/iNavFlight/inav/releases) and the documentation. @@ -52,10 +74,6 @@ Command line tools (`blackbox_decode`, `blackbox_render`) for Blackbox log conve Users of EdgeTX and OpenTX radios (Taranis, Horus, Jumper, Radiomaster, Nirvana) can use INAV OpenTX Telemetry Widget screen. Software and installation instruction are available here: [https://github.com/iNavFlight/OpenTX-Telemetry-Widget](https://github.com/iNavFlight/OpenTX-Telemetry-Widget) -### INAV magnetometer alignment helper - -[INAV Magnetometer Alignment helper](https://kernel-machine.github.io/INavMagAlignHelper/) allows to align INAV magnetometer despite position and orientation. This simplifies the process of INAV setup on multirotors with tilted GPS modules. - ### OSD layout Copy, Move, or Replace helper tool [Easy INAV OSD switcher tool](https://www.mrd-rc.com/tutorials-tools-and-testing/useful-tools/inav-osd-switcher-tool/) allows you to easily switch your OSD layouts around in INAV. Choose the from and to OSD layouts, and the method of transfering the layouts. diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 98a43854cf..cba13db687 100755 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -237,6 +237,8 @@ main_sources(COMMON_SRC drivers/rangefinder/rangefinder_us42.h drivers/rangefinder/rangefinder_tof10120_i2c.c drivers/rangefinder/rangefinder_tof10120_i2c.h + drivers/rangefinder/rangefinder_teraranger_evo.c + drivers/rangefinder/rangefinder_teraranger_evo.h drivers/resource.c drivers/resource.h diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 453b8fda0c..b16f03de77 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1844,9 +1844,9 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", systemConfig()->craftName); BLACKBOX_PRINT_HEADER_LINE("P interval", "%u/%u", blackboxConfig()->rate_num, blackboxConfig()->rate_denom); BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", getThrottleIdleValue()); - BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle); + BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", getMaxThrottle()); BLACKBOX_PRINT_HEADER_LINE("gyro_scale", "0x%x", castFloatBytesToInt(1.0f)); - BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),motorConfig()->maxthrottle); + BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),getMaxThrottle()); BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc.dev.acc_1G); #ifdef USE_ADC @@ -1915,9 +1915,8 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_type", "%d", pidProfile()->dterm_lpf_type); BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband); BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband); - BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf); + BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", GYRO_LPF_256HZ); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_hz", "%d", gyroConfig()->gyro_main_lpf_hz); - BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_type", "%d", gyroConfig()->gyro_main_lpf_type); #ifdef USE_DYNAMIC_FILTERS BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchQ", "%d", gyroConfig()->dynamicGyroNotchQ); BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchMinHz", "%d", gyroConfig()->dynamicGyroNotchMinHz); @@ -1940,8 +1939,6 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("waypoints", "%d,%d", getWaypointCount(),isWaypointListValid()); BLACKBOX_PRINT_HEADER_LINE("acc_notch_hz", "%d", accelerometerConfig()->acc_notch_hz); BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff); - BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit); - BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", pidProfile()->pidSumLimitYaw); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitRollPitch", "%d", pidProfile()->axisAccelerationLimitRollPitch); #ifdef USE_RPM_FILTER diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 7a6f04149d..3e6adb719b 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -35,6 +35,10 @@ #include "config/parameter_group.h" #include "config/parameter_group_ids.h" +#ifdef USE_SDCARD +#include "drivers/sdcard/sdcard.h" +#endif + #include "io/asyncfatfs/asyncfatfs.h" #include "io/flashfs.h" #include "io/serial.h" @@ -507,6 +511,36 @@ bool isBlackboxDeviceFull(void) } } +bool isBlackboxDeviceWorking(void) +{ + switch (blackboxConfig()->device) { + case BLACKBOX_DEVICE_SERIAL: + return blackboxPort != NULL; +#ifdef USE_SDCARD + case BLACKBOX_DEVICE_SDCARD: + return sdcard_isInserted() && sdcard_isFunctional() && (afatfs_getFilesystemState() == AFATFS_FILESYSTEM_STATE_READY); +#endif +#ifdef USE_FLASHFS + case BLACKBOX_DEVICE_FLASH: + return flashfsIsReady(); +#endif + default: + return false; + } +} + +int32_t blackboxGetLogNumber(void) +{ + switch (blackboxConfig()->device) { +#ifdef USE_SDCARD + case BLACKBOX_DEVICE_SDCARD: + return blackboxSDCard.largestLogFileNumber; +#endif + default: + return -1; + } +} + /** * Call once every loop iteration in order to maintain the global blackboxHeaderBudget with the number of bytes we can * transmit this iteration. diff --git a/src/main/blackbox/blackbox_io.h b/src/main/blackbox/blackbox_io.h index e71fdadca3..d143b72098 100644 --- a/src/main/blackbox/blackbox_io.h +++ b/src/main/blackbox/blackbox_io.h @@ -67,6 +67,8 @@ bool blackboxDeviceBeginLog(void); bool blackboxDeviceEndLog(bool retainLog); bool isBlackboxDeviceFull(void); +bool isBlackboxDeviceWorking(void); +int32_t blackboxGetLogNumber(void); void blackboxReplenishHeaderBudget(void); blackboxBufferReserveStatus_e blackboxDeviceReserveBufferSpace(int32_t bytes); diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index 7612ec4418..f8c75ab480 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -137,6 +137,30 @@ static long cmsx_PidWriteback(const OSD_Entry *self) return 0; } +static const OSD_Entry cmsx_menuEzTuneEntries[] = +{ + OSD_LABEL_DATA_ENTRY("-- EZTUNE --", profileIndexString), + + OSD_SETTING_ENTRY("ENABLED", SETTING_EZ_ENABLED), + OSD_SETTING_ENTRY("FILTER HZ", SETTING_EZ_FILTER_HZ), + OSD_SETTING_ENTRY("RATIO", SETTING_EZ_AXIS_RATIO), + OSD_SETTING_ENTRY("RESP.", SETTING_EZ_RESPONSE), + OSD_SETTING_ENTRY("DAMP.", SETTING_EZ_DAMPING), + OSD_SETTING_ENTRY("STAB.", SETTING_EZ_STABILITY), + OSD_SETTING_ENTRY("AGGR.", SETTING_EZ_AGGRESSIVENESS), + OSD_SETTING_ENTRY("RATE", SETTING_EZ_RATE), + OSD_SETTING_ENTRY("EXPO", SETTING_EZ_EXPO), + + OSD_BACK_AND_END_ENTRY, +}; + +static const CMS_Menu cmsx_menuEzTune = { + .onEnter = NULL, + .onExit = NULL, + .onGlobalExit = NULL, + .entries = cmsx_menuEzTuneEntries +}; + static const OSD_Entry cmsx_menuPidEntries[] = { OSD_LABEL_DATA_ENTRY("-- PID --", profileIndexString), @@ -398,7 +422,6 @@ static const CMS_Menu cmsx_menuProfileOther = { static const OSD_Entry cmsx_menuFilterPerProfileEntries[] = { OSD_LABEL_DATA_ENTRY("-- FILTERING --", profileIndexString), - OSD_SETTING_ENTRY("HARDWARE LPF", SETTING_GYRO_HARDWARE_LPF), OSD_SETTING_ENTRY("GYRO MAIN", SETTING_GYRO_MAIN_LPF_HZ), OSD_SETTING_ENTRY("DTERM LPF", SETTING_DTERM_LPF_HZ), #ifdef USE_DYNAMIC_FILTERS @@ -458,6 +481,7 @@ static const OSD_Entry cmsx_menuImuEntries[] = // Profile dependent OSD_UINT8_CALLBACK_ENTRY("PID PROF", cmsx_profileIndexOnChange, (&(const OSD_UINT8_t){ &tmpProfileIndex, 1, MAX_PROFILE_COUNT, 1})), + OSD_SUBMENU_ENTRY("EZTUNE", &cmsx_menuEzTune), OSD_SUBMENU_ENTRY("PID", &cmsx_menuPid), OSD_SUBMENU_ENTRY("PID ALTMAG", &cmsx_menuPidAltMag), OSD_SUBMENU_ENTRY("PID GPSNAV", &cmsx_menuPidGpsnav), diff --git a/src/main/common/maths.h b/src/main/common/maths.h index c681080500..f3f2fd6274 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -56,6 +56,8 @@ #define RADIANS_TO_CENTIDEGREES(angle) (((angle) * 100.0f) / RAD) #define CENTIDEGREES_TO_RADIANS(angle) (((angle) * 0.01f) * RAD) +#define MILLIMETERS_TO_CENTIMETERS(mm) (mm / 10.0f) + #define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048f) #define CENTIMETERS_TO_FEET(cm) (cm / 30.48f) #define CENTIMETERS_TO_METERS(cm) (cm * 0.01f) @@ -65,6 +67,8 @@ #define METERS_TO_MILES(m) (m / 1609.344f) #define METERS_TO_NAUTICALMILES(m) (m / 1852.00f) +#define MWH_TO_WH(mWh) (mWh / 1000.0f) + #define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363f) #define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f) #define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f) diff --git a/src/main/drivers/accgyro/accgyro_bmi160.c b/src/main/drivers/accgyro/accgyro_bmi160.c index cadaeb22da..fc7fb472b5 100644 --- a/src/main/drivers/accgyro/accgyro_bmi160.c +++ b/src/main/drivers/accgyro/accgyro_bmi160.c @@ -108,15 +108,6 @@ static const gyroFilterAndRateConfig_t gyroConfigs[] = { { GYRO_LPF_256HZ, 3200, { BMI160_BWP_OSR4 | BMI160_ODR_3200_Hz} }, { GYRO_LPF_256HZ, 1600, { BMI160_BWP_OSR2 | BMI160_ODR_1600_Hz} }, { GYRO_LPF_256HZ, 800, { BMI160_BWP_NORMAL | BMI160_ODR_800_Hz } }, - - { GYRO_LPF_188HZ, 800, { BMI160_BWP_OSR2 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 128 Hz - { GYRO_LPF_188HZ, 400, { BMI160_BWP_NORMAL | BMI160_ODR_400_Hz } }, // ODR = 400 Hz, LPF = 137 Hz - - { GYRO_LPF_98HZ, 800, { BMI160_BWP_OSR4 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 63 Hz - { GYRO_LPF_98HZ, 400, { BMI160_BWP_OSR2 | BMI160_ODR_400_Hz } }, // ODR = 400 Hz, LPF = 68 Hz - - { GYRO_LPF_42HZ, 800, { BMI160_BWP_OSR4 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 63 Hz - { GYRO_LPF_42HZ, 400, { BMI160_BWP_OSR4 | BMI160_ODR_400_Hz } }, // ODR = 400 Hz, LPF = 34 Hz }; static void bmi160AccAndGyroInit(gyroDev_t *gyro) diff --git a/src/main/drivers/accgyro/accgyro_bmi270.c b/src/main/drivers/accgyro/accgyro_bmi270.c index 3e1db22253..1dc4d3fc59 100644 --- a/src/main/drivers/accgyro/accgyro_bmi270.c +++ b/src/main/drivers/accgyro/accgyro_bmi270.c @@ -134,15 +134,6 @@ static const gyroFilterAndRateConfig_t gyroConfigs[] = { { GYRO_LPF_256HZ, 3200, { BMI270_BWP_OSR4 | BMI270_ODR_3200} }, { GYRO_LPF_256HZ, 1600, { BMI270_BWP_OSR2 | BMI270_ODR_1600} }, { GYRO_LPF_256HZ, 800, { BMI270_BWP_NORM | BMI270_ODR_800 } }, - - { GYRO_LPF_188HZ, 800, { BMI270_BWP_OSR2 | BMI270_ODR_800 } }, - { GYRO_LPF_188HZ, 400, { BMI270_BWP_NORM | BMI270_ODR_400 } }, - - { GYRO_LPF_98HZ, 800, { BMI270_BWP_OSR4 | BMI270_ODR_800 } }, - { GYRO_LPF_98HZ, 400, { BMI270_BWP_OSR2 | BMI270_ODR_400 } }, - - { GYRO_LPF_42HZ, 800, { BMI270_BWP_OSR4 | BMI270_ODR_800 } }, - { GYRO_LPF_42HZ, 400, { BMI270_BWP_OSR4 | BMI270_ODR_400 } }, }; // Toggle the CS to switch the device into SPI mode. diff --git a/src/main/drivers/accgyro/accgyro_icm42605.c b/src/main/drivers/accgyro/accgyro_icm42605.c index 082b31540e..13bc22fcee 100644 --- a/src/main/drivers/accgyro/accgyro_icm42605.c +++ b/src/main/drivers/accgyro/accgyro_icm42605.c @@ -198,21 +198,6 @@ static const gyroFilterAndRateConfig_t icm42605GyroConfigs[] = { { GYRO_LPF_256HZ, 2000, { 3, 5 } }, /* 250 Hz LPF */ { GYRO_LPF_256HZ, 1000, { 1, 6 } }, /* 250 Hz LPF */ { GYRO_LPF_256HZ, 500, { 0, 15 } }, /* 250 Hz LPF */ - - { GYRO_LPF_188HZ, 1000, { 3, 6 } }, /* 125 HZ */ - { GYRO_LPF_188HZ, 500, { 1, 15 } }, /* 125 HZ */ - - { GYRO_LPF_98HZ, 1000, { 4, 6 } }, /* 100 HZ*/ - { GYRO_LPF_98HZ, 500, { 2, 15 } }, /* 100 HZ*/ - - { GYRO_LPF_42HZ, 1000, { 6, 6 } }, /* 50 HZ */ - { GYRO_LPF_42HZ, 500, { 4, 15 } }, - - { GYRO_LPF_20HZ, 1000, { 7, 6 } }, /* 25 HZ */ - { GYRO_LPF_20HZ, 500, { 6, 15 } }, - - { GYRO_LPF_10HZ, 1000, { 7, 6 } }, /* 25 HZ */ - { GYRO_LPF_10HZ, 500, { 7, 15 } } /* 12.5 HZ */ }; static void icm42605AccAndGyroInit(gyroDev_t *gyro) diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c index 710865436b..a52606946b 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.c +++ b/src/main/drivers/accgyro/accgyro_mpu.c @@ -50,21 +50,6 @@ static const gyroFilterAndRateConfig_t mpuGyroConfigs[] = { { GYRO_LPF_256HZ, 1000, { MPU_DLPF_256HZ, 7 } }, { GYRO_LPF_256HZ, 666, { MPU_DLPF_256HZ, 11 } }, { GYRO_LPF_256HZ, 500, { MPU_DLPF_256HZ, 15 } }, - - { GYRO_LPF_188HZ, 1000, { MPU_DLPF_188HZ, 0 } }, - { GYRO_LPF_188HZ, 500, { MPU_DLPF_188HZ, 1 } }, - - { GYRO_LPF_98HZ, 1000, { MPU_DLPF_98HZ, 0 } }, - { GYRO_LPF_98HZ, 500, { MPU_DLPF_98HZ, 1 } }, - - { GYRO_LPF_42HZ, 1000, { MPU_DLPF_42HZ, 0 } }, - { GYRO_LPF_42HZ, 500, { MPU_DLPF_42HZ, 1 } }, - - { GYRO_LPF_20HZ, 1000, { MPU_DLPF_20HZ, 0 } }, - { GYRO_LPF_20HZ, 500, { MPU_DLPF_20HZ, 1 } }, - - { GYRO_LPF_10HZ, 1000, { MPU_DLPF_10HZ, 0 } }, - { GYRO_LPF_10HZ, 500, { MPU_DLPF_10HZ, 1 } } }; const gyroFilterAndRateConfig_t * mpuChooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz) diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index eca213b721..6c2cedaff0 100644 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -135,6 +135,7 @@ typedef enum { DEVHW_VL53L1X, DEVHW_US42, DEVHW_TOF10120_I2C, + DEVHW_TERARANGER_EVO_I2C, /* Other hardware */ DEVHW_MS4525, // Pitot meter diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index 5a501fbc5e..cb484937d3 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -26,4 +26,4 @@ #else #define NVIC_PRIORITY_GROUPING NVIC_PriorityGroup_4 #endif -#endif +#endif \ No newline at end of file diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index 2437b9d3c2..91cdcbb5f6 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -178,6 +178,8 @@ #define SYM_ALERT 0xDD // 221 General alert symbol #define SYM_TERRAIN_FOLLOWING 0xFB // 251 Terrain following (also Alt adjust) #define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error +#define SYM_ADSB 0xFD // 253 ADBS +#define SYM_BLACKBOX 0xFE // 254 Blackbox #define SYM_ADSB 0xFD // 253 ADSB diff --git a/src/main/drivers/pinio.c b/src/main/drivers/pinio.c index 69968ddb7d..3e89e5fccc 100644 --- a/src/main/drivers/pinio.c +++ b/src/main/drivers/pinio.c @@ -100,16 +100,14 @@ void pinioInit(void) } } -void pinioSet(int index, bool on) +void pinioSet(int index, bool newState) { - const bool newState = on ^ pinioRuntime[index].inverted; - if (!pinioRuntime[index].io) { return; } if (newState != pinioRuntime[index].state) { - IOWrite(pinioRuntime[index].io, newState); + IOWrite(pinioRuntime[index].io, newState ^ pinioRuntime[index].inverted); pinioRuntime[index].state = newState; } } diff --git a/src/main/drivers/pinio.h b/src/main/drivers/pinio.h index baecc35a18..a1de21c12d 100644 --- a/src/main/drivers/pinio.h +++ b/src/main/drivers/pinio.h @@ -38,4 +38,4 @@ extern const pinioHardware_t pinioHardware[]; extern const int pinioHardwareCount; void pinioInit(void); -void pinioSet(int index, bool on); +void pinioSet(int index, bool newState); diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index d898b1595f..d48f38679e 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -172,6 +172,8 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timHw, resourceOwner const IO_t io = IOGetByTag(timHw->tag); IOInit(io, owner, RESOURCE_OUTPUT, allocatedOutputPortCount); + pwmOutConfigTimer(p, tch, hz, period, value); + if (enableOutput) { IOConfigGPIOAF(io, IOCFG_AF_PP, timHw->alternateFunction); } @@ -181,7 +183,6 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timHw, resourceOwner IOLo(io); } - pwmOutConfigTimer(p, tch, hz, period, value); return p; } diff --git a/src/main/drivers/rangefinder/rangefinder_teraranger_evo.c b/src/main/drivers/rangefinder/rangefinder_teraranger_evo.c new file mode 100644 index 0000000000..1c397f5a38 --- /dev/null +++ b/src/main/drivers/rangefinder/rangefinder_teraranger_evo.c @@ -0,0 +1,128 @@ +/* + * 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 . + */ + +#include +#include + +#include "platform.h" + +#include "common/maths.h" + +#if defined(USE_RANGEFINDER) && defined(USE_RANGEFINDER_TERARANGER_EVO_I2C) + +#include "build/build_config.h" + +#include "common/crc.h" + +#include "drivers/time.h" +#include "drivers/bus_i2c.h" + +#include "drivers/rangefinder/rangefinder.h" +#include "drivers/rangefinder/rangefinder_teraranger_evo.h" + +#include "build/debug.h" + +#define TERARANGER_EVO_DETECTION_CONE_DECIDEGREES 900 +#define TERARANGER_EVO_DETECTION_CONE_EXTENDED_DECIDEGREES 900 + +#define TERARANGER_EVO_I2C_ADDRESS 0x31 +#define TERARANGER_EVO_I2C_REGISTRY_TRIGGER_READING 0x00 // Write this command to the TeraRanger Evo and after a wait of approximately 500us read the 3 byte distance response +#define TERARANGER_EVO_I2C_REGISTRY_WHO_AM_I 0x01 // Write this value to TeraRanger Evo via I2C and the device responds with 0xA +#define TERARANGER_EVO_I2C_REGISTRY_CHANGE_BASE_ADDR 0xA2 // This command assigns a base address that will be memorised by the TerRanger Evo ie. power cycling the Evo will not restore the default I2C address. + +#define TERARANGER_EVO_I2C_ANSWER_WHO_AM_I 0xA1 + +#define TERARANGER_EVO_VALUE_TOO_CLOSE 0x0000 +#define TERARANGER_EVO_VALUE_OUT_OF_RANGE 0xffff + +static int16_t minimumReadingIntervalMs = 50; + uint8_t triggerValue[0]; +volatile int32_t teraRangerMeasurementCm; +static uint32_t timeOfLastMeasurementMs; +static uint8_t dataBuff[3]; + +static void teraRangerInit(rangefinderDev_t *rangefinder){ + busWriteBuf(rangefinder->busDev, TERARANGER_EVO_I2C_REGISTRY_TRIGGER_READING, triggerValue, 1); +} + +void teraRangerUpdate(rangefinderDev_t *rangefinder){ + if (busReadBuf(rangefinder->busDev, TERARANGER_EVO_I2C_REGISTRY_TRIGGER_READING, dataBuff, 3)) { + teraRangerMeasurementCm = MILLIMETERS_TO_CENTIMETERS(((int32_t)dataBuff[0] << 8 | (int32_t)dataBuff[1])); + + if(dataBuff[2] == crc8_update(0, &dataBuff, 2)){ + if (teraRangerMeasurementCm == TERARANGER_EVO_VALUE_TOO_CLOSE || teraRangerMeasurementCm == TERARANGER_EVO_VALUE_OUT_OF_RANGE) { + teraRangerMeasurementCm = RANGEFINDER_OUT_OF_RANGE; + } + } + } else { + teraRangerMeasurementCm = RANGEFINDER_HARDWARE_FAILURE; + } + + const timeMs_t timeNowMs = millis(); + if (timeNowMs > timeOfLastMeasurementMs + minimumReadingIntervalMs) { + // measurement repeat interval should be greater than minimumReadingIntervalMs + // to avoid interference between connective measurements. + timeOfLastMeasurementMs = timeNowMs; + busWriteBuf(rangefinder->busDev, TERARANGER_EVO_I2C_ADDRESS, triggerValue, 1); + } +} + + +int32_t teraRangerGetDistance(rangefinderDev_t *rangefinder){ + UNUSED(rangefinder); + return teraRangerMeasurementCm; +} + +static bool deviceDetect(busDevice_t * busDev){ + for (int retry = 0; retry < 5; retry++) { + uint8_t whoIamResult; + + delay(150); + + bool ack = busRead(busDev, TERARANGER_EVO_I2C_REGISTRY_WHO_AM_I, &whoIamResult); + if (ack && whoIamResult == TERARANGER_EVO_I2C_ANSWER_WHO_AM_I) { + return true; + } + }; + + return false; +} + +bool teraRangerDetect(rangefinderDev_t *rangefinder){ + rangefinder->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_TERARANGER_EVO_I2C, 0, OWNER_RANGEFINDER); + if (rangefinder->busDev == NULL) { + return false; + } + + if (!deviceDetect(rangefinder->busDev)) { + busDeviceDeInit(rangefinder->busDev); + return false; + } + + rangefinder->delayMs = RANGEFINDER_TERA_EVO_TASK_PERIOD_MS; + rangefinder->maxRangeCm = RANGEFINDER_TERA_EVO_MAX_RANGE_CM; + rangefinder->detectionConeDeciDegrees = TERARANGER_EVO_DETECTION_CONE_DECIDEGREES; + rangefinder->detectionConeExtendedDeciDegrees = TERARANGER_EVO_DETECTION_CONE_EXTENDED_DECIDEGREES; + + rangefinder->init = &teraRangerInit; + rangefinder->update = &teraRangerUpdate; + rangefinder->read = &teraRangerGetDistance; + + return true; +} + +#endif \ No newline at end of file diff --git a/src/main/drivers/rangefinder/rangefinder_teraranger_evo.h b/src/main/drivers/rangefinder/rangefinder_teraranger_evo.h new file mode 100644 index 0000000000..be7618eca9 --- /dev/null +++ b/src/main/drivers/rangefinder/rangefinder_teraranger_evo.h @@ -0,0 +1,29 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ +#pragma once + +#define RANGEFINDER_TERA_EVO_TASK_PERIOD_MS 70 +#define RANGEFINDER_TERA_EVO_MAX_RANGE_CM 600 // max distance depends on model https://www.terabee.com/sensors-modules/lidar-tof-range-finders/#individual-distance-measurement-sensors + +bool teraRangerDetect(rangefinderDev_t *dev); diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 10c0a1e717..539a4ea93f 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -21,7 +21,6 @@ #include void systemInit(void); -void systemClockSetup(uint8_t cpuUnderclock); typedef enum { FAILURE_DEVELOPER = 0, diff --git a/src/main/drivers/system_at32f43x.c b/src/main/drivers/system_at32f43x.c index fadcfe239a..340058e183 100644 --- a/src/main/drivers/system_at32f43x.c +++ b/src/main/drivers/system_at32f43x.c @@ -114,12 +114,6 @@ uint32_t systemBootloaderAddress(void) //return system_isr_vector_table_base; } -void systemClockSetup(uint8_t cpuUnderclock) -{ - (void)cpuUnderclock; - // This is a stub -} - void systemInit(void) { //config system clock to 288mhz usb 48mhz diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 5cb9ccfd20..9863fa3c8c 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -143,12 +143,6 @@ uint32_t systemBootloaderAddress(void) return 0x1FFF0000; } -void systemClockSetup(uint8_t cpuUnderclock) -{ - (void)cpuUnderclock; - // This is a stub -} - void systemInit(void) { SetSysClock(); diff --git a/src/main/drivers/system_stm32f7xx.c b/src/main/drivers/system_stm32f7xx.c index 9c39be23e8..da58cf24b5 100644 --- a/src/main/drivers/system_stm32f7xx.c +++ b/src/main/drivers/system_stm32f7xx.c @@ -66,12 +66,6 @@ uint32_t systemBootloaderAddress(void) return 0x1FF00000; } -void systemClockSetup(uint8_t cpuUnderclock) -{ - (void)cpuUnderclock; - // This is a stub -} - void systemInit(void) { checkForBootLoaderRequest(); diff --git a/src/main/drivers/system_stm32h7xx.c b/src/main/drivers/system_stm32h7xx.c index a1de36f2c2..af3ea72e2a 100644 --- a/src/main/drivers/system_stm32h7xx.c +++ b/src/main/drivers/system_stm32h7xx.c @@ -60,12 +60,6 @@ uint32_t systemBootloaderAddress(void) #endif } -void systemClockSetup(uint8_t cpuUnderclock) -{ - (void)cpuUnderclock; - // This is a stub -} - void systemInit(void) { checkForBootLoaderRequest(); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index ea09c5776d..4834558341 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3359,6 +3359,7 @@ static void cliDumpProfile(uint8_t profileIndex, uint8_t dumpMask) cliPrintLinef("profile %d\r\n", getConfigProfile() + 1); dumpAllValues(PROFILE_VALUE, dumpMask); dumpAllValues(CONTROL_RATE_VALUE, dumpMask); + dumpAllValues(EZ_TUNE_VALUE, dumpMask); } static void cliBatteryProfile(char *cmdline) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 52cb06f81a..c9a50c60a2 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -115,9 +115,6 @@ PG_RESET_TEMPLATE(systemConfig_t, systemConfig, #endif #ifdef USE_I2C .i2c_speed = SETTING_I2C_SPEED_DEFAULT, -#endif -#ifdef USE_UNDERCLOCK - .cpuUnderclock = SETTING_CPU_UNDERCLOCK_DEFAULT, #endif .throttle_tilt_compensation_strength = SETTING_THROTTLE_TILT_COMP_STR_DEFAULT, // 0-100, 0 - disabled .craftName = SETTING_NAME_DEFAULT, diff --git a/src/main/fc/config.h b/src/main/fc/config.h index bafa5c0cbe..ddb6a826b8 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -76,9 +76,6 @@ typedef struct systemConfig_s { #endif #ifdef USE_I2C uint8_t i2c_speed; -#endif -#ifdef USE_UNDERCLOCK - uint8_t cpuUnderclock; #endif uint8_t throttle_tilt_compensation_strength; // the correction that will be applied at throttle_correction_angle. char craftName[MAX_NAME_LENGTH + 1]; diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 0d0863760d..bede8929fe 100644 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -237,7 +237,7 @@ static void updateArmingStatus(void) /* CHECK: pitch / roll sticks centered when NAV_LAUNCH_MODE enabled */ if (isNavLaunchEnabled()) { - if (isRollPitchStickDeflected(rcControlsConfig()->control_deadband)) { + if (isRollPitchStickDeflected(CONTROL_DEADBAND)) { ENABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED); } else { DISABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED); @@ -307,14 +307,6 @@ static void updateArmingStatus(void) DISABLE_ARMING_FLAG(ARMING_DISABLED_BOXFAILSAFE); } - /* CHECK: BOXKILLSWITCH */ - if (IS_RC_MODE_ACTIVE(BOXKILLSWITCH)) { - ENABLE_ARMING_FLAG(ARMING_DISABLED_BOXKILLSWITCH); - } - else { - DISABLE_ARMING_FLAG(ARMING_DISABLED_BOXKILLSWITCH); - } - /* CHECK: Do not allow arming if Servo AutoTrim is enabled */ if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) { ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); @@ -513,7 +505,7 @@ bool emergInflightRearmEnabled(void) timeMs_t currentTimeMs = millis(); emergRearmStabiliseTimeout = 0; - if ((lastDisarmReason != DISARM_SWITCH && lastDisarmReason != DISARM_KILLSWITCH) || + if ((lastDisarmReason != DISARM_SWITCH) || (currentTimeMs > US2MS(lastDisarmTimeUs) + EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS)) { return false; } @@ -1020,6 +1012,10 @@ float getFlightTime(void) return US2S(flightTime); } +void resetFlightTime(void) { + flightTime = 0; +} + float getArmTime(void) { return US2S(armTime); diff --git a/src/main/fc/fc_core.h b/src/main/fc/fc_core.h index c66a0050ba..ee5764696d 100644 --- a/src/main/fc/fc_core.h +++ b/src/main/fc/fc_core.h @@ -27,7 +27,6 @@ typedef enum disarmReason_e { DISARM_STICKS = 2, DISARM_SWITCH_3D = 3, DISARM_SWITCH = 4, - DISARM_KILLSWITCH = 5, DISARM_FAILSAFE = 6, DISARM_NAVIGATION = 7, DISARM_LANDING = 8, @@ -46,6 +45,7 @@ bool emergencyArmingUpdate(bool armingSwitchIsOn, bool forceArm); bool areSensorsCalibrating(void); float getFlightTime(void); +void resetFlightTime(void); float getArmTime(void); void fcReboot(bool bootLoader); \ No newline at end of file diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 849cdc2b7c..2839a338f2 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -229,13 +229,6 @@ void init(void) readEEPROM(); resumeRxSignal(); -#ifdef USE_UNDERCLOCK - // Re-initialize system clock to their final values (if necessary) - systemClockSetup(systemConfig()->cpuUnderclock); -#else - systemClockSetup(false); -#endif - #ifdef USE_I2C i2cSetSpeed(systemConfig()->i2c_speed); #endif @@ -256,7 +249,7 @@ void init(void) EXTIInit(); #endif -#ifdef USE_SPEKTRUM_BIND +#if defined(USE_SPEKTRUM_BIND) && defined(USE_SERIALRX_SPEKTRUM) if (rxConfig()->receiverType == RX_TYPE_SERIAL) { switch (rxConfig()->serialrx_provider) { case SERIALRX_SPEKTRUM1024: diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index e395139d3e..59f2fc0d21 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -505,6 +505,14 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU32(dst, 0); //Input reversing is not required since it can be done on mixer level } break; + case MSP2_INAV_SERVO_CONFIG: + for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { + sbufWriteU16(dst, servoParams(i)->min); + sbufWriteU16(dst, servoParams(i)->max); + sbufWriteU16(dst, servoParams(i)->middle); + sbufWriteU8(dst, servoParams(i)->rate); + } + break; case MSP_SERVO_MIX_RULES: for (int i = 0; i < MAX_SERVO_RULES; i++) { sbufWriteU8(dst, customServoMixers(i)->targetChannel); @@ -671,11 +679,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, getRSSI()); break; - case MSP_ARMING_CONFIG: - sbufWriteU8(dst, 0); - sbufWriteU8(dst, armingConfig()->disarm_kill_switch); - break; - case MSP_LOOP_TIME: sbufWriteU16(dst, gyroConfig()->looptime); break; @@ -770,7 +773,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, PWM_RANGE_MIDDLE); sbufWriteU16(dst, 0); // Was min_throttle - sbufWriteU16(dst, motorConfig()->maxthrottle); + sbufWriteU16(dst, getMaxThrottle()); sbufWriteU16(dst, motorConfig()->mincommand); sbufWriteU16(dst, currentBatteryProfile->failsafe_throttle); @@ -811,7 +814,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, PWM_RANGE_MIDDLE); sbufWriteU16(dst, 0); //Was min_throttle - sbufWriteU16(dst, motorConfig()->maxthrottle); + sbufWriteU16(dst, getMaxThrottle()); sbufWriteU16(dst, motorConfig()->mincommand); sbufWriteU16(dst, currentBatteryProfile->failsafe_throttle); @@ -896,13 +899,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, currentBatteryProfile->capacity.unit); break; - case MSP_MOTOR_PINS: - // FIXME This is hardcoded and should not be. - for (int i = 0; i < 8; i++) { - sbufWriteU8(dst, i + 1); - } - break; - #ifdef USE_GPS case MSP_RAW_GPS: sbufWriteU8(dst, gpsSol.fixType); @@ -1273,7 +1269,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff); sbufWriteU16(dst, 0); //Was gyroConfig()->gyro_stage2_lowpass_hz - break; + break; case MSP_PID_ADVANCED: sbufWriteU16(dst, 0); // pidProfile()->rollPitchItermIgnoreRate @@ -1283,7 +1279,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, 0); //BF: pidProfile()->vbatPidCompensation sbufWriteU8(dst, 0); //BF: pidProfile()->setpointRelaxRatio sbufWriteU8(dst, 0); - sbufWriteU16(dst, pidProfile()->pidSumLimit); + sbufWriteU16(dst, 0); //Was pidsum limit sbufWriteU8(dst, 0); //BF: pidProfile()->itermThrottleGain /* @@ -1301,7 +1297,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, pidProfile()->heading_hold_rate_limit); sbufWriteU8(dst, HEADING_HOLD_ERROR_LPF_FREQ); sbufWriteU16(dst, 0); - sbufWriteU8(dst, gyroConfig()->gyro_lpf); + sbufWriteU8(dst, GYRO_LPF_256HZ); sbufWriteU8(dst, accelerometerConfig()->acc_lpf_hz); sbufWriteU8(dst, 0); //reserved sbufWriteU8(dst, 0); //reserved @@ -1421,7 +1417,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, positionEstimationConfig()->w_xy_gps_p * 100); // 2 inav_w_xy_gps_p float as value * 100 sbufWriteU16(dst, positionEstimationConfig()->w_xy_gps_v * 100); // 2 inav_w_xy_gps_v float as value * 100 sbufWriteU8(dst, gpsConfigMutable()->gpsMinSats); // 1 - sbufWriteU8(dst, positionEstimationConfig()->use_gps_velned); // 1 inav_use_gps_velned ON/OFF + sbufWriteU8(dst, 1); // 1 inav_use_gps_velned ON/OFF break; @@ -1657,6 +1653,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, ezTune()->aggressiveness); sbufWriteU8(dst, ezTune()->rate); sbufWriteU8(dst, ezTune()->expo); + sbufWriteU8(dst, ezTune()->snappiness); } break; #endif @@ -1829,14 +1826,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) break; #endif - case MSP_SET_ARMING_CONFIG: - if (dataSize == 2) { - sbufReadU8(src); //Swallow the first byte, used to be auto_disarm_delay - armingConfigMutable()->disarm_kill_switch = !!sbufReadU8(src); - } else - return MSP_RESULT_ERROR; - break; - case MSP_SET_LOOP_TIME: if (sbufReadU16Safe(&tmp_u16, src)) gyroConfigMutable()->looptime = tmp_u16; @@ -1972,7 +1961,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) sbufReadU16(src); // midrc sbufReadU16(src); //Was min_throttle - motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); + sbufReadU16(src); //Was maxThrottle motorConfigMutable()->mincommand = constrain(sbufReadU16(src), 0, PWM_RANGE_MAX); currentBatteryProfileMutable->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); @@ -2020,7 +2009,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) sbufReadU16(src); // midrc sbufReadU16(src); // was min_throttle - motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); + sbufReadU16(src); // was maxThrottle motorConfigMutable()->mincommand = constrain(sbufReadU16(src), 0, PWM_RANGE_MAX); currentBatteryProfileMutable->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); @@ -2150,6 +2139,22 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } break; + case MSP2_INAV_SET_SERVO_CONFIG: + if (dataSize != 8) { + return MSP_RESULT_ERROR; + } + tmp_u8 = sbufReadU8(src); + if (tmp_u8 >= MAX_SUPPORTED_SERVOS) { + return MSP_RESULT_ERROR; + } else { + servoParamsMutable(tmp_u8)->min = sbufReadU16(src); + servoParamsMutable(tmp_u8)->max = sbufReadU16(src); + servoParamsMutable(tmp_u8)->middle = sbufReadU16(src); + servoParamsMutable(tmp_u8)->rate = sbufReadU8(src); + servoComputeScalingFactors(tmp_u8); + } + break; + case MSP_SET_SERVO_MIX_RULE: sbufReadU8Safe(&tmp_u8, src); if ((dataSize == 9) && (tmp_u8 < MAX_SERVO_RULES)) { @@ -2328,7 +2333,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) sbufReadU8(src); //BF: pidProfileMutable()->vbatPidCompensation sbufReadU8(src); //BF: pidProfileMutable()->setpointRelaxRatio sbufReadU8(src); - pidProfileMutable()->pidSumLimit = sbufReadU16(src); + sbufReadU16(src); // Was pidsumLimit sbufReadU8(src); //BF: pidProfileMutable()->itermThrottleGain /* @@ -2349,7 +2354,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) pidProfileMutable()->heading_hold_rate_limit = sbufReadU8(src); sbufReadU8(src); //HEADING_HOLD_ERROR_LPF_FREQ sbufReadU16(src); //Legacy yaw_jump_prevention_limit - gyroConfigMutable()->gyro_lpf = sbufReadU8(src); + sbufReadU8(src); // was gyro lpf accelerometerConfigMutable()->acc_lpf_hz = sbufReadU8(src); sbufReadU8(src); //reserved sbufReadU8(src); //reserved @@ -2490,7 +2495,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) positionEstimationConfigMutable()->w_xy_gps_p = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f); positionEstimationConfigMutable()->w_xy_gps_v = constrainf(sbufReadU16(src) / 100.0f, 0.0f, 10.0f); gpsConfigMutable()->gpsMinSats = constrain(sbufReadU8(src), 5, 10); - positionEstimationConfigMutable()->use_gps_velned = constrain(sbufReadU8(src), 0, 1); + sbufReadU8(src); // was positionEstimationConfigMutable()->use_gps_velned } else return MSP_RESULT_ERROR; break; @@ -3260,21 +3265,25 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP2_INAV_EZ_TUNE_SET: { - if (dataSize == 10) { - ezTuneMutable()->enabled = sbufReadU8(src); - ezTuneMutable()->filterHz = sbufReadU16(src); - ezTuneMutable()->axisRatio = sbufReadU8(src); - ezTuneMutable()->response = sbufReadU8(src); - ezTuneMutable()->damping = sbufReadU8(src); - ezTuneMutable()->stability = sbufReadU8(src); - ezTuneMutable()->aggressiveness = sbufReadU8(src); - ezTuneMutable()->rate = sbufReadU8(src); - ezTuneMutable()->expo = sbufReadU8(src); - ezTuneUpdate(); - } else { + if (dataSize < 10 || dataSize > 11) { return MSP_RESULT_ERROR; } + + ezTuneMutable()->enabled = sbufReadU8(src); + ezTuneMutable()->filterHz = sbufReadU16(src); + ezTuneMutable()->axisRatio = sbufReadU8(src); + ezTuneMutable()->response = sbufReadU8(src); + ezTuneMutable()->damping = sbufReadU8(src); + ezTuneMutable()->stability = sbufReadU8(src); + ezTuneMutable()->aggressiveness = sbufReadU8(src); + ezTuneMutable()->rate = sbufReadU8(src); + ezTuneMutable()->expo = sbufReadU8(src); + + if (dataSize == 11) { + ezTuneMutable()->snappiness = sbufReadU8(src); + } + ezTuneUpdate(); } break; diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index c61c2aa19e..2745f7e041 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -76,7 +76,6 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { .boxId = BOXTURNASSIST, .boxName = "TURN ASSIST", .permanentId = 35 }, { .boxId = BOXNAVLAUNCH, .boxName = "NAV LAUNCH", .permanentId = 36 }, { .boxId = BOXAUTOTRIM, .boxName = "SERVO AUTOTRIM", .permanentId = 37 }, - { .boxId = BOXKILLSWITCH, .boxName = "KILLSWITCH", .permanentId = 38 }, { .boxId = BOXCAMERA1, .boxName = "CAMERA CONTROL 1", .permanentId = 39 }, { .boxId = BOXCAMERA2, .boxName = "CAMERA CONTROL 2", .permanentId = 40 }, { .boxId = BOXCAMERA3, .boxName = "CAMERA CONTROL 3", .permanentId = 41 }, @@ -214,15 +213,12 @@ void initActiveBoxIds(void) ADD_ACTIVE_BOX(BOXFPVANGLEMIX); } - bool navReadyAltControl = sensors(SENSOR_BARO); + bool navReadyAltControl = getHwBarometerStatus() != HW_SENSOR_NONE; #ifdef USE_GPS navReadyAltControl = navReadyAltControl || (feature(FEATURE_GPS) && (STATE(AIRPLANE) || positionEstimationConfig()->use_gps_no_baro)); const bool navFlowDeadReckoning = sensors(SENSOR_OPFLOW) && sensors(SENSOR_ACC) && positionEstimationConfig()->allow_dead_reckoning; bool navReadyPosControl = sensors(SENSOR_ACC) && feature(FEATURE_GPS); - if (STATE(MULTIROTOR)) { - navReadyPosControl = navReadyPosControl && getHwCompassStatus() != HW_SENSOR_NONE; - } if (STATE(ALTITUDE_CONTROL) && navReadyAltControl && (navReadyPosControl || navFlowDeadReckoning)) { ADD_ACTIVE_BOX(BOXNAVPOSHOLD); @@ -320,7 +316,6 @@ void initActiveBoxIds(void) } #endif - ADD_ACTIVE_BOX(BOXKILLSWITCH); ADD_ACTIVE_BOX(BOXFAILSAFE); #if defined(USE_RCDEVICE) || defined(USE_MSP_DISPLAYPORT) @@ -405,7 +400,6 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_LAUNCH_MODE)), BOXNAVLAUNCH); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(AUTO_TUNE)), BOXAUTOTUNE); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAUTOTRIM)), BOXAUTOTRIM); - CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXKILLSWITCH)), BOXKILLSWITCH); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXHOMERESET)), BOXHOMERESET); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMERA1)), BOXCAMERA1); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCAMERA2)), BOXCAMERA2); diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 9cce60a2a3..d03bd466a4 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -75,24 +75,23 @@ stickPositions_e rcStickPositions; FASTRAM int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW -PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 3); +PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 4); PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, .deadband = SETTING_DEADBAND_DEFAULT, .yaw_deadband = SETTING_YAW_DEADBAND_DEFAULT, .pos_hold_deadband = SETTING_POS_HOLD_DEADBAND_DEFAULT, - .control_deadband = SETTING_CONTROL_DEADBAND_DEFAULT, .alt_hold_deadband = SETTING_ALT_HOLD_DEADBAND_DEFAULT, .mid_throttle_deadband = SETTING_3D_DEADBAND_THROTTLE_DEFAULT, .airmodeHandlingType = SETTING_AIRMODE_TYPE_DEFAULT, .airmodeThrottleThreshold = SETTING_AIRMODE_THROTTLE_THRESHOLD_DEFAULT, ); -PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 2); +PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 3); PG_RESET_TEMPLATE(armingConfig_t, armingConfig, .fixed_wing_auto_arm = SETTING_FIXED_WING_AUTO_ARM_DEFAULT, - .disarm_kill_switch = SETTING_DISARM_KILL_SWITCH_DEFAULT, + .disarm_always = SETTING_DISARM_ALWAYS_DEFAULT, .switchDisarmDelayMs = SETTING_SWITCH_DISARM_DELAY_DEFAULT, .prearmTimeoutMs = SETTING_PREARM_TIMEOUT_DEFAULT, ); @@ -104,7 +103,7 @@ bool areSticksInApModePosition(uint16_t ap_mode) bool areSticksDeflected(void) { - return (ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[YAW]) > rcControlsConfig()->control_deadband); + return (ABS(rcCommand[ROLL]) > CONTROL_DEADBAND) || (ABS(rcCommand[PITCH]) > CONTROL_DEADBAND) || (ABS(rcCommand[YAW]) > CONTROL_DEADBAND); } bool isRollPitchStickDeflected(uint8_t deadband) @@ -232,7 +231,7 @@ void processRcStickPositions(bool isThrottleLow) if (ARMING_FLAG(ARMED) && !IS_RC_MODE_ACTIVE(BOXFAILSAFE) && rxIsReceivingSignal() && !failsafeIsActive()) { const timeMs_t disarmDelay = currentTimeMs - rcDisarmTimeMs; if (disarmDelay > armingConfig()->switchDisarmDelayMs) { - if (armingConfig()->disarm_kill_switch || isThrottleLow) { + if (armingConfig()->disarm_always || isThrottleLow) { disarm(DISARM_SWITCH); } } @@ -241,11 +240,6 @@ void processRcStickPositions(bool isThrottleLow) rcDisarmTimeMs = currentTimeMs; } } - - // KILLSWITCH disarms instantly - if (IS_RC_MODE_ACTIVE(BOXKILLSWITCH)) { - disarm(DISARM_KILLSWITCH); - } } if (rcDelayCommand != 20) { diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index ea23eae907..8d5ee66bd7 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -19,7 +19,7 @@ #include "config/parameter_group.h" -#define AIRMODE_THROTTLE_THRESHOLD 1300 +#define CONTROL_DEADBAND 10 // Used to check if sticks are centered typedef enum rc_alias { ROLL = 0, @@ -85,7 +85,6 @@ typedef struct rcControlsConfig_s { uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero. uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero. uint8_t pos_hold_deadband; // Deadband for position hold - uint8_t control_deadband; // General deadband to check if sticks are deflected, us PWM. uint8_t alt_hold_deadband; // Defines the neutral zone of throttle stick during altitude hold uint16_t mid_throttle_deadband; // default throttle deadband from MIDRC uint8_t airmodeHandlingType; // Defaults to ANTI_WINDUP triggered at sticks centered @@ -96,7 +95,7 @@ PG_DECLARE(rcControlsConfig_t, rcControlsConfig); typedef struct armingConfig_s { bool fixed_wing_auto_arm; // Auto-arm fixed wing aircraft on throttle up and never disarm - bool disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value + bool disarm_always; // Disarm motors regardless of throttle value uint16_t switchDisarmDelayMs; // additional delay between ARM box going off and actual disarm uint16_t prearmTimeoutMs; // duration for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout. } armingConfig_t; diff --git a/src/main/fc/rc_curves.c b/src/main/fc/rc_curves.c index 47da45113b..5453083d27 100644 --- a/src/main/fc/rc_curves.c +++ b/src/main/fc/rc_curves.c @@ -39,7 +39,7 @@ int16_t lookupThrottleRCMid; // THROTTLE curve mid point void generateThrottleCurve(const controlRateConfig_t *controlRateConfig) { const int minThrottle = getThrottleIdleValue(); - lookupThrottleRCMid = minThrottle + (int32_t)(motorConfig()->maxthrottle - minThrottle) * controlRateConfig->throttle.rcMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE] + lookupThrottleRCMid = minThrottle + (int32_t)(getMaxThrottle() - minThrottle) * controlRateConfig->throttle.rcMid8 / 100; // [MINTHROTTLE;MAXTHROTTLE] for (int i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) { const int16_t tmp = 10 * i - controlRateConfig->throttle.rcMid8; @@ -49,7 +49,7 @@ void generateThrottleCurve(const controlRateConfig_t *controlRateConfig) if (tmp < 0) y = controlRateConfig->throttle.rcMid8; lookupThrottleRC[i] = 10 * controlRateConfig->throttle.rcMid8 + tmp * (100 - controlRateConfig->throttle.rcExpo8 + (int32_t) controlRateConfig->throttle.rcExpo8 * (tmp * tmp) / (y * y)) / 10; - lookupThrottleRC[i] = minThrottle + (int32_t) (motorConfig()->maxthrottle - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] + lookupThrottleRC[i] = minThrottle + (int32_t) (getMaxThrottle() - minThrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE] } } @@ -62,7 +62,7 @@ int16_t rcLookup(int32_t stickDeflection, uint8_t expo) uint16_t rcLookupThrottle(uint16_t absoluteDeflection) { if (absoluteDeflection > 999) - return motorConfig()->maxthrottle; + return getMaxThrottle(); const uint8_t lookupStep = absoluteDeflection / 100; return lookupThrottleRC[lookupStep] + (absoluteDeflection - lookupStep * 100) * (lookupThrottleRC[lookupStep + 1] - lookupThrottleRC[lookupStep]) / 100; diff --git a/src/main/fc/rc_modes.h b/src/main/fc/rc_modes.h index fa1827a6ad..04aea681bc 100644 --- a/src/main/fc/rc_modes.h +++ b/src/main/fc/rc_modes.h @@ -49,7 +49,6 @@ typedef enum { BOXAIRMODE = 20, BOXHOMERESET = 21, BOXGCSNAV = 22, - BOXKILLSWITCH = 23, // old HEADING LOCK BOXSURFACE = 24, BOXFLAPERON = 25, BOXTURNASSIST = 26, diff --git a/src/main/fc/runtime_config.c b/src/main/fc/runtime_config.c index daeb9cbbcd..44118ef54b 100644 --- a/src/main/fc/runtime_config.c +++ b/src/main/fc/runtime_config.c @@ -34,7 +34,7 @@ static EXTENDED_FASTRAM uint32_t enabledSensors = 0; #if !defined(CLI_MINIMAL_VERBOSITY) const char *armingDisableFlagNames[]= { "FS", "ANGLE", "CAL", "OVRLD", "NAV", "COMPASS", - "ACC", "ARMSW", "HWFAIL", "BOXFS", "KILLSW", "RX", + "ACC", "ARMSW", "HWFAIL", "BOXFS", "RX", "THR", "CLI", "CMS", "OSD", "ROLL/PITCH", "AUTOTRIM", "OOM", "SETTINGFAIL", "PWMOUT", "NOPREARM", "DSHOTBEEPER", "LANDED" }; @@ -50,7 +50,6 @@ const armingFlag_e armDisableReasonsChecklist[] = { ARMING_DISABLED_NAVIGATION_UNSAFE, ARMING_DISABLED_ARM_SWITCH, ARMING_DISABLED_BOXFAILSAFE, - ARMING_DISABLED_BOXKILLSWITCH, ARMING_DISABLED_THROTTLE, ARMING_DISABLED_CLI, ARMING_DISABLED_CMS_MENU, diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index 5b6c624139..974f90f8c4 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -34,7 +34,7 @@ typedef enum { ARMING_DISABLED_ARM_SWITCH = (1 << 14), ARMING_DISABLED_HARDWARE_FAILURE = (1 << 15), ARMING_DISABLED_BOXFAILSAFE = (1 << 16), - ARMING_DISABLED_BOXKILLSWITCH = (1 << 17), + ARMING_DISABLED_RC_LINK = (1 << 18), ARMING_DISABLED_THROTTLE = (1 << 19), ARMING_DISABLED_CLI = (1 << 20), @@ -53,7 +53,7 @@ typedef enum { ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED | ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | - ARMING_DISABLED_BOXKILLSWITCH | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | + ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING | ARMING_DISABLED_PWM_OUTPUT_ERROR | ARMING_DISABLED_NO_PREARM | ARMING_DISABLED_DSHOT_BEEPER | @@ -105,6 +105,7 @@ typedef enum { TURTLE_MODE = (1 << 15), SOARING_MODE = (1 << 16), ANGLEHOLD_MODE = (1 << 17), + NAV_FW_AUTOLAND = (1 << 18), } flightModeFlags_e; extern uint32_t flightModeFlags; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 0afd4c8bae..604385d3d6 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1,13 +1,11 @@ tables: - name: alignment values: ["DEFAULT", "CW0", "CW90", "CW180", "CW270", "CW0FLIP", "CW90FLIP", "CW180FLIP", "CW270FLIP"] - - name: gyro_lpf - values: ["256HZ", "188HZ", "98HZ", "42HZ", "20HZ", "10HZ"] - name: acc_hardware values: ["NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270","LSM6DXX", "FAKE"] enum: accelerationSensor_e - name: rangefinder_hardware - values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C", "FAKE"] + values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C", "FAKE", "TERARANGER_EVO"] enum: rangefinderType_e - name: mag_hardware values: ["NONE", "AUTO", "HMC5883", "AK8975", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"] @@ -68,9 +66,6 @@ tables: - name: osd_stats_energy_unit values: ["MAH", "WH"] enum: osd_stats_energy_unit_e - - name: osd_stats_min_voltage_unit - values: ["BATTERY", "CELL"] - enum: osd_stats_min_voltage_unit_e - name: osd_video_system values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "AVATAR", "BF43COMPAT", "BFHDCOMPAT"] enum: videoSystem_e @@ -182,7 +177,7 @@ tables: values: ["OFF", "ON", "FS"] enum: rthTrackbackMode_e - name: dynamic_gyro_notch_mode - values: ["2D", "3D_R", "3D_P", "3D_Y", "3D_RP", "3D_RY", "3D_PY", "3D"] + values: ["2D", "3D"] enum: dynamicGyroNotchMode_e - name: nav_fw_wp_turn_smoothing values: ["OFF", "ON", "ON-CUT"] @@ -220,32 +215,17 @@ groups: description: "This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible." default_value: 1000 max: 9000 - - name: gyro_hardware_lpf - description: "Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first." - default_value: "256HZ" - field: gyro_lpf - table: gyro_lpf - name: gyro_anti_aliasing_lpf_hz description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz" default_value: 250 field: gyro_anti_aliasing_lpf_hz max: 1000 - - name: gyro_anti_aliasing_lpf_type - description: "Specifies the type of the software LPF of the gyro signals." - default_value: "PT1" - field: gyro_anti_aliasing_lpf_type - table: filter_type - name: gyro_main_lpf_hz description: "Software based gyro main lowpass filter. Value is cutoff frequency (Hz)" default_value: 60 field: gyro_main_lpf_hz min: 0 max: 500 - - name: gyro_main_lpf_type - description: "Defines the type of the main gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." - default_value: BIQUAD - field: gyro_main_lpf_type - table: filter_type - name: gyro_use_dyn_lpf description: "Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position." default_value: OFF @@ -303,6 +283,7 @@ groups: min: 1 max: 1000 - name: gyro_to_use + description: "On multi-gyro targets, allows to choose which gyro to use. 0 = first gyro, 1 = second gyro" condition: USE_DUAL_GYRO min: 0 max: 2 @@ -385,10 +366,12 @@ groups: headers: ["sensors/acceleration.h"] members: - name: acc_notch_hz + description: "Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is center frequency (Hz)" min: 0 max: 255 default_value: 0 - name: acc_notch_cutoff + description: "Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz)" min: 1 max: 255 default_value: 1 @@ -468,6 +451,7 @@ groups: default_value: NONE table: opflow_hardware - name: opflow_scale + description: "Optical flow module scale factor" min: 0 max: 10000 default_value: 10.5 @@ -591,10 +575,12 @@ groups: default_value: "NONE" table: pitot_hardware - name: pitot_lpf_milli_hz + description: "Pitot tube lowpass filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay" min: 0 max: 10000 default_value: 350 - name: pitot_scale + description: "Pitot tube scale factor" min: 0 max: 100 default_value: 1.0 @@ -644,6 +630,7 @@ groups: max: RSSI_VISIBLE_VALUE_MAX - name: sbus_sync_interval field: sbusSyncInterval + description: "SBUS sync interval in us. Default value is 3000us. Lower values may cause issues with some receivers." min: 500 max: 10000 default_value: 3000 @@ -745,12 +732,6 @@ groups: type: motorConfig_t headers: ["flight/mixer.h"] members: - - name: max_throttle - description: "This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000." - default_value: 1850 - field: maxthrottle - min: PWM_RANGE_MIN - max: PWM_RANGE_MAX - name: min_command description: "This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once." default_value: 1000 @@ -1197,8 +1178,6 @@ groups: field: mixer_config.tailsitterOrientationOffset type: bool - - - name: PG_REVERSIBLE_MOTORS_CONFIG type: reversibleMotorsConfig_t members: @@ -1366,6 +1345,7 @@ groups: min: MANUAL_RATE_MIN max: MANUAL_RATE_MAX - name: fpv_mix_degrees + description: "The tilt angle of the FPV camera in degrees, used by the FPV ANGLE MIX mode" field: misc.fpvCamAngleDegrees min: 0 max: 50 @@ -1488,8 +1468,8 @@ groups: description: "Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured." default_value: OFF type: bool - - name: disarm_kill_switch - description: "Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel." + - name: disarm_always + description: "Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low." default_value: ON type: bool - name: switch_disarm_delay @@ -1575,6 +1555,12 @@ groups: field: expo min: 0 max: 200 + - name: ez_snappiness + description: "EzTune snappiness" + default_value: 0 + field: snappiness + min: 0 + max: 100 - name: PG_RPM_FILTER_CONFIG headers: ["flight/rpm_filter.h"] @@ -1682,12 +1668,12 @@ groups: members: - name: deadband description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." - default_value: 5 + default_value: 2 min: 0 max: 32 - name: yaw_deadband description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." - default_value: 5 + default_value: 2 min: 0 max: 100 - name: pos_hold_deadband @@ -1695,11 +1681,6 @@ groups: default_value: 10 min: 2 max: 250 - - name: control_deadband - description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered." - default_value: 10 - min: 2 - max: 250 - name: alt_hold_deadband description: "Defines the deadband of throttle during alt_hold [r/c points]" default_value: 50 @@ -1965,18 +1946,6 @@ groups: field: fixedWingYawItermBankFreeze min: 0 max: 90 - - name: pidsum_limit - description: "A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" - default_value: 500 - field: pidSumLimit - min: PID_SUM_LIMIT_MIN - max: PID_SUM_LIMIT_MAX - - name: pidsum_limit_yaw - description: "A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" - default_value: 350 - field: pidSumLimitYaw - min: PID_SUM_LIMIT_MIN - max: PID_SUM_LIMIT_MAX - name: iterm_windup description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" default_value: 50 @@ -2053,6 +2022,7 @@ groups: max: 255 default_value: 100 - name: nav_mc_vel_xy_ff + description: "FF gain of Position-Rate (Velocity to Acceleration)" field: bank_mc.pid[PID_VEL_XY].FF min: 0 max: 255 @@ -2064,6 +2034,7 @@ groups: min: 0 max: 255 - name: nav_mc_vel_xy_dterm_lpf_hz + description: "D-term low pass filter cutoff frequency for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating." field: navVelXyDTermLpfHz min: 0 max: 100 @@ -2153,33 +2124,39 @@ groups: min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: mc_iterm_relax + description: "Iterm relax type. When enabled, Iterm will be relaxed when stick is centered. This will help to reduce bounceback and followthrough on multirotors. It is recommended to enable this feature on all multirotors." field: iterm_relax table: iterm_relax default_value: RP - name: mc_iterm_relax_cutoff + description: "Iterm relax cutoff frequency." field: iterm_relax_cutoff min: 1 max: 100 default_value: 15 - name: d_boost_min + description: "D-term multiplier when pilot provides rapid stick input. Lower values give sharper response to stick input, higher values give smoother response." field: dBoostMin condition: USE_D_BOOST min: 0 max: 1 default_value: 0.5 - name: d_boost_max + description: "D-term multiplier when rapid external conditions are detected. Lower values give sharper response to stick input, higher values give smoother response by scaling D-gains up." field: dBoostMax condition: USE_D_BOOST min: 1 max: 3 default_value: 1.25 - name: d_boost_max_at_acceleration + description: "Acceleration threshold for D-term multiplier. When acceleration is above this value, D-term multiplier is set to `d_boost_max`" field: dBoostMaxAtAlleceleration condition: USE_D_BOOST min: 1000 max: 16000 default_value: 7500 - name: d_boost_gyro_delta_lpf_hz + description: "Cutoff frequency for the low pass filter applied to the gyro delta signal used for D-term boost. Lower value will produce a smoother D-term boost signal, but it will be more delayed." field: dBoostGyroDeltaLpfHz condition: USE_D_BOOST min: 10 @@ -2193,7 +2170,7 @@ groups: min: 1 max: 20 - name: antigravity_accelerator - description: "" + description: "Multiplier for Antigravity gain. The bigger is the difference between actual and filtered throttle input, the bigger Antigravity gain" default_value: 1 field: antigravityAccelerator condition: USE_ANTIGRAVITY @@ -2288,11 +2265,6 @@ groups: field: gravity_calibration_tolerance min: 0 max: 255 - - name: inav_use_gps_velned - description: "Defined if INAV should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF INAV will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance." - default_value: ON - field: use_gps_velned - type: bool - name: inav_use_gps_no_baro field: use_gps_no_baro type: bool @@ -2325,21 +2297,25 @@ groups: min: 0 max: 1000 - name: inav_w_z_surface_p + description: "Weight of rangefinder measurements in estimated altitude. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled" field: w_z_surface_p min: 0 max: 100 default_value: 3.5 - name: inav_w_z_surface_v + description: "Weight of rangefinder measurements in estimated climb rate. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled" field: w_z_surface_v min: 0 max: 100 default_value: 6.1 - name: inav_w_xy_flow_p + description: "Weight of optical flow measurements in estimated UAV position." field: w_xy_flow_p min: 0 max: 100 default_value: 1.0 - name: inav_w_xy_flow_v + description: "Weight of optical flow measurements in estimated UAV speed." field: w_xy_flow_v min: 0 max: 100 @@ -2505,7 +2481,7 @@ groups: min: 10 max: 2000 - name: nav_min_ground_speed - description: "Minimum ground speed for navigation flight modes [m/s]. Default 7 m/s." + description: "Minimum ground speed for navigation flight modes [m/s]. Currently, this only affects fixed wing. Default 7 m/s." default_value: 7 field: general.min_ground_speed min: 6 @@ -2867,10 +2843,10 @@ groups: min: 100 max: 10000 - name: nav_fw_launch_accel - description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s" + description: "Forward acceleration threshold for bungee launch or throw launch [cm/s/s], 1G = 981 cm/s/s" default_value: 1863 field: fw.launch_accel_thresh - min: 1000 + min: 1500 max: 20000 - name: nav_fw_launch_max_angle description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]" @@ -2890,6 +2866,13 @@ groups: field: fw.launch_idle_motor_timer min: 0 max: 60000 + - name: nav_fw_launch_wiggle_to_wake_idle + description: "Trigger the idle throttle by wiggling the plane. 0 = disabled. 1 and 2 signify 1 or 2 yaw wiggles to activate. 1 wiggle has a higher detection point, for airplanes without a tail. 2 wiggles has a lower detection point, but requires the repeated action. This is intended for larger models and airplanes with tails." + field: fw.launch_wiggle_wake_idle + type: uint8_t + default_value: 0 + min: 0 + max: 2 - name: nav_fw_launch_motor_delay description: "Delay between detected launch and launch sequence start and throttling up (ms)" default_value: 500 @@ -3068,35 +3051,41 @@ groups: max: INT16_MAX - name: mavlink_ext_status_rate field: mavlink.extended_status_rate + description: "Rate of the extended status message for MAVLink telemetry" type: uint8_t min: 0 max: 255 default_value: 2 - name: mavlink_rc_chan_rate + description: "Rate of the RC channels message for MAVLink telemetry" field: mavlink.rc_channels_rate type: uint8_t min: 0 max: 255 default_value: 5 - name: mavlink_pos_rate + description: "Rate of the position message for MAVLink telemetry" field: mavlink.position_rate type: uint8_t min: 0 max: 255 default_value: 2 - name: mavlink_extra1_rate + description: "Rate of the extra1 message for MAVLink telemetry" field: mavlink.extra1_rate type: uint8_t min: 0 max: 255 default_value: 10 - name: mavlink_extra2_rate + description: "Rate of the extra2 message for MAVLink telemetry" field: mavlink.extra2_rate type: uint8_t min: 0 max: 255 default_value: 2 - name: mavlink_extra3_rate + description: "Rate of the extra3 message for MAVLink telemetry" field: mavlink.extra3_rate type: uint8_t min: 0 @@ -3110,16 +3099,6 @@ groups: max: 2 default_value: 2 - - name: PG_LED_STRIP_CONFIG - type: ledStripConfig_t - headers: ["common/color.h", "io/ledstrip.h"] - condition: USE_LED_STRIP - members: - - name: ledstrip_visual_beeper - description: "" - default_value: OFF - type: bool - - name: PG_OSD_CONFIG type: osdConfig_t headers: ["io/osd.h", "drivers/osd.h"] @@ -3162,18 +3141,17 @@ groups: field: stats_energy_unit table: osd_stats_energy_unit type: uint8_t - - name: osd_stats_min_voltage_unit - description: "Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD stats." - default_value: "BATTERY" - field: stats_min_voltage_unit - table: osd_stats_min_voltage_unit - type: uint8_t - name: osd_stats_page_auto_swap_time description: "Auto swap display time interval between disarm stats pages (seconds). Reverts to manual control when Roll stick used to change pages. Disabled when set to 0." default_value: 3 field: stats_page_auto_swap_time min: 0 max: 10 + - name: osd_stats_show_metric_efficiency + description: "Enabling this option will show metric efficiency statistics on the post flight stats screen. In addition to the efficiency statistics in your chosen units." + default_value: OFF + type: bool + field: stats_show_metric_efficiency - name: osd_rssi_alarm description: "Value below which to make the OSD RSSI indicator blink" default_value: 20 @@ -3434,16 +3412,19 @@ groups: min: 0 max: 3 - name: osd_left_sidebar_scroll + description: "Scroll type for the left sidebar" field: left_sidebar_scroll table: osd_sidebar_scroll type: uint8_t default_value: NONE - name: osd_right_sidebar_scroll + description: "Scroll type for the right sidebar" field: right_sidebar_scroll table: osd_sidebar_scroll type: uint8_t default_value: NONE - name: osd_sidebar_scroll_arrows + description: "Show arrows for scrolling the sidebars" field: sidebar_scroll_arrows type: bool default_value: OFF @@ -3454,6 +3435,7 @@ groups: min: 1 max: 2 - name: osd_coordinate_digits + description: "Number of digits for the coordinates displayed in the OSD [8-11]." field: coordinate_digits min: 8 max: 11 @@ -3490,6 +3472,12 @@ groups: condition: USE_WIND_ESTIMATOR field: estimations_wind_compensation type: bool + - name: osd_estimations_wind_mps + description: "Wind speed estimation in m/s" + default_value: OFF + condition: USE_WIND_ESTIMATOR + field: estimations_wind_mps + type: bool - name: osd_failsafe_switch_layout description: "If enabled the OSD automatically switches to the first layout during failsafe" @@ -3735,12 +3723,6 @@ groups: default_value: "400KHZ" condition: USE_I2C table: i2c_speed - - name: cpu_underclock - description: "This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz" - default_value: OFF - field: cpuUnderclock - condition: USE_UNDERCLOCK - type: bool - name: debug_mode description: "Defines debug values exposed in debug variables (developer / debugging setting)" default_value: "NONE" @@ -3892,6 +3874,7 @@ groups: table: vtx_low_power_disarm type: uint8_t - name: vtx_pit_mode_chan + description: "Pit mode channel." field: pitModeChan min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL @@ -3996,12 +3979,6 @@ groups: headers: ["io/osd_dji_hd.h"] condition: USE_DJI_HD_OSD members: - - name: dji_workarounds - description: "Enables workarounds for different versions of MSP protocol used" - field: proto_workarounds - min: 0 - max: UINT8_MAX - default_value: 1 - name: dji_use_name_for_messages description: "Re-purpose the craft name field for messages." default_value: ON diff --git a/src/main/flight/dynamic_lpf.c b/src/main/flight/dynamic_lpf.c index 5751c84e85..0e5b4f6ef2 100644 --- a/src/main/flight/dynamic_lpf.c +++ b/src/main/flight/dynamic_lpf.c @@ -41,8 +41,8 @@ void dynamicLpfGyroTask(void) { return; } - const float throttleConstrained = (float) constrain(rcCommand[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); - const float throttle = scaleRangef(throttleConstrained, getThrottleIdleValue(), motorConfig()->maxthrottle, 0.0f, 1.0f); + const float throttleConstrained = (float) constrain(rcCommand[THROTTLE], getThrottleIdleValue(), getMaxThrottle()); + const float throttle = scaleRangef(throttleConstrained, getThrottleIdleValue(), getMaxThrottle(), 0.0f, 1.0f); const float cutoffFreq = dynLpfCutoffFreq(throttle, gyroConfig()->gyroDynamicLpfMinHz, gyroConfig()->gyroDynamicLpfMaxHz, gyroConfig()->gyroDynamicLpfCurveExpo); DEBUG_SET(DEBUG_DYNAMIC_GYRO_LPF, 0, cutoffFreq); diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index c6c57afbfe..4bde5b645e 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -34,7 +34,9 @@ #include "sensors/gyro.h" #include "fc/controlrate_profile.h" -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(ezTuneSettings_t, ezTune, PG_EZ_TUNE, 0); +#include "rx/rx.h" + +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(ezTuneSettings_t, ezTune, PG_EZ_TUNE, 1); PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, .enabled = SETTING_EZ_ENABLED_DEFAULT, @@ -46,6 +48,7 @@ PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, .aggressiveness = SETTING_EZ_AGGRESSIVENESS_DEFAULT, .rate = SETTING_EZ_RATE_DEFAULT, .expo = SETTING_EZ_EXPO_DEFAULT, + .snappiness = SETTING_EZ_SNAPPINESS_DEFAULT, ); #define EZ_TUNE_PID_RP_DEFAULT { 40, 75, 23, 100 } @@ -70,6 +73,9 @@ static float getYawPidScale(float input) { void ezTuneUpdate(void) { if (ezTune()->enabled) { + //Enforce RC auto smoothing + rxConfigMutable()->autoSmooth = 1; + // Setup filtering //Set Dterm LPF pidProfileMutable()->dterm_lpf_hz = MAX(ezTune()->filterHz - 5, 50); @@ -77,11 +83,9 @@ void ezTuneUpdate(void) { //Set main gyro filter gyroConfigMutable()->gyro_main_lpf_hz = ezTune()->filterHz; - gyroConfigMutable()->gyro_main_lpf_type = FILTER_PT1; //Set anti-aliasing filter gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT; - gyroConfigMutable()->gyro_anti_aliasing_lpf_type = FILTER_PT1; //Enable Smith predictor pidProfileMutable()->smithPredictorDelay = computePt1FilterDelayMs(ezTune()->filterHz); @@ -139,5 +143,8 @@ void ezTuneUpdate(void) { ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcExpo8 = scaleRange(ezTune()->rate, 0, 200, 40, 100); ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcYawExpo8 = scaleRange(ezTune()->rate, 0, 200, 40, 100); + //D-Boost snappiness + pidProfileMutable()->dBoostMin = scaleRangef(ezTune()->snappiness, 0, 100, 1.0f, 0.0f); + } } \ No newline at end of file diff --git a/src/main/flight/ez_tune.h b/src/main/flight/ez_tune.h index 5fcc1ef6f7..d923dca219 100644 --- a/src/main/flight/ez_tune.h +++ b/src/main/flight/ez_tune.h @@ -36,6 +36,7 @@ typedef struct ezTuneSettings_s { uint8_t aggressiveness; uint8_t rate; uint8_t expo; + uint8_t snappiness; } ezTuneSettings_t; PG_DECLARE_PROFILE(ezTuneSettings_t, ezTune); diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 780de21b0a..2a32dbbd12 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -242,6 +242,10 @@ static void failsafeActivate(failsafePhase_e newPhase) ENABLE_FLIGHT_MODE(FAILSAFE_MODE); failsafeState.landingShouldBeFinishedAt = millis() + failsafeConfig()->failsafe_off_delay * MILLIS_PER_TENTH_SECOND; +#ifdef USE_FW_AUTOLAND + posControl.fwLandState.landAborted = false; +#endif + failsafeState.events++; } diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 834841e658..d2a073f26e 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -57,6 +57,9 @@ #include "sensors/battery.h" +#define MAX_THROTTLE 2000 +#define MAX_THROTTLE_ROVER 1850 + FASTRAM int16_t motor[MAX_SUPPORTED_MOTORS]; FASTRAM int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; static float motorMixRange; @@ -83,12 +86,11 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, .neutral = SETTING_3D_NEUTRAL_DEFAULT ); -PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 10); +PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 11); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .motorPwmProtocol = SETTING_MOTOR_PWM_PROTOCOL_DEFAULT, .motorPwmRate = SETTING_MOTOR_PWM_RATE_DEFAULT, - .maxthrottle = SETTING_MAX_THROTTLE_DEFAULT, .mincommand = SETTING_MIN_COMMAND_DEFAULT, .motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles ); @@ -106,7 +108,7 @@ void pgResetFn_timerOverrides(timerOverride_t *instance) int getThrottleIdleValue(void) { if (!throttleIdleValue) { - throttleIdleValue = motorConfig()->mincommand + (((motorConfig()->maxthrottle - motorConfig()->mincommand) / 100.0f) * currentBatteryProfile->motor.throttleIdle); + throttleIdleValue = motorConfig()->mincommand + (((getMaxThrottle() - motorConfig()->mincommand) / 100.0f) * currentBatteryProfile->motor.throttleIdle); } return throttleIdleValue; @@ -242,11 +244,11 @@ void mixerResetDisarmedMotors(void) if (feature(FEATURE_REVERSIBLE_MOTORS)) { motorZeroCommand = reversibleMotorsConfig()->neutral; throttleRangeMin = throttleDeadbandHigh; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); } else { motorZeroCommand = motorConfig()->mincommand; throttleRangeMin = throttleIdleValue; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); } reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD; @@ -357,7 +359,7 @@ static void applyTurtleModeToMotors(void) { motorOutputNormalised = MIN(1.0f, flipPower * motorOutputNormalised); - motor[i] = (int16_t)scaleRangef(motorOutputNormalised, 0, 1, motorConfig()->mincommand, motorConfig()->maxthrottle); + motor[i] = (int16_t)scaleRangef(motorOutputNormalised, 0, 1, motorConfig()->mincommand, getMaxThrottle()); } } else { // Disarmed mode @@ -407,7 +409,7 @@ void FAST_CODE writeMotors(void) throttleIdleValue, DSHOT_DISARM_COMMAND, motorConfig()->mincommand, - motorConfig()->maxthrottle, + getMaxThrottle(), DSHOT_MIN_THROTTLE, DSHOT_MAX_THROTTLE, true @@ -424,7 +426,7 @@ void FAST_CODE writeMotors(void) throttleRangeMin, throttleRangeMax, reversibleMotorsConfig()->deadband_high, - motorConfig()->maxthrottle, + getMaxThrottle(), true ); } else { @@ -551,7 +553,7 @@ void FAST_CODE mixTable(void) #ifdef USE_PROGRAMMING_FRAMEWORK if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE)) { throttleRangeMin = throttleIdleValue; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); mixerThrottleCommand = constrain(logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE], throttleRangeMin, throttleRangeMax); } else #endif @@ -562,7 +564,7 @@ void FAST_CODE mixTable(void) * Throttle is above deadband, FORWARD direction */ reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); throttleRangeMin = throttleDeadbandHigh; DISABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD); } else if (rcCommand[THROTTLE] <= throttleDeadbandLow) { @@ -591,7 +593,7 @@ void FAST_CODE mixTable(void) } else { mixerThrottleCommand = rcCommand[THROTTLE]; throttleRangeMin = throttleIdleValue; - throttleRangeMax = motorConfig()->maxthrottle; + throttleRangeMax = getMaxThrottle(); // Throttle scaling to limit max throttle when battery is full #ifdef USE_PROGRAMMING_FRAMEWORK @@ -630,7 +632,7 @@ void FAST_CODE mixTable(void) motor[i] = rpyMix[i] + constrain(mixerThrottleCommand * currentMixer[i].throttle, throttleMin, throttleMax); if (failsafeIsActive()) { - motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle); + motor[i] = constrain(motor[i], motorConfig()->mincommand, getMaxThrottle()); } else { motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax); } @@ -652,7 +654,7 @@ int16_t getThrottlePercent(bool useScaled) int16_t thr = constrain(mixerThrottleCommand, PWM_RANGE_MIN, PWM_RANGE_MAX); if (useScaled) { - thr = (thr - throttleIdleValue) * 100 / (motorConfig()->maxthrottle - throttleIdleValue); + thr = (thr - throttleIdleValue) * 100 / (getMaxThrottle() - throttleIdleValue); } else { thr = (rxGetChannelValue(THROTTLE) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN); } @@ -667,7 +669,7 @@ uint16_t setDesiredThrottle(uint16_t throttle, bool allowMotorStop) ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); return throttle; } - return constrain(throttle, throttleIdleValue, motorConfig()->maxthrottle); + return constrain(throttle, throttleIdleValue, getMaxThrottle()); } motorStatus_e getMotorStatus(void) @@ -725,3 +727,18 @@ bool areMotorsRunning(void) return false; } + +uint16_t getMaxThrottle() { + + static uint16_t throttle = 0; + + if (throttle == 0) { + if (STATE(ROVER) || STATE(BOAT)) { + throttle = MAX_THROTTLE_ROVER; + } else { + throttle = MAX_THROTTLE; + } + } + + return throttle; +} \ No newline at end of file diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 9ee6a20654..0d40fdc11e 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -81,7 +81,6 @@ PG_DECLARE(reversibleMotorsConfig_t, reversibleMotorsConfig); typedef struct motorConfig_s { // PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms) - uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000 uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz) uint8_t motorPwmProtocol; @@ -130,4 +129,6 @@ void stopMotorsNoDelay(void); void stopPwmAllMotors(void); void loadPrimaryMotorMixer(void); -bool areMotorsRunning(void); \ No newline at end of file +bool areMotorsRunning(void); + +uint16_t getMaxThrottle(void); \ No newline at end of file diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index d913802d55..2a9a340784 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -99,7 +99,6 @@ typedef struct { biquadFilter_t dBoostGyroLpf; float dBoostTargetAcceleration; #endif - uint16_t pidSumLimit; filterApply4FnPtr ptermFilterApplyFn; bool itermLimitActive; bool itermFreezeActive; @@ -170,7 +169,7 @@ static EXTENDED_FASTRAM bool angleHoldIsLevel = false; static EXTENDED_FASTRAM float fixedWingLevelTrim; static EXTENDED_FASTRAM pidController_t fixedWingLevelTrimController; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 6); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 7); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -264,8 +263,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .max_angle_inclination[FD_ROLL] = SETTING_MAX_ANGLE_INCLINATION_RLL_DEFAULT, .max_angle_inclination[FD_PITCH] = SETTING_MAX_ANGLE_INCLINATION_PIT_DEFAULT, - .pidSumLimit = SETTING_PIDSUM_LIMIT_DEFAULT, - .pidSumLimitYaw = SETTING_PIDSUM_LIMIT_YAW_DEFAULT, .pidItermLimitPercent = SETTING_PID_ITERM_LIMIT_PERCENT_DEFAULT, .fixedWingReferenceAirspeed = SETTING_FW_REFERENCE_AIRSPEED_DEFAULT, @@ -466,8 +463,8 @@ static float calculateMultirotorTPAFactor(void) // TPA should be updated only when TPA is actually set if (currentControlRateProfile->throttle.dynPID == 0 || rcCommand[THROTTLE] < currentControlRateProfile->throttle.pa_breakpoint) { tpaFactor = 1.0f; - } else if (rcCommand[THROTTLE] < motorConfig()->maxthrottle) { - tpaFactor = (100 - (uint16_t)currentControlRateProfile->throttle.dynPID * (rcCommand[THROTTLE] - currentControlRateProfile->throttle.pa_breakpoint) / (float)(motorConfig()->maxthrottle - currentControlRateProfile->throttle.pa_breakpoint)) / 100.0f; + } else if (rcCommand[THROTTLE] < getMaxThrottle()) { + tpaFactor = (100 - (uint16_t)currentControlRateProfile->throttle.dynPID * (rcCommand[THROTTLE] - currentControlRateProfile->throttle.pa_breakpoint) / (float)(getMaxThrottle() - currentControlRateProfile->throttle.pa_breakpoint)) / 100.0f; } else { tpaFactor = (100 - currentControlRateProfile->throttle.dynPID) / 100.0f; } @@ -594,7 +591,7 @@ static float computePidLevelTarget(flight_dynamics_index_t axis) { // Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle #ifdef USE_FW_AUTOLAND - if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle() && !isFwLandInProgess()) { + if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle() && !FLIGHT_MODE(NAV_FW_AUTOLAND)) { #else if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) { #endif @@ -772,12 +769,14 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh applyItermLimiting(pidState); + const uint16_t limit = getPidSumLimit(axis); + if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; + float itermLimit = limit * pidProfile()->pidItermLimitPercent * 0.01f; pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } - axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit); + axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -limit, +limit); if (FLIGHT_MODE(SOARING_MODE) && axis == FD_PITCH && calculateRollPitchCenterStatus() == CENTERED) { if (!angleFreefloatDeadband(DEGREES_TO_DECIDEGREES(navConfig()->fw.soaring_pitch_deadband), FD_PITCH)) { @@ -787,7 +786,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh #ifdef USE_AUTOTUNE_FIXED_WING if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) { - autotuneFixedWingUpdate(axis, rateTarget, pidState->gyroRate, constrainf(newPTerm + newFFTerm, -pidState->pidSumLimit, +pidState->pidSumLimit)); + autotuneFixedWingUpdate(axis, rateTarget, pidState->gyroRate, constrainf(newPTerm + newFFTerm, -limit, +limit)); } #endif @@ -836,9 +835,11 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid */ const float newCDTerm = rateTargetDeltaFiltered * pidState->kCD; + const uint16_t limit = getPidSumLimit(axis); + // TODO: Get feedback from mixer on available correction range for each axis const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm; - const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit); + const float newOutputLimited = constrainf(newOutput, -limit, +limit); float itermErrorRate = applyItermRelax(axis, rateTarget, rateError); @@ -850,7 +851,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; + float itermLimit = limit * pidProfile()->pidItermLimitPercent * 0.01f; pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } @@ -1284,14 +1285,12 @@ void pidInit(void) pidState[axis].axis = axis; if (axis == FD_YAW) { - pidState[axis].pidSumLimit = pidProfile()->pidSumLimitYaw; if (yawLpfHz) { pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) pt1FilterApply4; } else { pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) nullFilterApply4; } } else { - pidState[axis].pidSumLimit = pidProfile()->pidSumLimit; pidState[axis].ptermFilterApplyFn = (filterApply4FnPtr) nullFilterApply4; } } @@ -1408,3 +1407,11 @@ float getFixedWingLevelTrim(void) { return STATE(AIRPLANE) ? fixedWingLevelTrim : 0; } + +uint16_t getPidSumLimit(const flight_dynamics_index_t axis) { + if (axis == FD_YAW) { + return STATE(MULTIROTOR) ? 400 : 500; + } else { + return 500; + } +} \ No newline at end of file diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index e0a8b9d310..e088ccffad 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -115,8 +115,6 @@ typedef struct pidProfile_s { int16_t max_angle_inclination[ANGLE_INDEX_COUNT]; // Max possible inclination (roll and pitch axis separately - uint16_t pidSumLimit; - uint16_t pidSumLimitYaw; uint16_t pidItermLimitPercent; // Airplane-specific parameters @@ -221,3 +219,4 @@ bool isFixedWingLevelTrimActive(void); void updateFixedWingLevelTrim(timeUs_t currentTimeUs); float getFixedWingLevelTrim(void); bool isAngleHoldLevel(void); +uint16_t getPidSumLimit(const flight_dynamics_index_t axis); \ No newline at end of file diff --git a/src/main/flight/pid_autotune.c b/src/main/flight/pid_autotune.c index 140c4ab61d..af6896f423 100755 --- a/src/main/flight/pid_autotune.c +++ b/src/main/flight/pid_autotune.c @@ -171,7 +171,7 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa float gainFF = tuneCurrent[axis].gainFF; float maxDesiredRate = maxRateSetting; - const float pidSumLimit = (axis == FD_YAW) ? pidProfile()->pidSumLimitYaw : pidProfile()->pidSumLimit; + const float pidSumLimit = getPidSumLimit(axis); const float absDesiredRate = fabsf(desiredRate); const float absReachedRate = fabsf(reachedRate); const float absPidOutput = fabsf(pidOutput); diff --git a/src/main/flight/secondary_dynamic_gyro_notch.c b/src/main/flight/secondary_dynamic_gyro_notch.c index e3cfdced37..75d28bfc0f 100644 --- a/src/main/flight/secondary_dynamic_gyro_notch.c +++ b/src/main/flight/secondary_dynamic_gyro_notch.c @@ -44,46 +44,25 @@ void secondaryDynamicGyroNotchFiltersInit(secondaryDynamicGyroNotchState_t *stat state->enabled = gyroConfig()->dynamicGyroNotchMode != DYNAMIC_NOTCH_MODE_2D; state->looptime = getLooptime(); - if ( - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_R || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_RP || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_RY || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_3D - ) { + if (gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_3D) { /* * Enable ROLL filter */ biquadFilterInit(&state->filters[FD_ROLL], SECONDARY_DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, state->looptime, 1.0f, FILTER_NOTCH); state->filtersApplyFn[FD_ROLL] = (filterApplyFnPtr)biquadFilterApplyDF1; - } - - if ( - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_P || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_RP || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_PY || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_3D - ) { + /* * Enable PITCH filter */ biquadFilterInit(&state->filters[FD_PITCH], SECONDARY_DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, state->looptime, 1.0f, FILTER_NOTCH); state->filtersApplyFn[FD_PITCH] = (filterApplyFnPtr)biquadFilterApplyDF1; - } - - if ( - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_Y || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_PY || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_RY || - gyroConfig()->dynamicGyroNotchMode == DYNAMIC_NOTCH_MODE_3D - ) { + /* * Enable YAW filter */ biquadFilterInit(&state->filters[FD_YAW], SECONDARY_DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, state->looptime, 1.0f, FILTER_NOTCH); state->filtersApplyFn[FD_YAW] = (filterApplyFnPtr)biquadFilterApplyDF1; } - - } void secondaryDynamicGyroNotchFiltersUpdate(secondaryDynamicGyroNotchState_t *state, int axis, float frequency[]) { diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index dd120a2295..7067ac140f 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -293,13 +293,12 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_THR: return BF_SYM_THR; -/* case SYM_TEMP_F: - return BF_SYM_TEMP_F; + return BF_SYM_F; case SYM_TEMP_C: - return BF_SYM_TEMP_C; -*/ + return BF_SYM_C; + case SYM_BLANK: return BF_SYM_BLANK; /* diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 71c537b4c7..62c41683f0 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -73,7 +73,7 @@ #include "telemetry/telemetry.h" -PG_REGISTER_WITH_RESET_FN(ledStripConfig_t, ledStripConfig, PG_LED_STRIP_CONFIG, 1); +PG_REGISTER_WITH_RESET_FN(ledStripConfig_t, ledStripConfig, PG_LED_STRIP_CONFIG, 2); static bool ledStripInitialised = false; static bool ledStripEnabled = true; diff --git a/src/main/io/ledstrip.h b/src/main/io/ledstrip.h index 644409b9e0..204a4661d1 100644 --- a/src/main/io/ledstrip.h +++ b/src/main/io/ledstrip.h @@ -153,7 +153,6 @@ typedef struct ledStripConfig_s { hsvColor_t colors[LED_CONFIGURABLE_COLOR_COUNT]; modeColorIndexes_t modeColors[LED_MODE_COUNT]; specialColorIndexes_t specialColors; - uint8_t ledstrip_visual_beeper; // suppress LEDLOW mode if beeper is on } ledStripConfig_t; PG_DECLARE(ledStripConfig_t, ledStripConfig); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index e792d87b6d..15aac6a1d6 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -28,6 +28,7 @@ #include #include #include +#include #include "platform.h" @@ -114,6 +115,10 @@ #include "programming/logic_condition.h" #include "programming/global_variables.h" +#ifdef USE_BLACKBOX +#include "blackbox/blackbox_io.h" +#endif + #ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" #endif @@ -180,6 +185,12 @@ typedef struct statistic_s { int16_t min_rssi_dbm; // for CRSF int32_t max_altitude; uint32_t max_distance; + uint8_t min_sats; + uint8_t max_sats; + int16_t max_esc_temp; + int16_t min_esc_temp; + int32_t flightStartMAh; + int32_t flightStartMWh; } statistic_t; static statistic_t stats; @@ -212,7 +223,7 @@ static bool osdDisplayHasCanvas; #define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees) -PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 9); +PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 10); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); void osdStartedSaveProcess(void) { @@ -224,8 +235,6 @@ void osdShowEEPROMSavedNotification(void) { notify_settings_saved = millis() + 5000; } - - bool osdDisplayIsPAL(void) { return displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL; @@ -240,11 +249,14 @@ bool osdDisplayIsHD(void) return false; } - +bool osdIsNotMetric(void) { + return !(osdConfig()->units == OSD_UNIT_METRIC || osdConfig()->units == OSD_UNIT_METRIC_MPH); +} /* * Aligns text to the left side. Adds spaces at the end to keep string length unchanged. */ +/* -- Currently unused -- static void osdLeftAlignString(char *buff) { uint8_t sp = 0, ch = 0; @@ -252,7 +264,7 @@ static void osdLeftAlignString(char *buff) while (buff[sp] == ' ') sp++; for (ch = 0; ch < (len - sp); ch++) buff[ch] = buff[ch + sp]; for (sp = ch; sp < len; sp++) buff[sp] = ' '; -} +}*/ /* * This is a simplified distance conversion code that does not use any scaling @@ -487,8 +499,16 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) break; default: case OSD_UNIT_METRIC: - centivalue = CMSEC_TO_CENTIKPH(ws); - suffix = SYM_KMH; + if (osdConfig()->estimations_wind_mps) + { + centivalue = ws; + suffix = SYM_MS; + } + else + { + centivalue = CMSEC_TO_CENTIKPH(ws); + suffix = SYM_KMH; + } break; } @@ -827,7 +847,7 @@ void osdFormatPilotName(char *buff) static const char * osdArmingDisabledReasonMessage(void) { const char *message = NULL; - char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; + static char messageBuf[OSD_MESSAGE_LENGTH+1]; switch (isArmingDisabledReason()) { case ARMING_DISABLED_FAILSAFE_SYSTEM: @@ -901,8 +921,6 @@ static const char * osdArmingDisabledReasonMessage(void) return OSD_MESSAGE_STR(OSD_MSG_HW_FAIL); case ARMING_DISABLED_BOXFAILSAFE: return OSD_MESSAGE_STR(OSD_MSG_FS_EN); - case ARMING_DISABLED_BOXKILLSWITCH: - return OSD_MESSAGE_STR(OSD_MSG_KILL_SW_EN); case ARMING_DISABLED_RC_LINK: return OSD_MESSAGE_STR(OSD_MSG_NO_RC_LINK); case ARMING_DISABLED_THROTTLE: @@ -986,7 +1004,7 @@ static const char * osdFailsafePhaseMessage(void) static const char * osdFailsafeInfoMessage(void) { - if (failsafeIsReceivingRxData()) { + if (failsafeIsReceivingRxData() && !FLIGHT_MODE(NAV_FW_AUTOLAND)) { // User must move sticks to exit FS mode return OSD_MESSAGE_STR(OSD_MSG_MOVE_EXIT_FS); } @@ -1991,6 +2009,27 @@ static bool osdDrawSingleElement(uint8_t item) osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); break; + case OSD_BLACKBOX: + { +#ifdef USE_BLACKBOX + if (IS_RC_MODE_ACTIVE(BOXBLACKBOX)) { + if (!isBlackboxDeviceWorking()) { + tfp_sprintf(buff, "%c%c", SYM_BLACKBOX, SYM_ALERT); + } else if (isBlackboxDeviceFull()) { + tfp_sprintf(buff, "%cFULL", SYM_BLACKBOX); + } else { + int32_t logNumber = blackboxGetLogNumber(); + if (logNumber >= 0) { + tfp_sprintf(buff, "%c%05" PRId32, SYM_BLACKBOX, logNumber); + } else { + tfp_sprintf(buff, "%c", SYM_BLACKBOX); + } + } + } +#endif // USE_BLACKBOX + } + break; + case OSD_ODOMETER: { displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_ODOMETER); @@ -2362,7 +2401,7 @@ static bool osdDrawSingleElement(uint8_t item) { char *p = "ACRO"; #ifdef USE_FW_AUTOLAND - if (isFwLandInProgess()) + if (FLIGHT_MODE(NAV_FW_AUTOLAND)) p = "LAND"; else #endif @@ -2726,7 +2765,7 @@ static bool osdDrawSingleElement(uint8_t item) // mAh/foot if (efficiencyValid) { osdFormatCentiNumber(buff, (value * METERS_PER_FOOT), 1, 2, 2, 3, false); - tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_FT_0, SYM_AH_V_FT_1); + tfp_sprintf(buff + strlen(buff), "%c%c", SYM_AH_V_FT_0, SYM_AH_V_FT_1); } else { buff[0] = buff[1] = buff[2] = '-'; buff[3] = SYM_AH_V_FT_0; @@ -2740,7 +2779,7 @@ static bool osdDrawSingleElement(uint8_t item) // mAh/metre if (efficiencyValid) { osdFormatCentiNumber(buff, value, 1, 2, 2, 3, false); - tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_M_0, SYM_AH_V_M_1); + tfp_sprintf(buff + strlen(buff), "%c%c", SYM_AH_V_M_0, SYM_AH_V_M_1); } else { buff[0] = buff[1] = buff[2] = '-'; buff[3] = SYM_AH_V_M_0; @@ -3203,9 +3242,9 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_IMPERIAL: moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, digits, false); if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); + tfp_sprintf(buff + strlen(buff), "%c%c", SYM_MAH_MI_0, SYM_MAH_MI_1); } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); + tfp_sprintf(buff + strlen(buff), "%c", SYM_AH_MI); } if (!efficiencyValid) { buff[0] = buff[1] = buff[2] = buff[3] = '-'; @@ -3217,9 +3256,9 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_GA: moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, digits, false); if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); + tfp_sprintf(buff + strlen(buff), "%c%c", SYM_MAH_NM_0, SYM_MAH_NM_1); } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); + tfp_sprintf(buff + strlen(buff), "%c", SYM_AH_NM); } if (!efficiencyValid) { buff[0] = buff[1] = buff[2] = buff[3] = '-'; @@ -3233,9 +3272,9 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_METRIC: moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, digits, false); if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); + tfp_sprintf(buff + strlen(buff), "%c%c", SYM_MAH_KM_0, SYM_MAH_KM_1); } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); + tfp_sprintf(buff + strlen(buff), "%c", SYM_AH_KM); } if (!efficiencyValid) { buff[0] = buff[1] = buff[2] = buff[3] = '-'; @@ -3954,8 +3993,8 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .force_grid = SETTING_OSD_FORCE_GRID_DEFAULT, .stats_energy_unit = SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT, - .stats_min_voltage_unit = SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT, - .stats_page_auto_swap_time = SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT + .stats_page_auto_swap_time = SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT, + .stats_show_metric_efficiency = SETTING_OSD_STATS_SHOW_METRIC_EFFICIENCY_DEFAULT ); void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) @@ -4121,6 +4160,10 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_POWER_LIMIT] = OSD_POS(3, 6); #endif +#ifdef USE_BLACKBOX + osdLayoutsConfig->item_pos[0][OSD_BLACKBOX] = OSD_POS(2, 10); +#endif + // Under OSD_FLYMODE. TODO: Might not be visible on NTSC? osdLayoutsConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG; @@ -4195,83 +4238,154 @@ uint8_t drawLogos(bool singular, uint8_t row) { return logoRow; } -uint8_t drawStats(uint8_t row) { #ifdef USE_STATS - char string_buffer[30]; - uint8_t statNameX = (osdDisplayPort->cols - 22) / 2; - uint8_t statValueX = statNameX + 21; +uint8_t drawStat_Stats(uint8_t statNameX, uint8_t row, uint8_t statValueX, bool isBootStats) +{ + uint8_t buffLen = 0; + char string_buffer[osdDisplayPort->cols - statValueX]; if (statsConfig()->stats_enabled) { - displayWrite(osdDisplayPort, statNameX, row, "ODOMETER:"); + if (isBootStats) + displayWrite(osdDisplayPort, statNameX, row, "ODOMETER:"); + else + displayWrite(osdDisplayPort, statNameX, row, "ODOMETER"); + switch (osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); - string_buffer[5] = SYM_MI; + if (isBootStats) { + tfp_sprintf(string_buffer, "%5d", (uint16_t)(statsConfig()->stats_total_dist / METERS_PER_MILE)); + buffLen = 5; + } else { + uint16_t statTotalDist = (uint16_t)(statsConfig()->stats_total_dist / METERS_PER_MILE); + tfp_sprintf(string_buffer, ": %d", statTotalDist); + buffLen = 3 + sizeof(statTotalDist); + } + + string_buffer[buffLen++] = SYM_MI; break; default: case OSD_UNIT_GA: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE)); - string_buffer[5] = SYM_NM; + if (isBootStats) { + tfp_sprintf(string_buffer, "%5d", (uint16_t)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE)); + buffLen = 5; + } else { + uint16_t statTotalDist = (uint16_t)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE); + tfp_sprintf(string_buffer, ": %d", statTotalDist); + buffLen = 3 + sizeof(statTotalDist); + } + + string_buffer[buffLen++] = SYM_NM; break; case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); - string_buffer[5] = SYM_KM; + if (isBootStats) { + tfp_sprintf(string_buffer, "%5d", (uint16_t)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); + buffLen = 5; + } else { + uint16_t statTotalDist = (uint16_t)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER); + tfp_sprintf(string_buffer, ": %d", statTotalDist); + buffLen = 3 + sizeof(statTotalDist); + } + + string_buffer[buffLen++] = SYM_KM; break; } - string_buffer[6] = '\0'; - displayWrite(osdDisplayPort, statValueX-5, row, string_buffer); + string_buffer[buffLen] = '\0'; + displayWrite(osdDisplayPort, statValueX-(isBootStats ? 5 : 0), row, string_buffer); - displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL TIME:"); + if (isBootStats) + displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL TIME:"); + else + displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL TIME"); + uint32_t tot_mins = statsConfig()->stats_total_time / 60; - tfp_sprintf(string_buffer, "%2d:%02dH:M", (int)(tot_mins / 60), (int)(tot_mins % 60)); - displayWrite(osdDisplayPort, statValueX-7, row, string_buffer); + if (isBootStats) + tfp_sprintf(string_buffer, "%d:%02dH:M%c", (int)(tot_mins / 60), (int)(tot_mins % 60), '\0'); + else + tfp_sprintf(string_buffer, ": %d:%02d H:M%c", (int)(tot_mins / 60), (int)(tot_mins % 60), '\0'); + + displayWrite(osdDisplayPort, statValueX-(isBootStats ? 7 : 0), row, string_buffer); #ifdef USE_ADC - if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { - displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL ENERGY:"); - osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4, false); - displayWrite(osdDisplayPort, statValueX-4, row, string_buffer); - displayWriteChar(osdDisplayPort, statValueX, row, SYM_WH); + if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER) && statsConfig()->stats_total_energy) { + uint8_t buffOffset = 0; + if (isBootStats) + displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL ENERGY:"); + else { + displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL ENERGY"); + string_buffer[0] = ':'; + buffOffset = 2; + } + + osdFormatCentiNumber(string_buffer + buffOffset, statsConfig()->stats_total_energy / 10, 0, 2, 0, 6, true); + displayWrite(osdDisplayPort, statValueX - (isBootStats ? 6 : 0), row, string_buffer); + displayWriteChar(osdDisplayPort, statValueX + (isBootStats ? 0 : 8), row, SYM_WH); + + char avgEffBuff[osdDisplayPort->cols - statValueX]; + + for (uint8_t i = 0; i < osdDisplayPort->cols - statValueX; i++) { + avgEffBuff[i] = '\0'; + string_buffer[i] = '\0'; + } - displayWrite(osdDisplayPort, statNameX, ++row, "AVG EFFICIENCY:"); if (statsConfig()->stats_total_dist) { - uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km + if (isBootStats) + displayWrite(osdDisplayPort, statNameX, ++row, "AVG EFFICIENCY:"); + else { + displayWrite(osdDisplayPort, statNameX, ++row, "AVG EFFICIENCY"); + strcat(avgEffBuff, ": "); + } + + float_t avg_efficiency = MWH_TO_WH(statsConfig()->stats_total_energy) / METERS_TO_KILOMETERS(statsConfig()->stats_total_dist); // Wh/km switch (osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3, false); - string_buffer[3] = SYM_WH_MI; + osdFormatCentiNumber(string_buffer, (int32_t)(avg_efficiency * METERS_PER_MILE / 10), 0, 2, 2, 4, false); + string_buffer[4] = SYM_WH_MI; break; case OSD_UNIT_GA: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3, false); - string_buffer[3] = SYM_WH_NM; + osdFormatCentiNumber(string_buffer, (int32_t)(avg_efficiency * METERS_PER_NAUTICALMILE / 10), 0, 2, 2, 4, false); + string_buffer[4] = SYM_WH_NM; break; default: case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3, false); - string_buffer[3] = SYM_WH_KM; + osdFormatCentiNumber(string_buffer, (int32_t)(avg_efficiency * 100), 0, 2, 2, 4, false); + string_buffer[4] = SYM_WH_KM; break; } + + if (isBootStats) + strcat(avgEffBuff, string_buffer); + else + strcat(avgEffBuff, osdFormatTrimWhiteSpace(string_buffer)); } else { - string_buffer[0] = string_buffer[1] = string_buffer[2] = '-'; + strcat(avgEffBuff, "----"); } - string_buffer[4] = '\0'; - displayWrite(osdDisplayPort, statValueX-3, row++, string_buffer); + + displayWrite(osdDisplayPort, statValueX-(isBootStats ? 4 : 0), row++, avgEffBuff); } #endif // USE_ADC } -#endif // USE_STATS return row; } -static void osdSetNextRefreshIn(uint32_t timeMs) { +uint8_t drawStats(uint8_t row) +{ + uint8_t statNameX = (osdDisplayPort->cols - 22) / 2; + uint8_t statValueX = statNameX + 21; + + return drawStat_Stats(statNameX, row, statValueX, true); +} +#endif // USE STATS + +static void osdSetNextRefreshIn(uint32_t timeMs) +{ resumeRefreshAt = micros() + timeMs * 1000; refreshWaitForResumeCmdRelease = true; } @@ -4358,16 +4472,29 @@ void osdInit(displayPort_t *osdDisplayPortToUse) static void osdResetStats(void) { + // Reset internal OSD stats + stats.max_distance = 0; stats.max_current = 0; stats.max_power = 0; stats.max_speed = 0; stats.max_3D_speed = 0; stats.max_air_speed = 0; - stats.min_voltage = 5000; + stats.min_voltage = 12000; stats.min_rssi = 99; stats.min_lq = 300; stats.min_rssi_dbm = 0; stats.max_altitude = 0; + stats.min_sats = 255; + stats.max_sats = 0; + stats.min_esc_temp = 300; + stats.max_esc_temp = 0; + stats.flightStartMAh = getMAhDrawn(); + stats.flightStartMWh = getMWhDrawn(); + + // Reset external stats + posControl.totalTripDistance = 0.0f; + resetFlightTime(); + resetGForceStats(); } static void osdUpdateStats(void) @@ -4389,7 +4516,27 @@ static void osdUpdateStats(void) if (stats.max_distance < GPS_distanceToHome) stats.max_distance = GPS_distanceToHome; + + if (stats.min_sats > gpsSol.numSat) + stats.min_sats = gpsSol.numSat; + + if (stats.max_sats < gpsSol.numSat) + stats.max_sats = gpsSol.numSat; } +#if defined(USE_ESC_SENSOR) + if (STATE(ESC_SENSOR_ENABLED)) { + escSensorData_t * escSensor = escSensorGetData(); + bool escTemperatureValid = escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE; + + if (escTemperatureValid) { + if (stats.min_esc_temp > escSensor->temperature) + stats.min_esc_temp = escSensor->temperature; + + if (stats.max_esc_temp < escSensor->temperature) + stats.max_esc_temp = escSensor->temperature; + } + } +#endif value = getBatteryVoltage(); if (stats.min_voltage > value) @@ -4421,16 +4568,433 @@ static void osdUpdateStats(void) stats.max_altitude = MAX(stats.max_altitude, osdGetAltitude()); } +uint8_t drawStat_FlightTime(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + displayWrite(osdDisplayPort, col, row, "FLIGHT TIME"); + uint16_t flySeconds = getFlightTime(); + uint16_t flyMinutes = flySeconds / 60; + flySeconds %= 60; + uint16_t flyHours = flyMinutes / 60; + flyMinutes %= 60; + tfp_sprintf(buff, ": %02u:%02u:%02u", flyHours, flyMinutes, flySeconds); + displayWrite(osdDisplayPort, statValX, row++, buff); + + return row; +} + +uint8_t drawStat_FlightDistance(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + + displayWrite(osdDisplayPort, col, row, "FLIGHT DISTANCE"); + tfp_sprintf(buff, ": "); + osdFormatDistanceStr(buff + 2, getTotalTravelDistance()); + displayWrite(osdDisplayPort, statValX, row++, buff); + + return row; +} + +uint8_t drawStat_MaxDistanceFromHome(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + uint8_t valueXOffset = 0; + if (!osdDisplayIsHD()) { + displayWrite(osdDisplayPort, col, row, "DISTANCE FROM "); + valueXOffset = 14; + } else { + displayWrite(osdDisplayPort, col, row, "MAX DISTANCE FROM "); + valueXOffset = 18; + } + displayWriteChar(osdDisplayPort, col + valueXOffset, row, SYM_HOME); + tfp_sprintf(buff, ": "); + osdFormatDistanceStr(buff + 2, stats.max_distance * 100); + displayWrite(osdDisplayPort, statValX, row++, buff); + + return row; +} + +uint8_t drawStat_Speed(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + char buff2[12]; + uint8_t multiValueXOffset = 0; + + displayWrite(osdDisplayPort, col, row, "MAX/AVG SPEED"); + + osdFormatVelocityStr(buff2, stats.max_3D_speed, true, false); + tfp_sprintf(buff, ": %s/", osdFormatTrimWhiteSpace(buff2)); + multiValueXOffset = strlen(buff); + displayWrite(osdDisplayPort, statValX, row, buff); + + osdGenerateAverageVelocityStr(buff2); + displayWrite(osdDisplayPort, statValX + multiValueXOffset, row++, osdFormatTrimWhiteSpace(buff2)); + + return row; +} + +uint8_t drawStat_MaximumAltitude(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + displayWrite(osdDisplayPort, col, row, "MAX ALTITUDE"); + tfp_sprintf(buff, ": "); + osdFormatAltitudeStr(buff + 2, stats.max_altitude); + displayWrite(osdDisplayPort, statValX, row++, buff); + + return row; +} + +uint8_t drawStat_BatteryVoltage(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + uint8_t multiValueXOffset = 0; + if (!osdDisplayIsHD()) + displayWrite(osdDisplayPort, col, row, "MIN VOLTS P/C"); + else + displayWrite(osdDisplayPort, col, row, "MIN VOLTS PACK/CELL"); + + // Pack voltage + tfp_sprintf(buff, ": "); + osdFormatCentiNumber(buff + 2, stats.min_voltage, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2, false); + strcat(osdFormatTrimWhiteSpace(buff), "/"); + multiValueXOffset = strlen(buff); + // AverageCell + osdFormatCentiNumber(buff + multiValueXOffset, stats.min_voltage / getBatteryCellCount(), 0, 2, 0, 3, false); + tfp_sprintf(buff + strlen(buff), "%c", SYM_VOLT); + + displayWrite(osdDisplayPort, statValX, row++, buff); + + return row; +} + +uint8_t drawStat_MaximumPowerAndCurrent(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + char outBuff[12]; + tfp_sprintf(outBuff, ": "); + osdFormatCentiNumber(buff, stats.max_current, 0, 2, 0, 3, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + strcat(outBuff, "/"); + bool kiloWatt = osdFormatCentiNumber(buff, stats.max_power, 1000, 2, 2, 3, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + displayWrite(osdDisplayPort, statValX, row, outBuff); + + if (kiloWatt) + displayWrite(osdDisplayPort, col, row, "MAX AMPS/K WATTS"); + else + displayWrite(osdDisplayPort, col, row, "MAX AMPS/WATTS"); + + return ++row; +} + +uint8_t drawStat_UsedEnergy(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + + if (osdDisplayIsHD()) + displayWrite(osdDisplayPort, col, row, "USED ENERGY FLT/TOT"); + else + displayWrite(osdDisplayPort, col, row, "USED ENERGY F/T"); + tfp_sprintf(buff, ": "); + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + tfp_sprintf(buff + 2, "%d/%d%c", (int)(getMAhDrawn() - stats.flightStartMAh), (int)getMAhDrawn(), SYM_MAH); + } else { + char preBuff[12]; + osdFormatCentiNumber(preBuff, (getMWhDrawn() - stats.flightStartMWh) / 10, 0, 2, 0, 3, false); + strcat(buff, osdFormatTrimWhiteSpace(preBuff)); + strcat(buff, "/"); + osdFormatCentiNumber(preBuff, getMWhDrawn() / 10, 0, 2, 0, 3, false); + strcat(buff, osdFormatTrimWhiteSpace(preBuff)); + tfp_sprintf(buff + strlen(buff), "%s%c", buff, SYM_WH); + } + displayWrite(osdDisplayPort, statValX, row++, buff); + + return row; +} + +uint8_t drawStat_AverageEfficiency(uint8_t col, uint8_t row, uint8_t statValX, bool forceMetric) +{ + char buff[15]; + char outBuff[15]; + int32_t totalDistance = getTotalTravelDistance(); + bool moreThanAh = false; + bool efficiencyValid = totalDistance >= 10000; + + if (osdDisplayIsHD()) + displayWrite(osdDisplayPort, col, row, "AVG EFFICIENCY FLT/TOT"); + else + displayWrite(osdDisplayPort, col, row, "AV EFFICIENCY F/T"); + + tfp_sprintf(outBuff, ": "); + uint8_t digits = 3U; // Total number of digits (including decimal point) +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values + if (isBfCompatibleVideoSystem(osdConfig())) { + // Add one digit so no switch to scaled decimal occurs above 99 + digits = 4U; + } +#endif + if (!forceMetric) { + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + if (efficiencyValid) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)((getMAhDrawn() - stats.flightStartMAh) * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + if (osdDisplayIsHD()) { + if (!moreThanAh) + tfp_sprintf(outBuff + strlen(outBuff), "%c%c", SYM_MAH_MI_0, SYM_MAH_MI_1); + else + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_AH_MI); + + moreThanAh = false; + } + + strcat(outBuff, "/"); + moreThanAh = moreThanAh || osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + + if (!moreThanAh) + tfp_sprintf(outBuff + strlen(outBuff), "%c%c", SYM_MAH_MI_0, SYM_MAH_MI_1); + else + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_AH_MI); + } else { + tfp_sprintf(outBuff + strlen(outBuff), "---/---%c%c", SYM_MAH_MI_0, SYM_MAH_MI_1); + } + } else { + if (efficiencyValid) { + osdFormatCentiNumber(buff, (int32_t)((getMWhDrawn() - stats.flightStartMWh) * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + strcat(outBuff, "/"); + osdFormatCentiNumber(buff + strlen(buff), (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + } else { + strcat(outBuff, "---/---"); + } + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_WH_MI); + } + break; + case OSD_UNIT_GA: + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + if (efficiencyValid) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)((getMAhDrawn()-stats.flightStartMAh) * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + if (osdDisplayIsHD()) { + if (!moreThanAh) + tfp_sprintf(outBuff + strlen(outBuff), "%c%c", SYM_MAH_NM_0, SYM_MAH_NM_1); + else + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_AH_NM); + + moreThanAh = false; + } + + strcat(outBuff, "/"); + moreThanAh = moreThanAh || osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + if (!moreThanAh) { + tfp_sprintf(outBuff + strlen(outBuff), "%c%c", SYM_MAH_NM_0, SYM_MAH_NM_1); + } else { + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_AH_NM); + } + } else { + tfp_sprintf(outBuff + strlen(outBuff), "---/---%c%c", SYM_MAH_NM_0, SYM_MAH_NM_1); + } + } else { + if (efficiencyValid) { + osdFormatCentiNumber(buff, (int32_t)((getMWhDrawn()-stats.flightStartMWh) * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + strcat(outBuff, "/"); + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + } else { + strcat(outBuff, "---/---"); + } + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_WH_NM); + } + break; + case OSD_UNIT_METRIC_MPH: + case OSD_UNIT_METRIC: + forceMetric = true; + break; + } + } + + if (forceMetric) { + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + if (efficiencyValid) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)((getMAhDrawn() - stats.flightStartMAh) * 10000000.0f / totalDistance), 1000, 0, 2, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + if (osdDisplayIsHD()) { + if (!moreThanAh) + tfp_sprintf(outBuff + strlen(outBuff), "%c%c", SYM_MAH_KM_0, SYM_MAH_KM_1); + else + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_AH_KM); + + moreThanAh = false; + } + + strcat(outBuff, "/"); + moreThanAh = moreThanAh || osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + if (!moreThanAh) { + tfp_sprintf(outBuff + strlen(outBuff), "%c%c", SYM_MAH_KM_0, SYM_MAH_KM_1); + } else { + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_AH_KM); + } + } else { + tfp_sprintf(outBuff + strlen(outBuff), "---/---%c%c", SYM_MAH_KM_0, SYM_MAH_KM_1); + } + } else { + if (efficiencyValid) { + osdFormatCentiNumber(buff, (int32_t)((getMWhDrawn() - stats.flightStartMWh) * 10000.0f / totalDistance), 0, 2, 0, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + strcat(outBuff, "/"); + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + } else { + strcat(outBuff, "---/---"); + } + tfp_sprintf(outBuff + strlen(outBuff), "%c", SYM_WH_KM); + } + } + + tfp_sprintf(outBuff + strlen(outBuff), "%c", '\0'); + displayWrite(osdDisplayPort, statValX, row++, outBuff); + + return row; +} + +uint8_t drawStat_RXStats(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[20]; + uint8_t multiValueXOffset = 0; + + tfp_sprintf(buff, "MIN RSSI"); + if (rxConfig()->serialrx_provider == SERIALRX_CRSF) { + strcat(buff, "/LQ"); + + if (osdDisplayIsHD()) + strcat(buff, "/DBM"); + } + displayWrite(osdDisplayPort, col, row, buff); + + memset(buff, '\0', strlen(buff)); + tfp_sprintf(buff, ": "); + itoa(stats.min_rssi, buff + 2, 10); + strcat(osdFormatTrimWhiteSpace(buff), "%"); + + if (rxConfig()->serialrx_provider == SERIALRX_CRSF) { + strcat(osdFormatTrimWhiteSpace(buff), "/"); + multiValueXOffset = strlen(buff); + itoa(stats.min_lq, buff + multiValueXOffset, 10); + strcat(osdFormatTrimWhiteSpace(buff), "%"); + + if (osdDisplayIsHD()) { + strcat(osdFormatTrimWhiteSpace(buff), "/"); + itoa(stats.min_rssi_dbm, buff + 2, 10); + tfp_sprintf(buff + strlen(buff), "%c", SYM_DBM); + displayWrite(osdDisplayPort, statValX, row++, buff); + } + } + + displayWrite(osdDisplayPort, statValX, row++, buff); + + if (!osdDisplayIsHD() && rxConfig()->serialrx_provider == SERIALRX_CRSF) { + displayWrite(osdDisplayPort, col, row, "MIN RX DBM"); + memset(buff, '\0', strlen(buff)); + tfp_sprintf(buff, ": "); + itoa(stats.min_rssi_dbm, buff + 2, 10); + tfp_sprintf(buff + strlen(buff), "%c", SYM_DBM); + displayWrite(osdDisplayPort, statValX, row++, buff); + } + + return row; +} + +uint8_t drawStat_GPS(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + displayWrite(osdDisplayPort, col, row, "MIN/MAX GPS SATS"); + tfp_sprintf(buff, ": %u/%u", stats.min_sats, stats.max_sats); + displayWrite(osdDisplayPort, statValX, row++, buff); + + return row; +} + +uint8_t drawStat_ESCTemperature(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + displayWrite(osdDisplayPort, col, row, "MIN/MAX ESC TEMP"); + tfp_sprintf(buff, ": %3d/%3d%c", + ((osdConfig()->units == OSD_UNIT_IMPERIAL) ? (int16_t)(stats.min_esc_temp * 9 / 5.0f + 320) : stats.min_esc_temp), + ((osdConfig()->units == OSD_UNIT_IMPERIAL) ? (int16_t)(stats.max_esc_temp * 9 / 5.0f + 320) : stats.max_esc_temp), + ((osdConfig()->units == OSD_UNIT_IMPERIAL) ? SYM_TEMP_F : SYM_TEMP_C)); + displayWrite(osdDisplayPort, statValX, row++, buff); + + return row; +} + +uint8_t drawStat_GForce(uint8_t col, uint8_t row, uint8_t statValX) +{ + char buff[12]; + char outBuff[12]; + + const float max_gforce = accGetMeasuredMaxG(); + const acc_extremes_t *acc_extremes = accGetMeasuredExtremes(); + const float acc_extremes_min = acc_extremes[Z].min; + const float acc_extremes_max = acc_extremes[Z].max; + + if (!osdDisplayIsHD()) + displayWrite(osdDisplayPort, col, row, "MAX G-FORCE"); + else + displayWrite(osdDisplayPort, col, row, "MAX/MIN Z/MAX Z G-FORCE"); + + tfp_sprintf(outBuff, ": "); + osdFormatCentiNumber(buff, max_gforce * 100, 0, 2, 0, 3, false); + + if (!osdDisplayIsHD()) { + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + displayWrite(osdDisplayPort, statValX, row++, outBuff); + + displayWrite(osdDisplayPort, col, row, "MIN/MAX Z G-FORCE"); + memset(outBuff, '\0', strlen(outBuff)); + tfp_sprintf(outBuff, ": "); + } else { + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + strcat(outBuff, "/"); + } + osdFormatCentiNumber(buff, acc_extremes_min * 100, 0, 2, 0, 4, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + strcat(outBuff, "/"); + + osdFormatCentiNumber(buff, acc_extremes_max * 100, 0, 2, 0, 3, false); + strcat(outBuff, osdFormatTrimWhiteSpace(buff)); + displayWrite(osdDisplayPort, statValX, row++, outBuff); + + return row; +} + +uint8_t drawStat_DisarmMethod(uint8_t col, uint8_t row, uint8_t statValX) +{ + // We keep "" for backward compatibility with the Blackbox explorer and other potential usages + const char * disarmReasonStr[DISARM_REASON_COUNT] = { "UNKNOWN", "TIMEOUT", "STICKS", "SWITCH", "SWITCH", "", "FAILSAFE", "NAV SYS", "LANDING"}; + + displayWrite(osdDisplayPort, col, row, "DISARMED BY"); + displayWrite(osdDisplayPort, statValX, row, ": "); + displayWrite(osdDisplayPort, statValX + 2, row++, disarmReasonStr[getDisarmReason()]); + + return row; +} + static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) { - const char * disarmReasonStr[DISARM_REASON_COUNT] = { "UNKNOWN", "TIMEOUT", "STICKS", "SWITCH", "SWITCH", "KILLSW", "FAILSAFE", "NAV SYS", "LANDING"}; - uint8_t top = 1; // Start one line down leaving space at the top of the screen. - size_t multiValueLengthOffset = 0; - - const uint8_t statNameX = osdDisplayIsHD() ? 11 : 1; - const uint8_t statValuesX = osdDisplayIsHD() ? 30 : 20; - char buff[10]; + const char * statsHeader[2] = {"*** STATS 1/2 -> ***", "*** STATS <- 2/2 ***"}; + uint8_t row = 1; // Start one line down leaving space at the top of the screen. + const uint8_t statNameX = (osdDisplayPort->cols - (osdDisplayIsHD() ? 41 : 28)) / 2; + const uint8_t statValuesX = osdDisplayPort->cols - statNameX - (osdDisplayIsHD() ? 15 : 11); + if (page > 1) page = 0; @@ -4438,247 +5002,111 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) displayClearScreen(osdDisplayPort); if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS ---"); - } else if (page == 0) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- 1/2 ->"); - } else if (page == 1) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- <- 2/2"); - } - - if (isSinglePageStatsCompatible || page == 0) { - if (feature(FEATURE_GPS)) { - if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top, "MAX/AVG SPEED :"); - osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff),"/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - osdGenerateAverageVelocityStr(buff); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MAX SPEED :"); - osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - - displayWrite(osdDisplayPort, statNameX, top, "AVG SPEED :"); - osdGenerateAverageVelocityStr(buff); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } - - displayWrite(osdDisplayPort, statNameX, top, "MAX DISTANCE :"); - osdFormatDistanceStr(buff, stats.max_distance*100); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - - displayWrite(osdDisplayPort, statNameX, top, "TRAVELED DISTANCE:"); - osdFormatDistanceStr(buff, getTotalTravelDistance()); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + char buff[25]; + tfp_sprintf(buff, "*** STATS "); +#ifdef USE_BLACKBOX +#ifdef USE_SDCARD + if (feature(FEATURE_BLACKBOX)) { + int32_t logNumber = blackboxGetLogNumber(); + if (logNumber >= 0) + tfp_sprintf(buff + strlen(buff), " %c%05" PRId32 " ", SYM_BLACKBOX, logNumber); + else + tfp_sprintf(buff + strlen(buff), " %c ", SYM_BLACKBOX); } +#endif +#endif + strcat(buff, "***"); - displayWrite(osdDisplayPort, statNameX, top, "MAX ALTITUDE :"); - osdFormatAltitudeStr(buff, stats.max_altitude); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buff)) / 2, row++, buff); + } else + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(statsHeader[page + 1])) / 2, row++, statsHeader[page]); - switch (rxConfig()->serialrx_provider) { - case SERIALRX_CRSF: - if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI %/DBM :"); - itoa(stats.min_rssi, buff, 10); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff), "%/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - itoa(stats.min_rssi_dbm, buff, 10); - tfp_sprintf(buff, "%s%c", buff, SYM_DBM); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI % :"); - itoa(stats.min_rssi, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + if (isSinglePageStatsCompatible) { + // Top 15 rows for most important stats. Max 19 rows (WTF) + row = drawStat_FlightTime(statNameX, row, statValuesX); // 1 row + row = drawStat_FlightDistance(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_GPS)) row = drawStat_MaxDistanceFromHome(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_GPS)) row = drawStat_Speed(statNameX, row, statValuesX); // 1 row + row = drawStat_MaximumAltitude(statNameX, row, statValuesX); // 1 row + row = drawStat_BatteryVoltage(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_CURRENT_METER)) row = drawStat_MaximumPowerAndCurrent(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_CURRENT_METER)) row = drawStat_UsedEnergy(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_CURRENT_METER) && feature(FEATURE_GPS)) row = drawStat_AverageEfficiency(statNameX, row, statValuesX, false); // 1 row + if (osdConfig()->stats_show_metric_efficiency && osdIsNotMetric() && feature(FEATURE_CURRENT_METER) && feature(FEATURE_GPS)) row = drawStat_AverageEfficiency(statNameX, row, statValuesX, true); // 1 row + row = drawStat_RXStats(statNameX, row, statValuesX); // 1 row if non-CRSF else 2 rows + if (feature(FEATURE_GPS)) row = drawStat_GPS(statNameX, row, statValuesX); // 1 row + if (STATE(ESC_SENSOR_ENABLED)) row = drawStat_ESCTemperature(statNameX, row, statValuesX); // 1 row - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI DBM :"); - itoa(stats.min_rssi_dbm, buff, 10); - tfp_sprintf(buff, "%s%c", buff, SYM_DBM); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } - - displayWrite(osdDisplayPort, statNameX, top, "MIN LQ :"); - itoa(stats.min_lq, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + // Draw these if there is space space + if (row < (osdDisplayPort->cols-3)) row = drawStat_GForce(statNameX, row, statValuesX); // 1 row HD or 2 rows SD +#ifdef USE_STATS + if (row < (osdDisplayPort->cols-7) && statsConfig()->stats_enabled) row = drawStat_Stats(statNameX, row, statValuesX, false); // 4 rows +#endif + } else { + switch (page) { + case 0: + // Max 10 rows + row = drawStat_FlightTime(statNameX, row, statValuesX); // 1 row + row = drawStat_FlightDistance(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_GPS)) row = drawStat_MaxDistanceFromHome(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_GPS)) row = drawStat_Speed(statNameX, row, statValuesX); // 1 row + row = drawStat_MaximumAltitude(statNameX, row, statValuesX); // 1 row + row = drawStat_BatteryVoltage(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_CURRENT_METER)) row = drawStat_MaximumPowerAndCurrent(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_CURRENT_METER))row = drawStat_UsedEnergy(statNameX, row, statValuesX); // 1 row + if (feature(FEATURE_CURRENT_METER) && feature(FEATURE_GPS)) row = drawStat_AverageEfficiency(statNameX, row, statValuesX, false); // 1 row + if (feature(FEATURE_GPS))row = drawStat_GPS(statNameX, row, statValuesX); // 1 row break; - default: - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI :"); - itoa(stats.min_rssi, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + case 1: + // Max 10 rows + row = drawStat_RXStats(statNameX, row, statValuesX); // 1 row if non-CRSF else 2 rows + if (STATE(ESC_SENSOR_ENABLED)) row = drawStat_ESCTemperature(statNameX, row, statValuesX); // 1 row + row = drawStat_GForce(statNameX, row, statValuesX); // 1 row HD or 2 rows SD + if (osdConfig()->stats_show_metric_efficiency && osdIsNotMetric() && feature(FEATURE_CURRENT_METER) && feature(FEATURE_GPS)) row = drawStat_AverageEfficiency(statNameX, row, statValuesX, true); // 1 row +#ifdef USE_BLACKBOX +#ifdef USE_SDCARD + if (feature(FEATURE_BLACKBOX)) { + char buff[12]; + displayWrite(osdDisplayPort, statNameX, row, "BLACKBOX FILE"); + + tfp_sprintf(buff, ": %u/%u", stats.min_sats, stats.max_sats); + + int32_t logNumber = blackboxGetLogNumber(); + if (logNumber >= 0) + tfp_sprintf(buff, ": %05ld ", logNumber); + else + strcat(buff, ": INVALID"); - displayWrite(osdDisplayPort, statNameX, top, "FLY TIME :"); - uint16_t flySeconds = getFlightTime(); - uint16_t flyMinutes = flySeconds / 60; - flySeconds %= 60; - uint16_t flyHours = flyMinutes / 60; - flyMinutes %= 60; - tfp_sprintf(buff, "%02u:%02u:%02u", flyHours, flyMinutes, flySeconds); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - - displayWrite(osdDisplayPort, statNameX, top, "DISARMED BY :"); - displayWrite(osdDisplayPort, statValuesX, top++, disarmReasonStr[getDisarmReason()]); - } - - if (isSinglePageStatsCompatible || page == 1) { - if (osdConfig()->stats_min_voltage_unit == OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY) { - displayWrite(osdDisplayPort, statNameX, top, "MIN BATTERY VOLT :"); - osdFormatCentiNumber(buff, stats.min_voltage, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2, false); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MIN CELL VOLTAGE :"); - osdFormatCentiNumber(buff, stats.min_voltage/getBatteryCellCount(), 0, 2, 0, 3, false); - } - tfp_sprintf(buff, "%s%c", buff, SYM_VOLT); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - - if (feature(FEATURE_CURRENT_METER)) { - displayWrite(osdDisplayPort, statNameX, top, "MAX CURRENT :"); - osdFormatCentiNumber(buff, stats.max_current, 0, 2, 0, 3, false); - tfp_sprintf(buff, "%s%c", buff, SYM_AMP); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - - displayWrite(osdDisplayPort, statNameX, top, "MAX POWER :"); - bool kiloWatt = osdFormatCentiNumber(buff, stats.max_power, 1000, 2, 2, 3, false); - buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; - buff[4] = '\0'; - displayWrite(osdDisplayPort, statValuesX, top++, buff); - - displayWrite(osdDisplayPort, statNameX, top, "USED CAPACITY :"); - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - tfp_sprintf(buff, "%d%c", (int)getMAhDrawn(), SYM_MAH); - } else { - osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3, false); - tfp_sprintf(buff, "%s%c", buff, SYM_WH); - } - displayWrite(osdDisplayPort, statValuesX, top++, buff); - - int32_t totalDistance = getTotalTravelDistance(); - bool moreThanAh = false; - bool efficiencyValid = totalDistance >= 10000; - if (feature(FEATURE_GPS)) { - displayWrite(osdDisplayPort, statNameX, top, "AVG EFFICIENCY :"); - uint8_t digits = 3U; // Total number of digits (including decimal point) - #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - // Add one digit so no switch to scaled decimal occurs above 99 - digits = 4U; - } - #endif - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits, false); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_MI_0; - buff[4] = SYM_MAH_MI_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits, false); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_MI); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; - case OSD_UNIT_GA: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits, false); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_NM_0; - buff[4] = SYM_MAH_NM_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits, false); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits, false); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_KM_0; - buff[4] = SYM_MAH_KM_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits, false); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_KM); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; + displayWrite(osdDisplayPort, statValuesX, row++, buff); // 1 row } - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } +#endif +#endif +#ifdef USE_STATS + if (row < (osdDisplayPort->cols-7) && statsConfig()->stats_enabled) row = drawStat_Stats(statNameX, row, statValuesX, false); // 4 rows +#endif + + break; } - - const float max_gforce = accGetMeasuredMaxG(); - displayWrite(osdDisplayPort, statNameX, top, "MAX G-FORCE :"); - osdFormatCentiNumber(buff, max_gforce * 100, 0, 2, 0, 3, false); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - - const acc_extremes_t *acc_extremes = accGetMeasuredExtremes(); - const float acc_extremes_min = acc_extremes[Z].min; - const float acc_extremes_max = acc_extremes[Z].max; - displayWrite(osdDisplayPort, statNameX, top, "MIN/MAX Z G-FORCE:"); - osdFormatCentiNumber(buff, acc_extremes_min * 100, 0, 2, 0, 4, false); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff),"/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - osdFormatCentiNumber(buff, acc_extremes_max * 100, 0, 2, 0, 3, false); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); } + + row = drawStat_DisarmMethod(statNameX, row, statValuesX); + + // The following has been commented out as it will be added in #9688 + // uint16_t rearmMs = (emergInflightRearmEnabled()) ? emergencyInFlightRearmTimeMS() : 0; if (savingSettings == true) { - displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS)); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS))) / 2, row++, OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS)); + /*} else if (rearmMs > 0) { // Show rearming time if settings not actively being saved. Ignore the settings saved message if rearm available. + char emReArmMsg[23]; + tfp_sprintf(emReArmMsg, "** REARM PERIOD: "); + tfp_sprintf(emReArmMsg + strlen(emReArmMsg), "%02d", (uint8_t)MS2S(rearmMs)); + strcat(emReArmMsg, " **\0"); + displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(emReArmMsg));*/ } else if (notify_settings_saved > 0) { if (millis() > notify_settings_saved) { notify_settings_saved = 0; } else { - displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED)); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED))) / 2, row++, OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED)); } } @@ -4982,16 +5410,16 @@ static void osdRefresh(timeUs_t currentTimeUs) if (ARMING_FLAG(ARMED)) { // Display the "Arming" screen statsDisplayed = false; - osdResetStats(); + if (!STATE(IN_FLIGHT_EMERG_REARM)) + osdResetStats(); + osdShowArmed(); uint16_t delay = osdConfig()->arm_screen_display_time; - if (STATE(IN_FLIGHT_EMERG_REARM)) { + if (STATE(IN_FLIGHT_EMERG_REARM)) delay = 500; - } #if defined(USE_SAFE_HOME) - else if (posControl.safehomeState.distance) { + else if (posControl.safehomeState.distance) delay += 3000; - } #endif osdSetNextRefreshIn(delay); } else { @@ -5057,13 +5485,13 @@ static void osdRefresh(timeUs_t currentTimeUs) // Process manual page change events for multi-page stats. if (manualPageUpRequested) { osdShowStats(statsSinglePageCompatible, 1); - statsCurrentPage = 1; + statsCurrentPage = 1; } else if (manualPageDownRequested) { osdShowStats(statsSinglePageCompatible, 0); statsCurrentPage = 0; + } } } - } // Handle events when either "Splash", "Armed" or "Stats" screens are displayed. if ((currentTimeUs > resumeRefreshAt) || OSD_RESUME_UPDATES_STICK_COMMAND) { @@ -5160,7 +5588,7 @@ void osdUpdate(timeUs_t currentTimeUs) #define STATS_FREQ_DENOM 50 counter++; - if ((counter % STATS_FREQ_DENOM) == 0) { + if ((counter % STATS_FREQ_DENOM) == 0 && ARMING_FLAG(ARMED)) { osdUpdateStats(); } @@ -5245,7 +5673,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter if (buff != NULL) { const char *message = NULL; - char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; + char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; //warning: shared buffer. Make sure it is used by single message in code below! // We might have up to 5 messages to show. const char *messages[5]; unsigned messageCount = 0; @@ -5254,7 +5682,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter if (ARMING_FLAG(ARMED)) { #ifdef USE_FW_AUTOLAND - if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding() || isFwLandInProgess()) { + if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding() || FLIGHT_MODE(NAV_FW_AUTOLAND)) { if (isWaypointMissionRTHActive() && !posControl.fwLandState.landWp) { #else if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { @@ -5295,7 +5723,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter #ifdef USE_FW_AUTOLAND if (canFwLandCanceld()) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_MOVE_STICKS); - } else if (!isFwLandInProgess()) { + } else if (!FLIGHT_MODE(NAV_FW_AUTOLAND)) { #endif const char *navStateMessage = navigationStateMessage(); if (navStateMessage) { @@ -5419,8 +5847,17 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter /* Messages that are shown regardless of Arming state */ + // The following has been commented out as it will be added in #9688 + // uint16_t rearmMs = (emergInflightRearmEnabled()) ? emergencyInFlightRearmTimeMS() : 0; + if (savingSettings == true) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS); + /*} else if (rearmMs > 0) { // Show rearming time if settings not actively being saved. Ignore the settings saved message if rearm available. + char emReArmMsg[23]; + tfp_sprintf(emReArmMsg, "** REARM PERIOD: "); + tfp_sprintf(emReArmMsg + strlen(emReArmMsg), "%02d", (uint8_t)MS2S(rearmMs)); + strcat(emReArmMsg, " **\0"); + messages[messageCount++] = OSD_MESSAGE_STR(emReArmMsg);*/ } else if (notify_settings_saved > 0) { if (millis() > notify_settings_saved) { notify_settings_saved = 0; diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 503f7dd0e0..ca5dca6613 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -75,7 +75,6 @@ #define OSD_MSG_PITOT_FAIL "PITOT METER FAILURE" #define OSD_MSG_HW_FAIL "HARDWARE FAILURE" #define OSD_MSG_FS_EN "FAILSAFE MODE ENABLED" -#define OSD_MSG_KILL_SW_EN "KILLSWITCH MODE ENABLED" #define OSD_MSG_NO_RC_LINK "NO RC LINK" #define OSD_MSG_THROTTLE_NOT_LOW "THROTTLE IS NOT LOW" #define OSD_MSG_ROLLPITCH_OFFCENTER "ROLLPITCH NOT CENTERED" @@ -286,6 +285,7 @@ typedef enum { OSD_CUSTOM_ELEMENT_3, OSD_ADSB_WARNING, OSD_ADSB_INFO, + OSD_BLACKBOX, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; @@ -304,11 +304,6 @@ typedef enum { OSD_STATS_ENERGY_UNIT_WH, } osd_stats_energy_unit_e; -typedef enum { - OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY, - OSD_STATS_MIN_VOLTAGE_UNIT_CELL, -} osd_stats_min_voltage_unit_e; - typedef enum { OSD_CROSSHAIRS_STYLE_DEFAULT, OSD_CROSSHAIRS_STYLE_AIRCRAFT, @@ -418,11 +413,12 @@ typedef struct osdConfig_s { uint8_t units; // from osd_unit_e uint8_t stats_energy_unit; // from osd_stats_energy_unit_e - uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) + bool stats_show_metric_efficiency; // If true, show metric efficiency as well as for the selected units #ifdef USE_WIND_ESTIMATOR bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance + bool estimations_wind_mps; // wind speed estimation in m/s #endif uint8_t coordinate_digits; bool osd_failsafe_switch_layout; diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 38db724c8e..b018d8f906 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -122,11 +122,10 @@ * but reuse the packet decoder to minimize code duplication */ -PG_REGISTER_WITH_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig, PG_DJI_OSD_CONFIG, 2); +PG_REGISTER_WITH_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig, PG_DJI_OSD_CONFIG, 3); PG_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig, .use_name_for_messages = SETTING_DJI_USE_NAME_FOR_MESSAGES_DEFAULT, .esc_temperature_source = SETTING_DJI_ESC_TEMP_SOURCE_DEFAULT, - .proto_workarounds = SETTING_DJI_WORKAROUNDS_DEFAULT, .messageSpeedSource = SETTING_DJI_MESSAGE_SPEED_SOURCE_DEFAULT, .rssi_source = SETTING_DJI_RSSI_SOURCE_DEFAULT, .useAdjustments = SETTING_DJI_USE_ADJUSTMENTS_DEFAULT, @@ -505,8 +504,6 @@ static char * osdArmingDisabledReasonMessage(void) // return OSD_MESSAGE_STR("HARDWARE FAILURE"); case ARMING_DISABLED_BOXFAILSAFE: return OSD_MESSAGE_STR("FAILSAFE ENABLED"); - case ARMING_DISABLED_BOXKILLSWITCH: - return OSD_MESSAGE_STR("KILLSWITCH ENABLED"); case ARMING_DISABLED_RC_LINK: return OSD_MESSAGE_STR("NO RC LINK"); case ARMING_DISABLED_THROTTLE: @@ -1063,6 +1060,10 @@ static bool djiFormatMessages(char *buff) if (FLIGHT_MODE(MANUAL_MODE)) { messages[messageCount++] = "(MANUAL)"; } + + if (FLIGHT_MODE(NAV_FW_AUTOLAND)) { + messages[messageCount++] = "(LAND)"; + } } } // Pick one of the available messages. Each message lasts @@ -1345,12 +1346,11 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms break; case DJI_MSP_ESC_SENSOR_DATA: - if (djiOsdConfig()->proto_workarounds & DJI_OSD_USE_NON_STANDARD_MSP_ESC_SENSOR_DATA) { - // Version 1.00.06 of DJI firmware is not using the standard MSP_ESC_SENSOR_DATA + { uint16_t protoRpm = 0; int16_t protoTemp = 0; -#if defined(USE_ESC_SENSOR) + #if defined(USE_ESC_SENSOR) if (STATE(ESC_SENSOR_ENABLED) && getMotorCount() > 0) { uint32_t motorRpmAcc = 0; int32_t motorTempAcc = 0; @@ -1364,7 +1364,7 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms protoRpm = motorRpmAcc / getMotorCount(); protoTemp = motorTempAcc / getMotorCount(); } -#endif + #endif switch (djiOsdConfig()->esc_temperature_source) { // This is ESC temperature (as intended) @@ -1389,47 +1389,6 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms sbufWriteU8(dst, protoTemp); sbufWriteU16(dst, protoRpm); } - else { - // Use standard MSP_ESC_SENSOR_DATA message - sbufWriteU8(dst, getMotorCount()); - for (int i = 0; i < getMotorCount(); i++) { - uint16_t motorRpm = 0; - int16_t motorTemp = 0; - - // If ESC_SENSOR is enabled, pull the telemetry data and get motor RPM -#if defined(USE_ESC_SENSOR) - if (STATE(ESC_SENSOR_ENABLED)) { - const escSensorData_t * escSensor = getEscTelemetry(i); - motorRpm = escSensor->rpm; - motorTemp = escSensor->temperature; - } -#endif - - // Now populate temperature field (which we may override for different purposes) - switch (djiOsdConfig()->esc_temperature_source) { - // This is ESC temperature (as intended) - case DJI_OSD_TEMP_ESC: - // No-op, temperature is already set to ESC - break; - - // Re-purpose the field for core temperature - case DJI_OSD_TEMP_CORE: - getIMUTemperature(&motorTemp); - motorTemp = motorTemp / 10; - break; - - // Re-purpose the field for baro temperature - case DJI_OSD_TEMP_BARO: - getBaroTemperature(&motorTemp); - motorTemp = motorTemp / 10; - break; - } - - // Add data for this motor to the packet - sbufWriteU8(dst, motorTemp); - sbufWriteU16(dst, motorRpm); - } - } break; case DJI_MSP_OSD_CONFIG: @@ -1452,7 +1411,7 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms sbufWriteU16(dst, 0); // BF: gyroConfig()->gyro_soft_notch_hz_2 sbufWriteU16(dst, 1); // BF: gyroConfig()->gyro_soft_notch_cutoff_2 sbufWriteU8(dst, 0); // BF: currentPidProfile->dterm_filter_type - sbufWriteU8(dst, gyroConfig()->gyro_lpf); // BF: gyroConfig()->gyro_hardware_lpf); + sbufWriteU8(dst, GYRO_LPF_256HZ); // BF: gyroConfig()->gyro_hardware_lpf); sbufWriteU8(dst, 0); // BF: DEPRECATED: gyro_32khz_hardware_lpf sbufWriteU16(dst, gyroConfig()->gyro_main_lpf_hz); // BF: gyroConfig()->gyro_lowpass_hz); sbufWriteU16(dst, 0); // BF: gyroConfig()->gyro_lowpass2_hz); diff --git a/src/main/io/osd_dji_hd.h b/src/main/io/osd_dji_hd.h index 4b3e0a1479..f109f84fb1 100644 --- a/src/main/io/osd_dji_hd.h +++ b/src/main/io/osd_dji_hd.h @@ -84,7 +84,6 @@ enum djiOsdProtoWorkarounds_e { typedef struct djiOsdConfig_s { uint8_t use_name_for_messages; uint8_t esc_temperature_source; - uint8_t proto_workarounds; uint8_t messageSpeedSource; uint8_t rssi_source; uint8_t useAdjustments; diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h index b44037f2f8..ac847afeae 100644 --- a/src/main/msp/msp_protocol.h +++ b/src/main/msp/msp_protocol.h @@ -163,9 +163,6 @@ #define MSP_SONAR_ALTITUDE 58 //out message get surface altitude [cm] -#define MSP_ARMING_CONFIG 61 //out message Returns auto_disarm_delay and disarm_kill_switch parameters -#define MSP_SET_ARMING_CONFIG 62 //in message Sets auto_disarm_delay and disarm_kill_switch parameters - // // Baseflight MSP commands (if enabled they exist in Cleanflight) // @@ -207,7 +204,6 @@ #define MSP_FILTER_CONFIG 92 #define MSP_SET_FILTER_CONFIG 93 - #define MSP_PID_ADVANCED 94 #define MSP_SET_PID_ADVANCED 95 @@ -248,7 +244,6 @@ #define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID #define MSP_ACTIVEBOXES 113 //out message Active box flags (full width, more than 32 bits) #define MSP_MISC 114 //out message powermeter trig -#define MSP_MOTOR_PINS 115 //out message which pins are in use for motors & servos, for GUI #define MSP_BOXNAMES 116 //out message the aux switch names #define MSP_PIDNAMES 117 //out message the PID names #define MSP_WP 118 //out message get a WP, WP# is in the payload, returns (WP#, lat, lon, alt, flags) WP#0-home, WP#16-poshold diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index ab194aab66..ad2e775e4e 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -111,3 +111,5 @@ #define MSP2_INAV_CUSTOM_OSD_ELEMENTS 0x2100 #define MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS 0x2101 +#define MSP2_INAV_SERVO_CONFIG 0x2200 +#define MSP2_INAV_SET_SERVO_CONFIG 0x2201 \ No newline at end of file diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index f9ddc1f255..e7261b068c 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -65,6 +65,7 @@ #include "sensors/boardalignment.h" #include "sensors/battery.h" #include "sensors/gyro.h" +#include "sensors/diagnostics.h" #include "programming/global_variables.h" #include "sensors/rangefinder.h" @@ -174,7 +175,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 + .cruise_yaw_rate = SETTING_NAV_CRUISE_YAW_RATE_DEFAULT, // 20dps .rth_fs_landing_delay = SETTING_NAV_RTH_FS_LANDING_DELAY_DEFAULT, // Delay before landing in FS. 0 = immedate landing }, @@ -203,44 +204,44 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, // Fixed wing .fw = { - .max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees - .max_manual_climb_rate = SETTING_NAV_FW_MANUAL_CLIMB_RATE_DEFAULT, // 3 m/s - .max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees - .max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees - .cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s + .max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees + .max_manual_climb_rate = SETTING_NAV_FW_MANUAL_CLIMB_RATE_DEFAULT, // 3 m/s + .max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees + .max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees + .cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s .control_smoothness = SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT, .pitch_to_throttle_smooth = SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT, .pitch_to_throttle_thresh = SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT, .minThrottleDownPitchAngle = SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT, - .loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m + .loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m .loiter_direction = SETTING_FW_LOITER_DIRECTION_DEFAULT, //Fixed wing landing - .land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default + .land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default // Fixed wing launch - .launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s - .launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G) - .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms - .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms - .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms - .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch - .launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode - .launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode - .launch_timeout = SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT, // ms, timeout for launch procedure - .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended - .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees - .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg - .launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT,// OFF - .launch_land_abort_deadband = SETTING_NAV_FW_LAUNCH_LAND_ABORT_DEADBAND_DEFAULT, // 100 us - + .launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s + .launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G) + .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms + .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms + .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms + .launch_wiggle_wake_idle = SETTING_NAV_FW_LAUNCH_WIGGLE_TO_WAKE_IDLE_DEFAULT, // uint8_t + .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to greaually increase throttle from idle to launch + .launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode + .launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode + .launch_timeout = SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT, // ms, timeout for launch procedure + .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended + .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees + .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg + .launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT, // OFF + .launch_land_abort_deadband = SETTING_NAV_FW_LAUNCH_LAND_ABORT_DEADBAND_DEFAULT, // 100 us .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, - .soaring_pitch_deadband = SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT,// pitch angle mode deadband when Saoring mode enabled - .wp_tracking_accuracy = SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT, // 0, improves course tracking accuracy during FW WP missions - .wp_tracking_max_angle = SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT, // 60 degs - .wp_turn_smoothing = SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT, // 0, smooths turns during FW WP mode missions + .soaring_pitch_deadband = SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT, // pitch angle mode deadband when Saoring mode enabled + .wp_tracking_accuracy = SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT, // 0, improves course tracking accuracy during FW WP missions + .wp_tracking_max_angle = SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT, // 60 degs + .wp_turn_smoothing = SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT, // 0, smooths turns during FW WP mode missions } ); @@ -1044,13 +1045,14 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { } }, +/** Advanced Fixed Wing Autoland **/ #ifdef USE_FW_AUTOLAND [NAV_STATE_FW_LANDING_CLIMB_TO_LOITER] = { .persistentId = NAV_PERSISTENT_ID_FW_LANDING_CLIMB_TO_LOITER, .onEntry = navOnEnteringState_NAV_STATE_FW_LANDING_CLIMB_TO_LOITER, .timeoutMs = 10, - .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH, - .mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE, + .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_AUTO_RTH, + .mapToFlightModes = NAV_FW_AUTOLAND, .mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwError = MW_NAV_ERROR_NONE, .onEvent = { @@ -1070,8 +1072,8 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .persistentId = NAV_PERSISTENT_ID_FW_LANDING_LOITER, .onEntry = navOnEnteringState_NAV_STATE_FW_LANDING_LOITER, .timeoutMs = 10, - .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH, - .mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE, + .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_AUTO_RTH, + .mapToFlightModes = NAV_FW_AUTOLAND, .mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwError = MW_NAV_ERROR_NONE, .onEvent = { @@ -1091,8 +1093,8 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .persistentId = NAV_PERSISTENT_ID_FW_LANDING_APPROACH, .onEntry = navOnEnteringState_NAV_STATE_FW_LANDING_APPROACH, .timeoutMs = 10, - .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_WP, - .mapToFlightModes = NAV_WP_MODE | NAV_ALTHOLD_MODE, + .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_AUTO_WP, + .mapToFlightModes = NAV_FW_AUTOLAND, .mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwError = MW_NAV_ERROR_NONE, .onEvent = { @@ -1113,7 +1115,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .onEntry = navOnEnteringState_NAV_STATE_FW_LANDING_GLIDE, .timeoutMs = 10, .stateFlags = NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_RC_POS | NAV_RC_YAW, - .mapToFlightModes = NAV_COURSE_HOLD_MODE, + .mapToFlightModes = NAV_FW_AUTOLAND, .mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwError = MW_NAV_ERROR_NONE, .onEvent = { @@ -1134,7 +1136,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .onEntry = navOnEnteringState_NAV_STATE_FW_LANDING_FLARE, .timeoutMs = 10, .stateFlags = NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_RC_POS | NAV_RC_YAW, - .mapToFlightModes = NAV_COURSE_HOLD_MODE, + .mapToFlightModes = NAV_FW_AUTOLAND, .mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwError = MW_NAV_ERROR_NONE, .onEvent = { @@ -1147,8 +1149,8 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .persistentId = NAV_PERSISTENT_ID_FW_LANDING_ABORT, .onEntry = navOnEnteringState_NAV_STATE_FW_LANDING_ABORT, .timeoutMs = 10, - .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH | NAV_RC_POS | NAV_RC_YAW, - .mapToFlightModes = NAV_WP_MODE | NAV_ALTHOLD_MODE, + .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_AUTO_RTH | NAV_RC_POS | NAV_RC_YAW, + .mapToFlightModes = NAV_FW_AUTOLAND, .mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwError = MW_NAV_ERROR_NONE, .onEvent = { @@ -1677,7 +1679,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF /* If position sensors unavailable - land immediately (wait for timeout on GPS) * Continue to check for RTH sanity during landing */ - if (posControl.flags.estHeadingStatus == EST_NONE || checkForPositionSensorTimeout() || !validateRTHSanityChecker()) { + if (posControl.flags.estHeadingStatus == EST_NONE || checkForPositionSensorTimeout() || (previousState != NAV_STATE_WAYPOINT_REACHED && !validateRTHSanityChecker())) { return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING; } @@ -1687,7 +1689,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF #ifdef USE_FW_AUTOLAND if (STATE(AIRPLANE)) { - int8_t missionIdx = -1, shIdx = -1, missionFwLandConfigStartIdx = 8; + int8_t missionIdx = -1, shIdx = -1, missionFwLandConfigStartIdx = 8, approachSettingIdx = -1; #ifdef USE_MULTI_MISSION missionIdx = posControl.loadedMultiMissionIndex - 1; #endif @@ -1696,18 +1698,23 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF shIdx = posControl.safehomeState.index; missionFwLandConfigStartIdx = MAX_SAFE_HOMES; #endif - if (!posControl.fwLandState.landAborted && (shIdx >= 0 || missionIdx >= 0) && (fwAutolandApproachConfig(shIdx)->landApproachHeading1 != 0 || fwAutolandApproachConfig(shIdx)->landApproachHeading2 != 0)) { + if (previousState == NAV_STATE_WAYPOINT_REACHED && missionIdx >= 0) { + approachSettingIdx = missionFwLandConfigStartIdx + missionIdx; + } else if (shIdx >= 0) { + approachSettingIdx = shIdx; + } + + if (!posControl.fwLandState.landAborted && approachSettingIdx >= 0 && (fwAutolandApproachConfig(approachSettingIdx)->landApproachHeading1 != 0 || fwAutolandApproachConfig(approachSettingIdx)->landApproachHeading2 != 0)) { if (previousState == NAV_STATE_WAYPOINT_REACHED) { posControl.fwLandState.landPos = posControl.activeWaypoint.pos; - posControl.fwLandState.approachSettingIdx = missionFwLandConfigStartIdx + missionIdx; posControl.fwLandState.landWp = true; } else { posControl.fwLandState.landPos = posControl.safehomeState.nearestSafeHome; - posControl.fwLandState.approachSettingIdx = shIdx; posControl.fwLandState.landWp = false; } + posControl.fwLandState.approachSettingIdx = approachSettingIdx; posControl.fwLandState.landAltAgl = fwAutolandApproachConfig(posControl.fwLandState.approachSettingIdx)->isSeaLevelRef ? fwAutolandApproachConfig(posControl.fwLandState.approachSettingIdx)->landAlt - GPS_home.alt : fwAutolandApproachConfig(posControl.fwLandState.approachSettingIdx)->landAlt; posControl.fwLandState.landAproachAltAgl = fwAutolandApproachConfig(posControl.fwLandState.approachSettingIdx)->isSeaLevelRef ? fwAutolandApproachConfig(posControl.fwLandState.approachSettingIdx)->approachAlt - GPS_home.alt : fwAutolandApproachConfig(posControl.fwLandState.approachSettingIdx)->approachAlt; return NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING; @@ -1779,6 +1786,12 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_INITIALIZE(nav resetPositionController(); resetAltitudeController(false); // Make sure surface tracking is not enabled - WP uses global altitude, not AGL +#ifdef USE_FW_AUTOLAND + if (previousState != NAV_STATE_FW_LANDING_ABORT) { + posControl.fwLandState.landAborted = false; + } +#endif + if (posControl.activeWaypointIndex == posControl.startWpIndex || posControl.wpMissionRestart) { /* Use p3 as the volatile jump counter, allowing embedded, rearmed jumps Using p3 minimises the risk of saving an invalid counter if a mission is aborted */ @@ -1988,11 +2001,20 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_RTH_LAND(navig { UNUSED(previousState); +#ifdef USE_FW_AUTOLAND + if (posControl.fwLandState.landAborted) { + return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED; + } +#endif + const navigationFSMEvent_t landEvent = navOnEnteringState_NAV_STATE_RTH_LANDING(previousState); +#ifdef USE_FW_AUTOLAND if (landEvent == NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING) { return NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING; - } else if (landEvent == NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME) { + } else +#endif + if (landEvent == NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME) { return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED; } else if (landEvent == NAV_FSM_EVENT_SUCCESS) { // Landing controller returned success - invoke RTH finishing state and finish the waypoint @@ -2322,7 +2344,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_FW_LANDING_APPROACH(nav if (isLandingDetected()) { posControl.fwLandState.landState = FW_AUTOLAND_STATE_IDLE; - disarm(DISARM_LANDING); + //disarm(DISARM_LANDING); return NAV_FSM_EVENT_SWITCH_TO_IDLE; } @@ -2366,14 +2388,14 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_FW_LANDING_GLIDE(naviga return NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_ABORT; } - if (getLandAltitude() <= posControl.fwLandState.landAltAgl + navFwAutolandConfig()->flareAltitude) { + if (getHwRangefinderStatus() == HW_SENSOR_OK && getLandAltitude() <= posControl.fwLandState.landAltAgl + navFwAutolandConfig()->flareAltitude) { posControl.fwLandState.landState = FW_AUTOLAND_STATE_FLARE; return NAV_FSM_EVENT_SUCCESS; } if (isLandingDetected()) { posControl.fwLandState.landState = FW_AUTOLAND_STATE_IDLE; - disarm(DISARM_LANDING); + //disarm(DISARM_LANDING); return NAV_FSM_EVENT_SWITCH_TO_IDLE; } @@ -2387,7 +2409,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_FW_LANDING_FLARE(naviga if (isLandingDetected()) { posControl.fwLandState.landState = FW_AUTOLAND_STATE_IDLE; - disarm(DISARM_LANDING); + //disarm(DISARM_LANDING); return NAV_FSM_EVENT_SUCCESS; } setDesiredPosition(NULL, posControl.cruise.course, NAV_POS_UPDATE_HEADING); @@ -2993,7 +3015,7 @@ void setHomePosition(const fpVector3_t * pos, int32_t heading, navSetWaypointFla updateDesiredRTHAltitude(); // Reset RTH sanity checker for new home position if RTH active - if (FLIGHT_MODE(NAV_RTH_MODE)) { + if (FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_FW_AUTOLAND) ) { initializeRTHSanityChecker(); } @@ -3115,7 +3137,7 @@ void updateHomePosition(void) static bool isHomeResetAllowed = false; // If pilot so desires he may reset home position to current position if (IS_RC_MODE_ACTIVE(BOXHOMERESET)) { - if (isHomeResetAllowed && !FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE) && (posControl.flags.estPosStatus >= EST_USABLE)) { + if (isHomeResetAllowed && !FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_FW_AUTOLAND) && !FLIGHT_MODE(NAV_WP_MODE) && (posControl.flags.estPosStatus >= EST_USABLE)) { homeUpdateFlags = 0; homeUpdateFlags = STATE(GPS_FIX_HOME) ? (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_HEADING) : (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING); setHome = true; @@ -3935,6 +3957,7 @@ bool isNavHoldPositionActive(void) // Also hold position during emergency landing if position valid return (FLIGHT_MODE(NAV_RTH_MODE) && !posControl.flags.rthTrackbackActive) || FLIGHT_MODE(NAV_POSHOLD_MODE) || + (posControl.navState == NAV_STATE_FW_LANDING_CLIMB_TO_LOITER || posControl.navState == NAV_STATE_FW_LANDING_LOITER) || navigationIsExecutingAnEmergencyLanding(); } @@ -3974,7 +3997,9 @@ bool isWaypointNavTrackingActive(void) // is set from current position not previous WP. Works for WP Restart intermediate WP as well as first mission WP. // (NAV_WP_MODE flag isn't set until WP initialisation is finished, i.e. after calculateAndSetActiveWaypoint called) - return FLIGHT_MODE(NAV_WP_MODE) || (posControl.flags.rthTrackbackActive && rth_trackback.activePointIndex != rth_trackback.lastSavedIndex); + return FLIGHT_MODE(NAV_WP_MODE) + || posControl.navState == NAV_STATE_FW_LANDING_APPROACH + || (posControl.flags.rthTrackbackActive && rth_trackback.activePointIndex != rth_trackback.lastSavedIndex); } /*----------------------------------------------------------- @@ -4039,7 +4064,7 @@ void applyWaypointNavigationAndAltitudeHold(void) posControl.flags.verticalPositionDataConsumed = false; #ifdef USE_FW_AUTOLAND - if (!isFwLandInProgess()) { + if (!FLIGHT_MODE(NAV_FW_AUTOLAND)) { posControl.fwLandState.landState = FW_AUTOLAND_STATE_IDLE; } #endif @@ -4080,7 +4105,7 @@ void applyWaypointNavigationAndAltitudeHold(void) void switchNavigationFlightModes(void) { const flightModeFlags_e enabledNavFlightModes = navGetMappedFlightModes(posControl.navState); - const flightModeFlags_e disabledFlightModes = (NAV_ALTHOLD_MODE | NAV_RTH_MODE | NAV_POSHOLD_MODE | NAV_WP_MODE | NAV_LAUNCH_MODE | NAV_COURSE_HOLD_MODE) & (~enabledNavFlightModes); + const flightModeFlags_e disabledFlightModes = (NAV_ALTHOLD_MODE | NAV_RTH_MODE | NAV_FW_AUTOLAND | NAV_POSHOLD_MODE | NAV_WP_MODE | NAV_LAUNCH_MODE | NAV_COURSE_HOLD_MODE) & (~enabledNavFlightModes); DISABLE_FLIGHT_MODE(disabledFlightModes); ENABLE_FLIGHT_MODE(enabledNavFlightModes); } @@ -4192,22 +4217,6 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } posControl.rthSanityChecker.rthSanityOK = true; - /* WP mission activation control: - * canActivateWaypoint & waypointWasActivated are used to prevent WP mission - * auto restarting after interruption by Manual or RTH modes. - * WP mode must be deselected before it can be reactivated again. */ - static bool waypointWasActivated = false; - const bool isWpMissionLoaded = isWaypointMissionValid(); - bool canActivateWaypoint = isWpMissionLoaded && !posControl.flags.wpMissionPlannerActive; // Block activation if using WP Mission Planner - - if (waypointWasActivated && !FLIGHT_MODE(NAV_WP_MODE)) { - canActivateWaypoint = false; - if (!IS_RC_MODE_ACTIVE(BOXNAVWP)) { - canActivateWaypoint = true; - waypointWasActivated = false; - } - } - /* Airplane specific modes */ if (STATE(AIRPLANE)) { // LAUNCH mode has priority over any other NAV mode @@ -4247,14 +4256,36 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) return NAV_FSM_EVENT_SWITCH_TO_RTH; } - /* Pilot-triggered RTH, also fall-back for WP if there is no mission loaded. - * WP prevented from falling back to RTH if WP mission planner is active */ - const bool wpRthFallbackIsActive = IS_RC_MODE_ACTIVE(BOXNAVWP) && !isWpMissionLoaded && !posControl.flags.wpMissionPlannerActive; + /* WP mission activation control: + * canActivateWaypoint & waypointWasActivated are used to prevent WP mission + * auto restarting after interruption by Manual or RTH modes. + * WP mode must be deselected before it can be reactivated again + * WP Mode also inhibited when Mission Planner is active */ + static bool waypointWasActivated = false; + bool canActivateWaypoint = isWaypointMissionValid(); + bool wpRthFallbackIsActive = false; + + if (IS_RC_MODE_ACTIVE(BOXMANUAL) || posControl.flags.wpMissionPlannerActive) { + canActivateWaypoint = false; + } else { + if (waypointWasActivated && !FLIGHT_MODE(NAV_WP_MODE)) { + canActivateWaypoint = false; + + if (!IS_RC_MODE_ACTIVE(BOXNAVWP)) { + canActivateWaypoint = true; + waypointWasActivated = false; + } + } + + wpRthFallbackIsActive = IS_RC_MODE_ACTIVE(BOXNAVWP) && !canActivateWaypoint; + } + + /* Pilot-triggered RTH, also fall-back for WP if no mission is loaded. + * Check for isExecutingRTH to prevent switching our from RTH in case of a brief GPS loss + * Without this loss of any of the canActivateNavigation && canActivateAltHold + * will kick us out of RTH state machine via NAV_FSM_EVENT_SWITCH_TO_IDLE and will prevent any of the fall-back + * logic kicking in (waiting for GPS on airplanes, switch to emergency landing etc) */ if (IS_RC_MODE_ACTIVE(BOXNAVRTH) || wpRthFallbackIsActive) { - // Check for isExecutingRTH to prevent switching our from RTH in case of a brief GPS loss - // Without this loss of any of the canActivateNavigation && canActivateAltHold - // will kick us out of RTH state machine via NAV_FSM_EVENT_SWITCH_TO_IDLE and will prevent any of the fall-back - // logic kicking in (waiting for GPS on airplanes, switch to emergency landing etc) if (isExecutingRTH || (canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) { return NAV_FSM_EVENT_SWITCH_TO_RTH; } @@ -4268,11 +4299,11 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) // Pilot-activated waypoint mission. Fall-back to RTH if no mission loaded. // Also check multimission mission change status before activating WP mode. #ifdef USE_MULTI_MISSION - if (updateWpMissionChange() && IS_RC_MODE_ACTIVE(BOXNAVWP) && canActivateWaypoint) { + if (updateWpMissionChange() && IS_RC_MODE_ACTIVE(BOXNAVWP)) { #else - if (IS_RC_MODE_ACTIVE(BOXNAVWP) && canActivateWaypoint) { + if (IS_RC_MODE_ACTIVE(BOXNAVWP)) { #endif - if (FLIGHT_MODE(NAV_WP_MODE) || (canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) { + if (FLIGHT_MODE(NAV_WP_MODE) || (canActivateWaypoint && canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) { waypointWasActivated = true; return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT; } @@ -4767,7 +4798,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 | NAV_MIXERAT))) { + if (posControl.flags.forcedRTHActivated && ((navGetStateFlags(posControl.navState) & (NAV_AUTO_RTH | NAV_CTL_EMERG | NAV_MIXERAT)) || FLIGHT_MODE(NAV_FW_AUTOLAND))) { if (posControl.navState == NAV_STATE_RTH_FINISHED || posControl.navState == NAV_STATE_EMERGENCY_LANDING_FINISHED) { return RTH_HAS_LANDED; } @@ -4849,6 +4880,12 @@ bool navigationIsFlyingAutonomousMode(void) bool navigationRTHAllowsLanding(void) { +#ifdef USE_FW_AUTOLAND + if (posControl.fwLandState.landAborted) { + return false; + } +#endif + // WP mission RTH landing setting if (isWaypointMissionRTHActive() && isWaypointMissionValid()) { return posControl.waypointList[posControl.startWpIndex + posControl.waypointCount - 1].p1 > 0; @@ -5006,15 +5043,6 @@ void resetFwAutolandApproach(int8_t idx) } } -bool isFwLandInProgess(void) -{ - return posControl.navState == NAV_STATE_FW_LANDING_CLIMB_TO_LOITER - || posControl.navState == NAV_STATE_FW_LANDING_LOITER - || posControl.navState == NAV_STATE_FW_LANDING_APPROACH - || posControl.navState == NAV_STATE_FW_LANDING_GLIDE - || posControl.navState == NAV_STATE_FW_LANDING_FLARE; -} - bool canFwLandCanceld(void) { return posControl.navState == NAV_STATE_FW_LANDING_CLIMB_TO_LOITER diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 84e5390d43..98bf6c4d62 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -193,9 +193,9 @@ typedef enum { } navRTHClimbFirst_e; typedef enum { // keep aligned with fixedWingLaunchState_t - FW_LAUNCH_DETECTED = 4, - FW_LAUNCH_ABORTED = 9, - FW_LAUNCH_FLYING = 10, + FW_LAUNCH_DETECTED = 5, + FW_LAUNCH_ABORTED = 10, + FW_LAUNCH_FLYING = 11, } navFwLaunchStatus_e; typedef enum { @@ -234,7 +234,6 @@ typedef struct positionEstimationConfig_s { uint8_t reset_altitude_type; // from nav_reset_type_e uint8_t reset_home_type; // nav_reset_type_e uint8_t gravity_calibration_tolerance; // Tolerance of gravity calibration (cm/s/s) - uint8_t use_gps_velned; uint8_t allow_dead_reckoning; uint16_t max_surface_altitude; @@ -367,6 +366,7 @@ typedef struct navConfig_s { uint16_t launch_time_thresh; // Time threshold for launch detection (ms) uint16_t launch_motor_timer; // Time to wait before setting launch_throttle (ms) uint16_t launch_idle_motor_timer; // Time to wait before motor starts at_idle throttle (ms) + uint8_t launch_wiggle_wake_idle; // Activate the idle throttle by wiggling the plane. 0 = disabled, 1 or 2 specify the number of wiggles. uint16_t launch_motor_spinup_time; // Time to speed-up motors from idle to launch_throttle (ESC desync prevention) uint16_t launch_end_time; // Time to make the transition from launch angle to leveled and throttle transition from launch throttle to the stick position uint16_t launch_min_time; // Minimum time in launch mode to prevent possible bump of the sticks from leaving launch mode early @@ -702,7 +702,6 @@ uint8_t getActiveWpNumber(void); int32_t navigationGetHomeHeading(void); #ifdef USE_FW_AUTOLAND -bool isFwLandInProgess(void); bool canFwLandCanceld(void); #endif diff --git a/src/main/navigation/navigation_declination_gen.c b/src/main/navigation/navigation_declination_gen.c index 04e1c73172..c7d632cd87 100644 --- a/src/main/navigation/navigation_declination_gen.c +++ b/src/main/navigation/navigation_declination_gen.c @@ -1,7 +1,7 @@ /* this file is automatically generated by src/utils/declination.py - DO NOT EDIT! */ -/* Updated on 2019-05-16 19:59:45.672184 */ +/* Updated on 2024-04-19 12:54:15.842704 */ #include @@ -16,25 +16,25 @@ #define SAMPLING_MAX_LAT 90.00000f static const float declination_table[19][37] = { - {149.21545f,139.21545f,129.21545f,119.21545f,109.21545f,99.21545f,89.21545f,79.21545f,69.21545f,59.21545f,49.21545f,39.21545f,29.21545f,19.21545f,9.21545f,-0.78455f,-10.78455f,-20.78455f,-30.78455f,-40.78455f,-50.78455f,-60.78455f,-70.78455f,-80.78455f,-90.78455f,-100.78455f,-110.78455f,-120.78455f,-130.78455f,-140.78455f,-150.78455f,-160.78455f,-170.78455f,179.21545f,169.21545f,159.21545f,149.21545f}, - {129.49173f,117.24379f,106.10409f,95.92286f,86.51411f,77.69583f,69.30955f,61.22803f,53.35622f,45.62814f,38.00071f,30.44524f,22.93795f,15.45138f,7.94874f,0.38309f,-7.29841f,-15.14665f,-23.20230f,-31.49030f,-40.01947f,-48.78754f,-57.79007f,-67.03110f,-76.53295f,-86.34401f,-96.54357f,-107.24276f,-118.57946f,-130.70159f,-143.72988f,-157.69312f,-172.44642f,172.37735f,157.31228f,142.89420f,129.49173f}, - {85.58549f,77.67225f,71.30884f,65.86377f,60.92589f,56.17990f,51.37001f,46.30480f,40.87538f,35.06788f,28.95999f,22.69753f,16.44959f,10.34723f,4.42361f,-1.41547f,-7.36729f,-13.65814f,-20.45428f,-27.80115f,-35.61613f,-43.73164f,-51.96263f,-60.16701f,-68.28139f,-76.33426f,-84.45291f,-92.88710f,-102.08596f,-112.90534f,-127.14324f,-148.72029f,177.01697f,138.42469f,112.13402f,96.22709f,85.58549f}, - {47.63660f,46.34868f,44.88668f,43.46724f,42.13334f,40.75578f,39.03991f,36.60567f,33.13133f,28.48297f,22.78165f,16.40811f,9.93011f,3.92458f,-1.26916f,-5.73344f,-9.95561f,-14.59663f,-20.17634f,-26.83800f,-34.30473f,-42.04900f,-49.54378f,-56.41737f,-62.46557f,-67.58445f,-71.67147f,-74.48888f,-75.41488f,-72.72854f,-60.65739f,-20.78150f,26.31817f,42.64478f,47.39885f,48.29568f,47.63660f}, - {30.97061f,31.18244f,30.92007f,30.51421f,30.19783f,30.07382f,29.96272f,29.32724f,27.44230f,23.71829f,17.99066f,10.70786f,2.93356f,-4.02123f,-9.25421f,-12.72420f,-15.16719f,-17.68585f,-21.36741f,-26.80526f,-33.62817f,-40.77079f,-47.22749f,-52.37678f,-55.85085f,-57.33789f,-56.38997f,-52.20324f,-43.65581f,-30.23589f,-13.76879f,1.84396f,13.87138f,22.01689f,27.05355f,29.80197f,30.97061f}, - {22.35701f,22.87747f,22.95380f,22.77246f,22.50130f,22.37009f,22.48347f,22.51381f,21.59756f,18.63829f,12.92222f,4.75452f,-4.29892f,-12.13023f,-17.44827f,-20.36076f,-21.71093f,-22.23838f,-22.95576f,-25.55066f,-30.56100f,-36.48539f,-41.58017f,-44.82620f,-45.65465f,-43.72977f,-38.84914f,-30.98997f,-21.09926f,-11.31468f,-3.00404f,3.97652f,9.93802f,14.84528f,18.57977f,21.04644f,22.35701f}, - {16.83374f,17.31701f,17.52984f,17.52512f,17.27497f,16.89826f,16.64631f,16.52197f,15.82359f,13.20018f,7.50544f,-1.01430f,-10.31063f,-17.86218f,-22.52054f,-24.77956f,-25.51811f,-24.67883f,-22.16922f,-20.17352f,-21.46713f,-25.48482f,-29.63408f,-31.91043f,-31.42054f,-28.23519f,-22.87573f,-15.95318f,-8.88587f,-3.41726f,0.43088f,3.87433f,7.44305f,10.85242f,13.73685f,15.75505f,16.83374f}, - {13.16653f,13.42584f,13.56856f,13.64914f,13.49908f,13.04415f,12.54312f,12.17294f,11.33249f,8.62333f,2.85124f,-5.49975f,-14.06214f,-20.49962f,-23.98868f,-24.97282f,-24.13471f,-21.32697f,-16.43179f,-11.33581f,-9.07326f,-10.72561f,-14.43596f,-17.29905f,-17.69300f,-15.77796f,-12.24267f,-7.56947f,-3.00400f,-0.11834f,1.39928f,3.14408f,5.63638f,8.32414f,10.72028f,12.39111f,13.16653f}, - {10.90437f,10.88236f,10.81163f,10.86511f,10.80010f,10.39894f,9.91702f,9.49494f,8.41184f,5.36760f,-0.47690f,-8.26124f,-15.66061f,-20.76090f,-22.78986f,-21.89942f,-18.89020f,-14.52921f,-9.53528f,-4.91597f,-1.91353f,-1.76484f,-4.25201f,-7.17489f,-8.55660f,-8.15241f,-6.39303f,-3.54345f,-0.64444f,0.81130f,1.15035f,2.11074f,4.17898f,6.59237f,8.80142f,10.33532f,10.90437f}, - {9.69156f,9.50282f,9.23338f,9.25605f,9.28344f,8.98186f,8.56848f,8.04846f,6.56771f,3.06569f,-2.75457f,-9.75616f,-15.91853f,-19.62874f,-20.10653f,-17.62100f,-13.38807f,-8.80249f,-4.83206f,-1.62618f,0.85458f,1.72352f,0.35339f,-2.00271f,-3.58526f,-3.93648f,-3.30170f,-1.78891f,-0.13334f,0.41999f,0.14853f,0.72192f,2.61852f,5.02104f,7.34668f,9.06648f,9.69156f}, - {8.99220f,9.02256f,8.80901f,8.93941f,9.15462f,8.99412f,8.49413f,7.54605f,5.38233f,1.29060f,-4.51973f,-10.72800f,-15.61393f,-17.87879f,-17.08037f,-13.87843f,-9.54744f,-5.34026f,-2.15287f,0.11672f,2.02473f,3.04733f,2.31093f,0.47960f,-0.96646f,-1.54925f,-1.53032f,-1.00772f,-0.42112f,-0.63497f,-1.37540f,-1.17754f,0.48492f,2.94585f,5.61932f,7.87900f,8.99220f}, - {8.04368f,8.88487f,9.24731f,9.76871f,10.30385f,10.32830f,9.60849f,7.94603f,4.81731f,-0.08975f,-6.10101f,-11.65411f,-15.25677f,-16.15822f,-14.52060f,-11.22653f,-7.24580f,-3.44558f,-0.61333f,1.25309f,2.76805f,3.73177f,3.36695f,1.97948f,0.74967f,0.13075f,-0.18979f,-0.42444f,-0.85420f,-1.93961f,-3.28866f,-3.62225f,-2.35247f,0.08639f,3.11990f,6.05468f,8.04368f}, - {6.44887f,8.52898f,10.00772f,11.25814f,12.19628f,12.38325f,11.43950f,9.05774f,4.87180f,-1.07081f,-7.58681f,-12.76972f,-15.34699f,-15.21292f,-13.06213f,-9.80318f,-6.10115f,-2.52848f,0.26062f,2.11110f,3.47313f,4.40612f,4.43031f,3.60979f,2.68625f,2.01876f,1.34276f,0.35243f,-1.18272f,-3.35038f,-5.50704f,-6.45531f,-5.60558f,-3.25332f,0.01287f,3.49652f,6.44887f}, - {4.61309f,7.91484f,10.67459f,12.86217f,14.28349f,14.59916f,13.44634f,10.43327f,5.19620f,-1.95110f,-9.25904f,-14.43995f,-16.45824f,-15.72227f,-13.22423f,-9.85034f,-6.14231f,-2.53072f,0.48676f,2.68447f,4.29956f,5.52570f,6.19623f,6.20084f,5.73301f,4.92006f,3.60085f,1.53163f,-1.39438f,-4.87688f,-7.94536f,-9.43097f,-8.85100f,-6.51552f,-3.06017f,0.84306f,4.61309f}, - {3.21875f,7.41586f,11.19354f,14.28261f,16.32057f,16.89633f,15.56524f,11.80300f,5.20653f,-3.55470f,-11.97809f,-17.43029f,-19.22616f,-18.17302f,-15.37952f,-11.69571f,-7.65025f,-3.63286f,-0.01295f,2.99661f,5.46716f,7.56207f,9.25413f,10.31810f,10.49165f,9.54146f,7.26006f,3.54973f,-1.33752f,-6.50635f,-10.55663f,-12.38793f,-11.79132f,-9.25449f,-5.49875f,-1.18292f,3.21875f}, - {2.52051f,7.33138f,11.79037f,15.58977f,18.29190f,19.30865f,17.85567f,12.95067f,3.98293f,-7.53431f,-17.54806f,-23.19596f,-24.60407f,-23.07402f,-19.77569f,-15.49637f,-10.73649f,-5.85097f,-1.12175f,3.26826f,7.26895f,10.88888f,14.03678f,16.41453f,17.52792f,16.76756f,13.54324f,7.61980f,-0.22282f,-7.89770f,-13.19396f,-15.21847f,-14.33135f,-11.37454f,-7.18383f,-2.40863f,2.52051f}, - {2.02983f,7.36989f,12.37081f,16.71056f,19.89761f,21.11515f,18.97400f,11.40232f,-2.70274f,-18.81527f,-29.66002f,-33.88571f,-33.57644f,-30.58814f,-26.04521f,-20.59815f,-14.64262f,-8.44459f,-2.20066f,3.93897f,9.85468f,15.42277f,20.45728f,24.64081f,27.44761f,28.04182f,25.18387f,17.54097f,5.49796f,-6.72811f,-14.58218f,-17.34691f,-16.39748f,-13.14509f,-8.58967f,-3.38880f,2.02983f}, - {0.42359f,5.67280f,10.45897f,14.18719f,15.84273f,13.44387f,3.31185f,-17.06908f,-37.86930f,-48.41039f,-50.74957f,-48.66334f,-44.20871f,-38.40471f,-31.78712f,-24.66267f,-17.22360f,-9.60278f,-1.90231f,5.78964f,13.38658f,20.79088f,27.87654f,34.46122f,40.25514f,44.75763f,47.03469f,45.25758f,36.18138f,17.77476f,-1.60905f,-12.11869f,-14.89059f,-13.37813f,-9.65915f,-4.84192f,0.42359f}, - {-178.76222f,-168.76222f,-158.76222f,-148.76222f,-138.76222f,-128.76222f,-118.76222f,-108.76222f,-98.76222f,-88.76222f,-78.76222f,-68.76222f,-58.76222f,-48.76222f,-38.76222f,-28.76222f,-18.76222f,-8.76222f,1.23778f,11.23778f,21.23778f,31.23778f,41.23778f,51.23778f,61.23778f,71.23778f,81.23778f,91.23778f,101.23778f,111.23778f,121.23778f,131.23778f,141.23778f,151.23778f,161.23778f,171.23778f,-178.76222f} + {148.63040f,138.63040f,128.63040f,118.63040f,108.63040f,98.63040f,88.63040f,78.63040f,68.63040f,58.63040f,48.63040f,38.63040f,28.63040f,18.63040f,8.63040f,-1.36960f,-11.36960f,-21.36960f,-31.36960f,-41.36960f,-51.36960f,-61.36960f,-71.36960f,-81.36960f,-91.36960f,-101.36960f,-111.36960f,-121.36960f,-131.36960f,-141.36960f,-151.36960f,-161.36960f,-171.36960f,178.63040f,168.63040f,158.63040f,148.63040f}, + {128.87816f,116.70769f,105.62443f,95.48127f,86.09683f,77.29367f,68.91718f,60.84302f,52.97822f,45.25811f,37.64003f,30.09478f,22.59702f,15.11676f,7.61418f,0.03947f,-7.66207f,-15.54157f,-23.63819f,-31.97410f,-40.55489f,-49.37538f,-58.42917f,-67.71936f,-77.26833f,-87.12519f,-97.37007f,-108.11458f,-119.49579f,-131.65830f,-144.71588f,-158.68662f,-173.41452f,171.47213f,156.49935f,142.18469f,128.87816f}, + {85.86755f,77.88182f,71.42849f,65.89217f,60.86962f,56.04972f,51.17842f,46.06489f,40.60132f,34.77619f,28.67056f,22.43282f,16.23087f,10.18755f,4.31917f,-1.49067f,-7.45797f,-13.81467f,-20.71641f,-28.18762f,-36.12471f,-44.34676f,-52.66473f,-60.93937f,-69.11381f,-77.22546f,-85.41334f,-93.94372f,-103.29064f,-114.35005f,-128.97727f,-151.06023f,174.83520f,137.67818f,112.23020f,96.52063f,85.86756f}, + {48.43188f,46.98353f,45.36982f,43.80186f,42.32760f,40.82382f,38.99678f,36.46379f,32.90329f,28.18877f,22.45599f,16.10387f,9.71432f,3.86202f,-1.14650f,-5.45997f,-9.64078f,-14.38658f,-20.18766f,-27.11174f,-34.80967f,-42.71859f,-50.31107f,-57.23008f,-63.28782f,-68.39719f,-72.47622f,-75.31221f,-76.30788f,-73.74072f,-61.55512f,-18.96160f,29.20071f,44.46666f,48.67974f,49.28540f,48.43188f}, + {31.58850f,31.74835f,31.39924f,30.87678f,30.43574f,30.19800f,29.98360f,29.24010f,27.23113f,23.37602f,17.54538f,10.24099f,2.57680f,-4.11819f,-8.98330f,-12.08874f,-14.32383f,-16.91831f,-20.97106f,-26.92020f,-34.17714f,-41.56631f,-48.09571f,-53.19469f,-56.53278f,-57.82558f,-56.66031f,-52.27310f,-43.55594f,-29.95085f,-13.24765f,2.54212f,14.60798f,22.72224f,27.72553f,30.44935f,31.58850f}, + {22.79850f,23.32533f,23.34746f,23.05694f,22.66226f,22.42885f,22.46289f,22.41289f,21.37705f,18.23370f,12.30982f,4.02530f,-4.93197f,-12.42012f,-17.23389f,-19.62803f,-20.56810f,-20.93312f,-21.98947f,-25.41090f,-31.19026f,-37.44166f,-42.49725f,-45.51856f,-46.02918f,-43.74555f,-38.55838f,-30.56411f,-20.73773f,-11.07131f,-2.79308f,4.21937f,10.21441f,15.15242f,18.92948f,21.44642f,22.79850f}, + {17.16987f,17.68582f,17.85385f,17.73377f,17.34906f,16.86130f,16.52747f,16.34574f,15.56790f,12.74839f,6.74610f,-2.00418f,-11.22826f,-18.37193f,-22.46233f,-24.19496f,-24.47888f,-23.22908f,-20.72783f,-19.60150f,-21.98233f,-26.43395f,-30.43203f,-32.35125f,-31.47499f,-27.95264f,-22.40690f,-15.51422f,-8.63620f,-3.35146f,0.42144f,3.87188f,7.48128f,10.95260f,13.91406f,16.01563f,17.16987f}, + {13.46149f,13.75829f,13.85281f,13.81813f,13.52893f,12.94281f,12.32698f,11.88976f,11.00215f,8.11359f,1.99478f,-6.62228f,-15.08744f,-21.05798f,-23.92224f,-24.34577f,-23.04831f,-19.84546f,-14.88685f,-10.38631f,-9.06427f,-11.31395f,-15.06340f,-17.65505f,-17.71488f,-15.54256f,-11.89991f,-7.27581f,-2.87289f,-0.16517f,1.24684f,2.97092f,5.51371f,8.29954f,10.80542f,12.58786f,13.46149f}, + {11.19370f,11.20122f,11.07257f,11.02175f,10.82482f,10.26986f,9.62418f,9.09716f,7.97068f,4.77978f,-1.35469f,-9.31946f,-16.55524f,-21.15274f,-22.50861f,-21.01857f,-17.63827f,-13.15823f,-8.29683f,-4.01764f,-1.51484f,-1.87967f,-4.62279f,-7.47003f,-8.63091f,-8.05888f,-6.24442f,-3.42551f,-0.62936f,0.67783f,0.89029f,1.80510f,3.93778f,6.48671f,8.83523f,10.50781f,11.19370f}, + {9.96310f,9.79689f,9.46606f,9.40362f,9.31492f,8.84240f,8.22130f,7.55735f,6.02850f,2.43377f,-3.55150f,-10.60044f,-16.54723f,-19.75861f,-19.59018f,-16.58982f,-12.16100f,-7.67553f,-3.93189f,-0.91522f,1.34973f,1.87637f,0.22653f,-2.15228f,-3.61566f,-3.90720f,-3.29932f,-1.83286f,-0.23997f,0.20367f,-0.19418f,0.32122f,2.29252f,4.85536f,7.33778f,9.21090f,9.96310f}, + {9.18888f,9.24336f,8.98253f,9.05281f,9.17191f,8.83598f,8.10836f,7.00345f,4.80464f,0.69064f,-5.15618f,-11.30079f,-15.93916f,-17.74937f,-16.42349f,-12.86230f,-8.44857f,-4.38855f,-1.42704f,0.70613f,2.51072f,3.31152f,2.34785f,0.48172f,-0.89199f,-1.49634f,-1.59901f,-1.18437f,-0.66243f,-0.94842f,-1.78088f,-1.62463f,0.11657f,2.73547f,5.55820f,7.95812f,9.18888f}, + {8.09034f,8.95675f,9.30400f,9.80188f,10.27100f,10.13647f,9.19791f,7.38846f,4.25004f,-0.60600f,-6.53915f,-11.93135f,-15.26054f,-15.79066f,-13.79060f,-10.27561f,-6.25103f,-2.56551f,0.07346f,1.80766f,3.24155f,4.05015f,3.51428f,2.10305f,0.93136f,0.25053f,-0.27213f,-0.70545f,-1.24346f,-2.37500f,-3.75122f,-4.07408f,-2.71911f,-0.15132f,2.99380f,6.02278f,8.09034f}, + {6.27792f,8.37723f,9.88296f,11.16334f,12.08487f,12.15767f,11.03142f,8.51947f,4.34248f,-1.47518f,-7.78911f,-12.71269f,-15.01118f,-14.61457f,-12.25578f,-8.87216f,-5.13675f,-1.63793f,0.99774f,2.71417f,3.98293f,4.78698f,4.67468f,3.82712f,2.93970f,2.18792f,1.25958f,-0.01231f,-1.71794f,-3.92282f,-6.03566f,-6.90283f,-5.95491f,-3.51614f,-0.20102f,3.30598f,6.27792f}, + {4.15672f,7.47883f,10.31556f,12.59798f,14.06987f,14.34572f,13.08042f,9.97537f,4.77447f,-2.16465f,-9.14687f,-14.00316f,-15.77819f,-14.88455f,-12.28640f,-8.84845f,-5.11869f,-1.55612f,1.34605f,3.41756f,4.91977f,6.01696f,6.56254f,6.51350f,6.02774f,5.09138f,3.48456f,1.07344f,-2.08240f,-5.60383f,-8.56486f,-9.89888f,-9.20525f,-6.83312f,-3.41374f,0.42499f,4.15672f}, + {2.38746f,6.60961f,10.51138f,13.76537f,15.94256f,16.59043f,15.27093f,11.52705f,5.06990f,-3.36003f,-11.36932f,-16.51244f,-18.15167f,-17.03678f,-14.21651f,-10.51524f,-6.47146f,-2.49805f,1.03216f,3.92789f,6.27640f,8.24229f,9.81368f,10.78355f,10.85070f,9.68870f,7.04509f,2.91449f,-2.25894f,-7.44786f,-11.30963f,-12.92043f,-12.20858f,-9.70263f,-6.08438f,-1.92562f,2.38746f}, + {1.14371f,5.95768f,10.55039f,14.56595f,17.51248f,18.77049f,17.56825f,12.99646f,4.54568f,-6.33792f,-15.91121f,-21.43028f,-22.88293f,-21.44177f,-18.22110f,-13.99911f,-9.28961f,-4.46489f,0.18470f,4.47851f,8.37200f,11.87759f,14.90388f,17.13814f,18.04159f,16.93503f,13.18748f,6.66358f,-1.56678f,-9.20492f,-14.20053f,-15.96059f,-14.99797f,-12.15657f,-8.19328f,-3.64820f,1.14371f}, + {-0.35955f,4.92766f,9.99739f,14.51863f,17.99503f,19.64821f,18.23668f,11.99980f,-0.09657f,-14.74873f,-25.55246f,-30.33910f,-30.58104f,-28.00627f,-23.75441f,-18.51083f,-12.70165f,-6.61593f,-0.46628f,5.58665f,11.41580f,16.88997f,21.81133f,25.83916f,28.40134f,28.57592f,24.99531f,16.28607f,3.28542f,-9.10495f,-16.59733f,-19.05958f,-18.04316f,-14.91590f,-10.58486f,-5.61478f,-0.35955f}, + {-5.35521f,-0.10619f,4.69597f,8.54683f,10.65268f,9.65875f,3.42678f,-9.71040f,-26.04578f,-37.63969f,-42.28407f,-42.02380f,-38.82980f,-33.88684f,-27.86664f,-21.16414f,-14.02720f,-6.62426f,0.91924f,8.49972f,16.02040f,23.37681f,30.43782f,37.01500f,42.80483f,47.26542f,49.32663f,46.69337f,34.75696f,10.85970f,-10.89085f,-20.36338f,-21.94791f,-19.71753f,-15.63466f,-10.66363f,-5.35521f}, + {-166.99999f,-156.99999f,-146.99999f,-136.99999f,-126.99999f,-116.99999f,-106.99999f,-96.99999f,-86.99999f,-76.99999f,-66.99999f,-56.99999f,-46.99999f,-36.99999f,-26.99999f,-16.99999f,-6.99999f,3.00001f,13.00001f,23.00001f,33.00000f,43.00000f,53.00000f,63.00000f,73.00000f,83.00000f,93.00000f,103.00000f,113.00000f,123.00000f,133.00000f,143.00000f,153.00000f,163.00000f,173.00000f,-177.00000f,-167.00000f} }; #else /* !NAV_AUTO_MAG_DECLINATION_PRECISE */ @@ -45,19 +45,19 @@ static const float declination_table[19][37] = { #define SAMPLING_MAX_LAT 60.00000f static const int8_t declination_table[13][37] = { - {48,46,45,43,42,41,39,37,33,28,23,16,10,4,-1,-6,-10,-15,-20,-27,-34,-42,-50,-56,-62,-68,-72,-74,-75,-73,-61,-21,26,43,47,48,48}, - {31,31,31,31,30,30,30,29,27,24,18,11,3,-4,-9,-13,-15,-18,-21,-27,-34,-41,-47,-52,-56,-57,-56,-52,-44,-30,-14,2,14,22,27,30,31}, - {22,23,23,23,23,22,22,23,22,19,13,5,-4,-12,-17,-20,-22,-22,-23,-26,-31,-36,-42,-45,-46,-44,-39,-31,-21,-11,-3,4,10,15,19,21,22}, - {17,17,18,18,17,17,17,17,16,13,8,-1,-10,-18,-23,-25,-26,-25,-22,-20,-21,-25,-30,-32,-31,-28,-23,-16,-9,-3,0,4,7,11,14,16,17}, - {13,13,14,14,13,13,13,12,11,9,3,-5,-14,-20,-24,-25,-24,-21,-16,-11,-9,-11,-14,-17,-18,-16,-12,-8,-3,0,1,3,6,8,11,12,13}, - {11,11,11,11,11,10,10,9,8,5,0,-8,-16,-21,-23,-22,-19,-15,-10,-5,-2,-2,-4,-7,-9,-8,-6,-4,-1,1,1,2,4,7,9,10,11}, - {10,10,9,9,9,9,9,8,7,3,-3,-10,-16,-20,-20,-18,-13,-9,-5,-2,1,2,0,-2,-4,-4,-3,-2,0,0,0,1,3,5,7,9,10}, - {9,9,9,9,9,9,8,8,5,1,-5,-11,-16,-18,-17,-14,-10,-5,-2,0,2,3,2,0,-1,-2,-2,-1,0,-1,-1,-1,0,3,6,8,9}, - {8,9,9,10,10,10,10,8,5,0,-6,-12,-15,-16,-15,-11,-7,-3,-1,1,3,4,3,2,1,0,0,0,-1,-2,-3,-4,-2,0,3,6,8}, - {6,9,10,11,12,12,11,9,5,-1,-8,-13,-15,-15,-13,-10,-6,-3,0,2,3,4,4,4,3,2,1,0,-1,-3,-6,-6,-6,-3,0,3,6}, - {5,8,11,13,14,15,13,10,5,-2,-9,-14,-16,-16,-13,-10,-6,-3,0,3,4,6,6,6,6,5,4,2,-1,-5,-8,-9,-9,-7,-3,1,5}, - {3,7,11,14,16,17,16,12,5,-4,-12,-17,-19,-18,-15,-12,-8,-4,0,3,5,8,9,10,10,10,7,4,-1,-7,-11,-12,-12,-9,-5,-1,3}, - {3,7,12,16,18,19,18,13,4,-8,-18,-23,-25,-23,-20,-15,-11,-6,-1,3,7,11,14,16,18,17,14,8,0,-8,-13,-15,-14,-11,-7,-2,3} + {48,47,45,44,42,41,39,36,33,28,22,16,10,4,-1,-5,-10,-14,-20,-27,-35,-43,-50,-57,-63,-68,-72,-75,-76,-74,-62,-19,29,44,49,49,48}, + {32,32,31,31,30,30,30,29,27,23,18,10,3,-4,-9,-12,-14,-17,-21,-27,-34,-42,-48,-53,-57,-58,-57,-52,-44,-30,-13,3,15,23,28,30,32}, + {23,23,23,23,23,22,22,22,21,18,12,4,-5,-12,-17,-20,-21,-21,-22,-25,-31,-37,-42,-46,-46,-44,-39,-31,-21,-11,-3,4,10,15,19,21,23}, + {17,18,18,18,17,17,17,16,16,13,7,-2,-11,-18,-22,-24,-24,-23,-21,-20,-22,-26,-30,-32,-31,-28,-22,-16,-9,-3,0,4,7,11,14,16,17}, + {13,14,14,14,14,13,12,12,11,8,2,-7,-15,-21,-24,-24,-23,-20,-15,-10,-9,-11,-15,-18,-18,-16,-12,-7,-3,0,1,3,6,8,11,13,13}, + {11,11,11,11,11,10,10,9,8,5,-1,-9,-17,-21,-23,-21,-18,-13,-8,-4,-2,-2,-5,-7,-9,-8,-6,-3,-1,1,1,2,4,6,9,11,11}, + {10,10,9,9,9,9,8,8,6,2,-4,-11,-17,-20,-20,-17,-12,-8,-4,-1,1,2,0,-2,-4,-4,-3,-2,0,0,0,0,2,5,7,9,10}, + {9,9,9,9,9,9,8,7,5,1,-5,-11,-16,-18,-16,-13,-8,-4,-1,1,3,3,2,0,-1,-1,-2,-1,-1,-1,-2,-2,0,3,6,8,9}, + {8,9,9,10,10,10,9,7,4,-1,-7,-12,-15,-16,-14,-10,-6,-3,0,2,3,4,4,2,1,0,0,-1,-1,-2,-4,-4,-3,0,3,6,8}, + {6,8,10,11,12,12,11,9,4,-1,-8,-13,-15,-15,-12,-9,-5,-2,1,3,4,5,5,4,3,2,1,0,-2,-4,-6,-7,-6,-4,0,3,6}, + {4,7,10,13,14,14,13,10,5,-2,-9,-14,-16,-15,-12,-9,-5,-2,1,3,5,6,7,7,6,5,3,1,-2,-6,-9,-10,-9,-7,-3,0,4}, + {2,7,11,14,16,17,15,12,5,-3,-11,-17,-18,-17,-14,-11,-6,-2,1,4,6,8,10,11,11,10,7,3,-2,-7,-11,-13,-12,-10,-6,-2,2}, + {1,6,11,15,18,19,18,13,5,-6,-16,-21,-23,-21,-18,-14,-9,-4,0,4,8,12,15,17,18,17,13,7,-2,-9,-14,-16,-15,-12,-8,-4,1} }; #endif diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index db4b3229d5..49fbf11ab5 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -271,7 +271,7 @@ static int8_t loiterDirection(void) { static void calculateVirtualPositionTarget_FW(float trackingPeriod) { - if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { + if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) || posControl.navState == NAV_STATE_FW_LANDING_GLIDE || posControl.navState == NAV_STATE_FW_LANDING_FLARE) { return; } @@ -405,7 +405,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta static bool forceTurnDirection = false; int32_t virtualTargetBearing; - if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { + if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) || posControl.navState == NAV_STATE_FW_LANDING_GLIDE || posControl.navState == NAV_STATE_FW_LANDING_FLARE) { virtualTargetBearing = posControl.desiredState.yaw; } else { // We have virtual position target, calculate heading error @@ -643,15 +643,11 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat uint16_t correctedThrottleValue = constrain(currentBatteryProfile->nav.fw.cruise_throttle + throttleCorrection, currentBatteryProfile->nav.fw.min_throttle, currentBatteryProfile->nav.fw.max_throttle); // Manual throttle increase -#ifdef USE_FW_AUTOLAND - if (navConfig()->fw.allow_manual_thr_increase && !FLIGHT_MODE(FAILSAFE_MODE) && !isFwLandInProgess()) { -#else - if (navConfig()->fw.allow_manual_thr_increase && !FLIGHT_MODE(FAILSAFE_MODE)) { -#endif + if (navConfig()->fw.allow_manual_thr_increase && !FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_FW_AUTOLAND)) { if (rcCommand[THROTTLE] < PWM_RANGE_MIN + (PWM_RANGE_MAX - PWM_RANGE_MIN) * 0.95){ correctedThrottleValue += MAX(0, rcCommand[THROTTLE] - currentBatteryProfile->nav.fw.cruise_throttle); } else { - correctedThrottleValue = motorConfig()->maxthrottle; + correctedThrottleValue = getMaxThrottle(); } isAutoThrottleManuallyIncreased = (rcCommand[THROTTLE] > currentBatteryProfile->nav.fw.cruise_throttle); } else { @@ -665,7 +661,6 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat // Advanced autoland if (posControl.navState == NAV_STATE_FW_LANDING_GLIDE || posControl.navState == NAV_STATE_FW_LANDING_FLARE || STATE(LANDING_DETECTED)) { // Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled - rcCommand[THROTTLE] = getThrottleIdleValue(); ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); if (posControl.navState == NAV_STATE_FW_LANDING_GLIDE) { @@ -727,6 +722,7 @@ bool isFixedWingLandingDetected(void) // Basic condition to start looking for landing bool startCondition = (navGetCurrentStateFlags() & (NAV_CTL_LAND | NAV_CTL_EMERG)) || FLIGHT_MODE(FAILSAFE_MODE) + || FLIGHT_MODE(NAV_FW_AUTOLAND) || (!navigationIsControllingThrottle() && throttleStickIsLow()); if (!startCondition || posControl.flags.resetLandingDetector) { diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 5708e5dcaa..cc6256dbdd 100644 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -49,6 +49,7 @@ #include "io/gps.h" #include "sensors/battery.h" +#include "sensors/gyro.h" #define SWING_LAUNCH_MIN_ROTATION_RATE DEGREES_TO_RADIANS(100) // expect minimum 100dps rotation rate #define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms @@ -81,20 +82,22 @@ typedef enum { typedef enum { // if changed update navFwLaunchStatus_e FW_LAUNCH_STATE_WAIT_THROTTLE = 0, + FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT, FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, FW_LAUNCH_STATE_MOTOR_IDLE, FW_LAUNCH_STATE_WAIT_DETECTION, - FW_LAUNCH_STATE_DETECTED, // 4 + FW_LAUNCH_STATE_DETECTED, // FW_LAUNCH_DETECTED = 5 FW_LAUNCH_STATE_MOTOR_DELAY, FW_LAUNCH_STATE_MOTOR_SPINUP, FW_LAUNCH_STATE_IN_PROGRESS, FW_LAUNCH_STATE_FINISH, - FW_LAUNCH_STATE_ABORTED, // 9 - FW_LAUNCH_STATE_FLYING, // 10 + FW_LAUNCH_STATE_ABORTED, // FW_LAUNCH_ABORTED = 10 + FW_LAUNCH_STATE_FLYING, // FW_LAUNCH_FLYING = 11 FW_LAUNCH_STATE_COUNT } fixedWingLaunchState_t; static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs_t currentTimeUs); +static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_DETECTION(timeUs_t currentTimeUs); @@ -126,12 +129,22 @@ static const fixedWingLaunchStateDescriptor_t launchStateMachine[FW_LAUNCH_STATE [FW_LAUNCH_STATE_WAIT_THROTTLE] = { .onEntry = fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE, .onEvent = { - [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, + [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT, [FW_LAUNCH_EVENT_GOTO_DETECTION] = FW_LAUNCH_STATE_WAIT_DETECTION }, .messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE }, + [FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT] = { + .onEntry = fwLaunchState_FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT, + .onEvent = { + [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_MOTOR_IDLE, + [FW_LAUNCH_EVENT_GOTO_DETECTION] = FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, + [FW_LAUNCH_EVENT_THROTTLE_LOW] = FW_LAUNCH_STATE_WAIT_THROTTLE, + }, + .messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE + }, + [FW_LAUNCH_STATE_IDLE_MOTOR_DELAY] = { .onEntry = fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, .onEvent = { @@ -243,6 +256,47 @@ static void applyThrottleIdleLogic(bool forceMixerIdle) } } +static bool hasIdleWakeWiggleSucceeded(timeUs_t currentTimeUs) { + static timeMs_t wiggleTime = 0; + static timeMs_t wigglesTime = 0; + static int8_t wiggleStageOne = 0; + static uint8_t wiggleCount = 0; + const bool isAircraftWithinLaunchAngle = (calculateCosTiltAngle() >= cos_approx(DEGREES_TO_RADIANS(navConfig()->fw.launch_max_angle))); + const uint8_t wiggleStrength = (navConfig()->fw.launch_wiggle_wake_idle == 1) ? 50 : 40; + int8_t wiggleDirection = 0; + int16_t yawRate = (int16_t)(gyroRateDps(YAW) * (4 / 16.4)); + + // Check to see if yaw rate has exceeded 50 dps. If so proceed to the next stage or continue to idle + if ((yawRate < -wiggleStrength || yawRate > wiggleStrength) && isAircraftWithinLaunchAngle) { + wiggleDirection = (yawRate > 0) ? 1 : -1; + + if (wiggleStageOne == 0) { + wiggleStageOne = wiggleDirection; + wigglesTime = US2MS(currentTimeUs); + } else if (wiggleStageOne != wiggleDirection) { + wiggleStageOne = 0; + wiggleCount++; + + if (wiggleCount == navConfig()->fw.launch_wiggle_wake_idle) { + return true; + } + } + + wiggleTime = US2MS(currentTimeUs); + } + + // If time between wiggle stages is > 100ms, or the time between two wiggles is > 1s. Reset the wiggle + if ( + ((wiggleStageOne != 0) && (US2MS(currentTimeUs) > (wiggleTime + 100))) || + ((wiggleCount != 0) && (US2MS(currentTimeUs) > (wigglesTime + 500))) + ) { + wiggleStageOne = 0; + wiggleCount = 0; + } + + return false; +} + static inline bool isLaunchMaxAltitudeReached(void) { return (navConfig()->fw.launch_max_altitude > 0) && (getEstimatedActualPosition(Z) >= navConfig()->fw.launch_max_altitude); @@ -300,6 +354,25 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs return FW_LAUNCH_EVENT_NONE; } +static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT(timeUs_t currentTimeUs) { + if (throttleStickIsLow()) { + return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE + } + + if (navConfig()->fw.launch_wiggle_wake_idle == 0 || navConfig()->fw.launch_idle_motor_timer > 0 ) { + return FW_LAUNCH_EVENT_GOTO_DETECTION; + } + + applyThrottleIdleLogic(true); + + if (hasIdleWakeWiggleSucceeded(currentTimeUs)) { + idleMotorAboutToStart = false; + return FW_LAUNCH_EVENT_SUCCESS; + } + + return FW_LAUNCH_EVENT_NONE; +} + static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs) { if (throttleStickIsLow()) { @@ -308,10 +381,11 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(tim applyThrottleIdleLogic(true); - if (currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) { + if ((currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) || (navConfig()->fw.launch_wiggle_wake_idle > 0 && hasIdleWakeWiggleSucceeded(currentTimeUs))) { idleMotorAboutToStart = false; return FW_LAUNCH_EVENT_SUCCESS; } + // 5 second warning motor about to start at idle, changes Beeper sound idleMotorAboutToStart = navConfig()->fw.launch_idle_motor_timer - currentStateElapsedMs(currentTimeUs) < 5000; diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index a9a6997a9f..54caccb52b 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -114,7 +114,7 @@ static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros) { // Calculate min and max throttle boundaries (to compensate for integral windup) const int16_t thrCorrectionMin = getThrottleIdleValue() - currentBatteryProfile->nav.mc.hover_throttle; - const int16_t thrCorrectionMax = motorConfig()->maxthrottle - currentBatteryProfile->nav.mc.hover_throttle; + const int16_t thrCorrectionMax = getMaxThrottle() - currentBatteryProfile->nav.mc.hover_throttle; float velocity_controller = navPidApply2(&posControl.pids.vel[Z], posControl.desiredState.vel.z, navGetCurrentActualPositionAndVelocity()->vel.z, US2S(deltaMicros), thrCorrectionMin, thrCorrectionMax, 0); @@ -127,7 +127,7 @@ static void updateAltitudeThrottleController_MC(timeDelta_t deltaMicros) bool adjustMulticopterAltitudeFromRCInput(void) { if (posControl.flags.isTerrainFollowEnabled) { - const float altTarget = scaleRangef(rcCommand[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle, 0, navConfig()->general.max_terrain_follow_altitude); + const float altTarget = scaleRangef(rcCommand[THROTTLE], getThrottleIdleValue(), getMaxThrottle(), 0, navConfig()->general.max_terrain_follow_altitude); // In terrain follow mode we apply different logic for terrain control if (posControl.flags.estAglStatus == EST_TRUSTED && altTarget > 10.0f) { @@ -151,7 +151,7 @@ bool adjustMulticopterAltitudeFromRCInput(void) // Make sure we can satisfy max_manual_climb_rate in both up and down directions if (rcThrottleAdjustment > 0) { // Scaling from altHoldThrottleRCZero to maxthrottle - rcClimbRate = rcThrottleAdjustment * navConfig()->mc.max_manual_climb_rate / (float)(motorConfig()->maxthrottle - altHoldThrottleRCZero - rcControlsConfig()->alt_hold_deadband); + rcClimbRate = rcThrottleAdjustment * navConfig()->mc.max_manual_climb_rate / (float)(getMaxThrottle() - altHoldThrottleRCZero - rcControlsConfig()->alt_hold_deadband); } else { // Scaling from minthrottle to altHoldThrottleRCZero @@ -190,7 +190,7 @@ void setupMulticopterAltitudeController(void) // Make sure we are able to satisfy the deadband altHoldThrottleRCZero = constrain(altHoldThrottleRCZero, getThrottleIdleValue() + rcControlsConfig()->alt_hold_deadband + 10, - motorConfig()->maxthrottle - rcControlsConfig()->alt_hold_deadband - 10); + getMaxThrottle() - rcControlsConfig()->alt_hold_deadband - 10); // Force AH controller to initialize althold integral for pending takeoff on reset // Signal for that is low throttle _and_ low actual altitude diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 3453c75c92..19018983cc 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -56,7 +56,7 @@ navigationPosEstimator_t posEstimator; static float initialBaroAltitudeOffset = 0.0f; -PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 5); +PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 6); PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, // Inertial position estimator parameters @@ -64,7 +64,6 @@ PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, .reset_altitude_type = SETTING_INAV_RESET_ALTITUDE_DEFAULT, .reset_home_type = SETTING_INAV_RESET_HOME_DEFAULT, .gravity_calibration_tolerance = SETTING_INAV_GRAVITY_CAL_TOLERANCE_DEFAULT, // 5 cm/s/s calibration error accepted (0.5% of gravity) - .use_gps_velned = SETTING_INAV_USE_GPS_VELNED_DEFAULT, // "Disabled" is mandatory with gps_dyn_model = Pedestrian .use_gps_no_baro = SETTING_INAV_USE_GPS_NO_BARO_DEFAULT, // Use GPS altitude if no baro is available on all aircrafts .allow_dead_reckoning = SETTING_INAV_ALLOW_DEAD_RECKONING_DEFAULT, @@ -229,7 +228,7 @@ void onNewGPSData(void) /* Use VELNED provided by GPS if available, calculate from coordinates otherwise */ float gpsScaleLonDown = constrainf(cos_approx((ABS(gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f), 0.01f, 1.0f); - if (!ARMING_FLAG(SIMULATOR_MODE_SITL) && positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelNE) { + if (!ARMING_FLAG(SIMULATOR_MODE_SITL) && gpsSol.flags.validVelNE) { posEstimator.gps.vel.x = gpsSol.velNED[X]; posEstimator.gps.vel.y = gpsSol.velNED[Y]; } @@ -238,7 +237,7 @@ void onNewGPSData(void) posEstimator.gps.vel.y = (posEstimator.gps.vel.y + (gpsScaleLonDown * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR * (gpsSol.llh.lon - previousLon) / dT)) / 2.0f; } - if (positionEstimationConfig()->use_gps_velned && gpsSol.flags.validVelD) { + if (gpsSol.flags.validVelD) { posEstimator.gps.vel.z = -gpsSol.velNED[Z]; // NEU } else { diff --git a/src/main/navigation/navigation_rover_boat.c b/src/main/navigation/navigation_rover_boat.c index 5f8134c6a2..8816880388 100644 --- a/src/main/navigation/navigation_rover_boat.c +++ b/src/main/navigation/navigation_rover_boat.c @@ -127,7 +127,7 @@ void applyRoverBoatPitchRollThrottleController(navigationFSMStateFlags_t navStat rcCommand[YAW] = posControl.rcAdjustment[YAW]; } - rcCommand[THROTTLE] = constrain(currentBatteryProfile->nav.fw.cruise_throttle, motorConfig()->mincommand, motorConfig()->maxthrottle); + rcCommand[THROTTLE] = constrain(currentBatteryProfile->nav.fw.cruise_throttle, motorConfig()->mincommand, getMaxThrottle()); } } } diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index ad1cb21c6c..343db2989f 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -483,8 +483,9 @@ static int logicConditionCompute( } break; -#ifdef LED_PIN +#ifdef USE_LED_STRIP case LOGIC_CONDITION_LED_PIN_PWM: + if (operandA >=0 && operandA <= 100) { ledPinStartPWM((uint8_t)operandA); } else { @@ -768,7 +769,7 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING: // 0/1 #ifdef USE_FW_AUTOLAND - return ((navGetCurrentStateFlags() & NAV_CTL_LAND) || isFwLandInProgess()) ? 1 : 0; + return ((navGetCurrentStateFlags() & NAV_CTL_LAND) || FLIGHT_MODE(NAV_FW_AUTOLAND)) ? 1 : 0; #else return ((navGetCurrentStateFlags() & NAV_CTL_LAND)) ? 1 : 0; #endif diff --git a/src/main/rx/crsf.h b/src/main/rx/crsf.h index 80e356223f..f3bc793349 100755 --- a/src/main/rx/crsf.h +++ b/src/main/rx/crsf.h @@ -45,7 +45,6 @@ enum { CRSF_FRAME_GPS_PAYLOAD_SIZE = 15, CRSF_FRAME_VARIO_SENSOR_PAYLOAD_SIZE = 2, CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE = 8, - CRSF_FRAME_BAROVARIO_SENSOR_PAYLOAD_SIZE = 4, CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE = 10, CRSF_FRAME_RC_CHANNELS_PAYLOAD_SIZE = 22, // 11 bits per channel * 16 channels = 22 bytes. CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE = 6, @@ -87,7 +86,6 @@ typedef enum { CRSF_FRAMETYPE_GPS = 0x02, CRSF_FRAMETYPE_VARIO_SENSOR = 0x07, CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08, - CRSF_FRAMETYPE_BAROVARIO_SENSOR = 0x09, CRSF_FRAMETYPE_LINK_STATISTICS = 0x14, CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16, CRSF_FRAMETYPE_ATTITUDE = 0x1E, diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 695f49b00b..4e46f17884 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -529,6 +529,15 @@ float accGetMeasuredMaxG(void) return acc.maxG; } +void resetGForceStats(void) { + acc.maxG = 0.0f; + + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + acc.extremes[axis].min = 100; + acc.extremes[axis].max = -100; + } +} + void accUpdate(void) { #ifdef USE_SIMULATOR diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index f3385edc6d..a25063ec4f 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -86,6 +86,7 @@ void accGetMeasuredAcceleration(fpVector3_t *measuredAcc); const acc_extremes_t* accGetMeasuredExtremes(void); float accGetMeasuredMaxG(void); void updateAccExtremes(void); +void resetGForceStats(void); void accGetVibrationLevels(fpVector3_t *accVibeLevels); float accGetVibrationLevel(void); uint32_t accGetClipCount(void); diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 3745ed7a8e..2ca7024694 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -66,7 +66,7 @@ #define ADCVREF 3300 // in mV (3300 = 3.3V) #define VBATT_CELL_FULL_MAX_DIFF 10 // Max difference with cell max voltage for the battery to be considered full (10mV steps) -#define VBATT_PRESENT_THRESHOLD 100 // Minimum voltage to consider battery present +#define VBATT_PRESENT_THRESHOLD 220 // Minimum voltage to consider battery present #define VBATT_STABLE_DELAY 40 // Delay after connecting battery to begin monitoring #define VBATT_HYSTERESIS 10 // Batt Hysteresis of +/-100mV for changing battery state #define VBATT_LPF_FREQ 1 // Battery voltage filtering cutoff diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index a586ce6df6..97e3f3be43 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -95,18 +95,15 @@ EXTENDED_FASTRAM secondaryDynamicGyroNotchState_t secondaryDynamicGyroNotchState #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 6); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 8); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, - .gyro_lpf = SETTING_GYRO_HARDWARE_LPF_DEFAULT, .gyro_anti_aliasing_lpf_hz = SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT, - .gyro_anti_aliasing_lpf_type = SETTING_GYRO_ANTI_ALIASING_LPF_TYPE_DEFAULT, .looptime = SETTING_LOOPTIME_DEFAULT, #ifdef USE_DUAL_GYRO .gyro_to_use = SETTING_GYRO_TO_USE_DEFAULT, #endif .gyro_main_lpf_hz = SETTING_GYRO_MAIN_LPF_HZ_DEFAULT, - .gyro_main_lpf_type = SETTING_GYRO_MAIN_LPF_TYPE_DEFAULT, .useDynamicLpf = SETTING_GYRO_USE_DYN_LPF_DEFAULT, .gyroDynamicLpfMinHz = SETTING_GYRO_DYN_LPF_MIN_HZ_DEFAULT, .gyroDynamicLpfMaxHz = SETTING_GYRO_DYN_LPF_MAX_HZ_DEFAULT, @@ -233,24 +230,13 @@ STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHard return gyroHardware; } -static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint8_t type, uint16_t cutoff, uint32_t looptime) +static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint16_t cutoff, uint32_t looptime) { *applyFn = nullFilterApply; if (cutoff > 0) { - switch (type) - { - case FILTER_PT1: - *applyFn = (filterApplyFnPtr)pt1FilterApply; - for (int axis = 0; axis < 3; axis++) { - pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); - } - break; - case FILTER_BIQUAD: - *applyFn = (filterApplyFnPtr)biquadFilterApply; - for (int axis = 0; axis < 3; axis++) { - biquadFilterInitLPF(&state[axis].biquad, cutoff, looptime); - } - break; + *applyFn = (filterApplyFnPtr)pt1FilterApply; + for (int axis = 0; axis < 3; axis++) { + pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); } } } @@ -258,10 +244,10 @@ static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint8_t static void gyroInitFilters(void) { //First gyro LPF running at full gyro frequency 8kHz - initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_anti_aliasing_lpf_type, gyroConfig()->gyro_anti_aliasing_lpf_hz, getGyroLooptime()); + initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_anti_aliasing_lpf_hz, getGyroLooptime()); //Second gyro LPF runnig and PID frequency - this filter is dynamic when gyro_use_dyn_lpf = ON - initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_main_lpf_type, gyroConfig()->gyro_main_lpf_hz, getLooptime()); + initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_main_lpf_hz, getLooptime()); #ifdef USE_GYRO_KALMAN if (gyroConfig()->kalmanEnabled) { @@ -295,7 +281,7 @@ bool gyroInit(void) sensorsSet(SENSOR_GYRO); // Driver initialisation - gyroDev[0].lpf = gyroConfig()->gyro_lpf; + gyroDev[0].lpf = GYRO_LPF_256HZ; gyroDev[0].requestedSampleIntervalUs = TASK_GYRO_LOOPTIME; gyroDev[0].sampleRateIntervalUs = TASK_GYRO_LOOPTIME; gyroDev[0].initFn(&gyroDev[0]); @@ -566,14 +552,8 @@ int16_t gyroRateDps(int axis) } void gyroUpdateDynamicLpf(float cutoffFreq) { - if (gyroConfig()->gyro_main_lpf_type == FILTER_PT1) { - for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - pt1FilterUpdateCutoff(&gyroLpf2State[axis].pt1, cutoffFreq); - } - } else if (gyroConfig()->gyro_main_lpf_type == FILTER_BIQUAD) { - for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - biquadFilterUpdate(&gyroLpf2State[axis].biquad, cutoffFreq, getLooptime(), BIQUAD_Q, FILTER_LPF); - } + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + pt1FilterUpdateCutoff(&gyroLpf2State[axis].pt1, cutoffFreq); } } diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 669f8fbee4..2ea70c589d 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -49,12 +49,6 @@ typedef enum { typedef enum { DYNAMIC_NOTCH_MODE_2D = 0, - DYNAMIC_NOTCH_MODE_R, - DYNAMIC_NOTCH_MODE_P, - DYNAMIC_NOTCH_MODE_Y, - DYNAMIC_NOTCH_MODE_RP, - DYNAMIC_NOTCH_MODE_RY, - DYNAMIC_NOTCH_MODE_PY, DYNAMIC_NOTCH_MODE_3D } dynamicGyroNotchMode_e; @@ -70,14 +64,11 @@ extern dynamicGyroNotchState_t dynamicGyroNotchState; typedef struct gyroConfig_s { uint16_t looptime; // imu loop time in us - uint8_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen. uint16_t gyro_anti_aliasing_lpf_hz; - uint8_t gyro_anti_aliasing_lpf_type; #ifdef USE_DUAL_GYRO uint8_t gyro_to_use; #endif uint16_t gyro_main_lpf_hz; - uint8_t gyro_main_lpf_type; uint8_t useDynamicLpf; uint16_t gyroDynamicLpfMinHz; uint16_t gyroDynamicLpfMaxHz; diff --git a/src/main/sensors/rangefinder.c b/src/main/sensors/rangefinder.c index a4af166cfe..88f027f154 100644 --- a/src/main/sensors/rangefinder.c +++ b/src/main/sensors/rangefinder.c @@ -41,6 +41,7 @@ #include "drivers/rangefinder/rangefinder_vl53l1x.h" #include "drivers/rangefinder/rangefinder_virtual.h" #include "drivers/rangefinder/rangefinder_us42.h" +#include "drivers/rangefinder/rangefinder_teraranger_evo.h" #include "drivers/rangefinder/rangefinder_tof10120_i2c.h" #include "fc/config.h" @@ -88,6 +89,14 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar #endif break; + case RANGEFINDER_TERARANGER_EVO: +#if defined(USE_RANGEFINDER_TERARANGER_EVO_I2C) + if (teraRangerDetect(dev)) { + rangefinderHardware = RANGEFINDER_TERARANGER_EVO; + rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TERA_EVO_TASK_PERIOD_MS)); + } +#endif + break; case RANGEFINDER_VL53L0X: #if defined(USE_RANGEFINDER_VL53L0X) if (vl53l0xDetect(dev)) { diff --git a/src/main/sensors/rangefinder.h b/src/main/sensors/rangefinder.h index a57253bd3f..2888e7838a 100644 --- a/src/main/sensors/rangefinder.h +++ b/src/main/sensors/rangefinder.h @@ -22,15 +22,16 @@ #include "drivers/rangefinder/rangefinder.h" typedef enum { - RANGEFINDER_NONE = 0, - RANGEFINDER_SRF10 = 1, - RANGEFINDER_VL53L0X = 2, - RANGEFINDER_MSP = 3, - RANGEFINDER_BENEWAKE = 4, - RANGEFINDER_VL53L1X = 5, - RANGEFINDER_US42 = 6, - RANGEFINDER_TOF10102I2C = 7, - RANGEFINDER_FAKE = 8, + RANGEFINDER_NONE = 0, + RANGEFINDER_SRF10 = 1, + RANGEFINDER_VL53L0X = 2, + RANGEFINDER_MSP = 3, + RANGEFINDER_BENEWAKE = 4, + RANGEFINDER_VL53L1X = 5, + RANGEFINDER_US42 = 6, + RANGEFINDER_TOF10102I2C = 7, + RANGEFINDER_FAKE = 8, + RANGEFINDER_TERARANGER_EVO = 9, } rangefinderType_e; typedef struct rangefinderConfig_s { diff --git a/src/main/target/AOCODARCF405AIO/target.h b/src/main/target/AOCODARCF405AIO/target.h index a45205fbc5..d732ebdd04 100644 --- a/src/main/target/AOCODARCF405AIO/target.h +++ b/src/main/target/AOCODARCF405AIO/target.h @@ -142,7 +142,8 @@ #define SERIALRX_UART SERIAL_PORT_USART2 #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_PROVIDER SERIALRX_CRSF -#define CURRENT_METER_SCALE 500 +#define CURRENT_METER_SCALE 589 +#define CURRENT_METER_OFFSET -204 /*** Optical Flow & Lidar ***/ #define USE_RANGEFINDER diff --git a/src/main/target/AOCODARCF4V3/CMakeLists.txt b/src/main/target/AOCODARCF4V3/CMakeLists.txt new file mode 100644 index 0000000000..706b818e2b --- /dev/null +++ b/src/main/target/AOCODARCF4V3/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f405xg(AOCODARCF4V3_SD) +target_stm32f405xg(AOCODARCF4V3) + diff --git a/src/main/target/AOCODARCF4V3/config.c b/src/main/target/AOCODARCF4V3/config.c new file mode 100644 index 0000000000..c80a92940a --- /dev/null +++ b/src/main/target/AOCODARCF4V3/config.c @@ -0,0 +1,40 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ +#include + +#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; + pinioBoxConfigMutable()->permanentId[2] = BOX_PERMANENT_ID_USER3; + // beeperConfigMutable()->pwmMode = true; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].msp_baudrateIndex = BAUD_115200; + serialConfigMutable()->portConfigs[4].functionMask = FUNCTION_VTX_TRAMP; + serialConfigMutable()->portConfigs[4].peripheral_baudrateIndex = BAUD_115200; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_RX_SERIAL; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_ESCSERIAL; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_GPS; +} diff --git a/src/main/target/AOCODARCF4V3/target.c b/src/main/target/AOCODARCF4V3/target.c new file mode 100644 index 0000000000..8581cc5bf1 --- /dev/null +++ b/src/main/target/AOCODARCF4V3/target.c @@ -0,0 +1,46 @@ +/* + * 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 . + */ + + +#include + +#include "platform.h" +#include "drivers/io.h" +#include "drivers/timer.h" +#include "drivers/pwm_mapping.h" +#include "drivers/bus.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0 ), // PPM IN + + 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_OUTPUT_AUTO, 0, 0 ), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S6 + + 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 + + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF4V3/target.h b/src/main/target/AOCODARCF4V3/target.h new file mode 100644 index 0000000000..0c95564162 --- /dev/null +++ b/src/main/target/AOCODARCF4V3/target.h @@ -0,0 +1,192 @@ +/* + * 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 . + */ + +#pragma once + +#define USE_TARGET_CONFIG + +#ifdef AOCODARCF4V3 +#define TARGET_BOARD_IDENTIFIER "AOF4V3" +#define USBD_PRODUCT_STRING "AOCODARCF4V3" +#else +#define TARGET_BOARD_IDENTIFIER "AOF4V3SD" +#define USBD_PRODUCT_STRING "AOCODARCF4V3_SD" +#endif + +// ******** Board LEDs ********************** +#define LED0 PC13 + +// ******* Beeper *********** +#define BEEPER PB8 +#define BEEPER_INVERTED + + +// ******* GYRO and ACC ******** +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW90_DEG +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_CS_PIN PA4 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW90_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + + +// *************** Baro ************************** +#define USE_I2C +#define USE_I2C_DEVICE_1 + +#define I2C1_SCL PB6 // SCL +#define I2C1_SDA PB7 // SDA +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define BARO_I2C_BUS DEFAULT_I2C_BUS + +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +//*********** Magnetometer / Compass ************* +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS +#define USE_MAG_ALL + +// ******* SERIAL ******** +#define USE_VCP +#define VBUS_SENSING_PIN PB12 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + + +#define SERIAL_PORT_COUNT 6 + + +// ******* SPI ******** +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PA13 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PC0 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// ******* ADC ******** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PC3 + +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 + +#define VBAT_SCALE_DEFAULT 1100 +#define CURRENT_METER_SCALE 206 + +// ******* OSD ******** +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PA13 + +//******* FLASH ******** +#if defined(AOCODARCF4V3_SD) +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PC0 +#define SDCARD_DETECT_INVERTED +#define SDCARD_DETECT_PIN PC14 +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#else +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PC0 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#endif +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC5 // VTX power switcher +#define PINIO2_PIN PA14 //bluetooth +#define PINIO3_PIN PC15 //Camera control +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED +#define PINIO2_FLAGS PINIO_FLAGS_INVERTED + +//************ LEDSTRIP ***************** +#define USE_LED_STRIP +#define WS2811_PIN PB1 + +// ******* FEATURES ******** +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART2 +#define SERIALRX_PROVIDER SERIALRX_CRSF + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_GPS | FEATURE_BLACKBOX | FEATURE_LED_STRIP) + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 10 + +// ESC-related features +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/AOCODARCH7DUAL/target.c b/src/main/target/AOCODARCH7DUAL/target.c index 85e8b00493..ac3be12719 100644 --- a/src/main/target/AOCODARCH7DUAL/target.c +++ b/src/main/target/AOCODARCH7DUAL/target.c @@ -36,11 +36,11 @@ timerHardware_t timerHardware[] = { 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_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, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 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 diff --git a/src/main/target/ASGARD32F4/config.c b/src/main/target/ASGARD32F4/config.c index 9aaa2793ce..fee0992038 100644 --- a/src/main/target/ASGARD32F4/config.c +++ b/src/main/target/ASGARD32F4/config.c @@ -36,5 +36,4 @@ void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT; - motorConfigMutable()->maxthrottle = 1950; } diff --git a/src/main/target/ASGARD32F7/config.c b/src/main/target/ASGARD32F7/config.c index 9aaa2793ce..fee0992038 100644 --- a/src/main/target/ASGARD32F7/config.c +++ b/src/main/target/ASGARD32F7/config.c @@ -36,5 +36,4 @@ void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT; - motorConfigMutable()->maxthrottle = 1950; } diff --git a/src/main/target/BETAFPVF411/CMakeLists.txt b/src/main/target/BETAFPVF411/CMakeLists.txt new file mode 100644 index 0000000000..087194803c --- /dev/null +++ b/src/main/target/BETAFPVF411/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f411xe(BETAFPVF411 SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/BETAFPVF411/target.c b/src/main/target/BETAFPVF411/target.c new file mode 100644 index 0000000000..58e44f9780 --- /dev/null +++ b/src/main/target/BETAFPVF411/target.c @@ -0,0 +1,34 @@ +/* + * 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 . + */ + +#include +#include +#include "drivers/io.h" +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/bus.h" +#include "drivers/pwm_mapping.h" + + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/BETAFPVF411/target.h b/src/main/target/BETAFPVF411/target.h new file mode 100644 index 0000000000..1f57281d2f --- /dev/null +++ b/src/main/target/BETAFPVF411/target.h @@ -0,0 +1,130 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "B411" +#define USBD_PRODUCT_STRING "BETAFPVF411" + +#define LED0 PC13 + +#define BEEPER PB2 +#define BEEPER_INVERTED + +// *************** SPI ********************** +#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_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +// *************** SPI Gyro & ACC ********************** +#define USE_IMU_MPU6000 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 +#define IMU_MPU6000_ALIGN CW180_DEG + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW90_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + +// *************** Baro ***************************** + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_ALL + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +// *************** SPI OSD ***************************** +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** SPI FLASH ************************** +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PB2 +#define M25P16_SPI_BUS BUS_SPI2 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PB3 +#define SOFTSERIAL_1_RX_PIN PB3 + +#define USE_SOFTSERIAL2 +#define SOFTSERIAL_2_TX_PIN PB10 +#define SOFTSERIAL_2_RX_PIN PB10 + +#define SERIAL_PORT_COUNT 5 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC_CHANNEL_1_PIN PB0 +#define ADC_CHANNEL_2_PIN PB1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +#define VBAT_SCALE_DEFAULT 1100 + +// *************** LED2812 ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +// *************** OTHERS ************************* +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_BLACKBOX) + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 4 diff --git a/src/main/target/FOXEERF722DUAL/config.c b/src/main/target/FOXEERF722DUAL/config.c new file mode 100644 index 0000000000..38763948c3 --- /dev/null +++ b/src/main/target/FOXEERF722DUAL/config.c @@ -0,0 +1,31 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" + +#if defined(FOXEERF722V2) +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} +#endif diff --git a/src/main/target/FOXEERF722DUAL/target.c b/src/main/target/FOXEERF722DUAL/target.c index fe34e0a45d..e81731651e 100644 --- a/src/main/target/FOXEERF722DUAL/target.c +++ b/src/main/target/FOXEERF722DUAL/target.c @@ -22,6 +22,7 @@ #include "drivers/timer.h" #include "drivers/sensor.h" #include "drivers/pwm_mapping.h" +#include "drivers/pinio.h" BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); #if defined(FOXEERF722DUAL) diff --git a/src/main/target/FOXEERF722DUAL/target.h b/src/main/target/FOXEERF722DUAL/target.h index 250a88a307..1eafd86af9 100644 --- a/src/main/target/FOXEERF722DUAL/target.h +++ b/src/main/target/FOXEERF722DUAL/target.h @@ -147,3 +147,13 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) + +// *************** PINIO *************************** +#if defined(FOXEERF722V2) +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC6 // Enable GPS power +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED +#endif + + diff --git a/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt b/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt new file mode 100644 index 0000000000..6a430dc675 --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(IFLIGHT_2RAW_H743) diff --git a/src/main/target/IFLIGHT_2RAW_H743/config.c b/src/main/target/IFLIGHT_2RAW_H743/config.c new file mode 100644 index 0000000000..0f1fec5a81 --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/config.c @@ -0,0 +1,31 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/IFLIGHT_2RAW_H743/target.c b/src/main/target/IFLIGHT_2RAW_H743/target.c new file mode 100644 index 0000000000..23dd0e0c37 --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/target.c @@ -0,0 +1,49 @@ +/* + * 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 . + */ + +#include + +#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(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_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_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 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_2RAW_H743/target.h b/src/main/target/IFLIGHT_2RAW_H743/target.h new file mode 100644 index 0000000000..d8a33a12ee --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/target.h @@ -0,0 +1,167 @@ +/* + * 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 . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "2RH7" + +#define USBD_PRODUCT_STRING "IFLIGHT_2RAW_H743" + +#define LED0 PE3 +#define LED1 PE4 + +#define BEEPER PC9 +#define BEEPER_INVERTED + +// SPI Buses +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PD7 + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +// I2C +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +// Gyro +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PC15 + +// OSD +// #define USE_MAX7456 +// #define MAX7456_SPI_BUS BUS_SPI2 +// #define MAX7456_CS_PIN PB12 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_ALL + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 +#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 PB9 +#define UART4_RX_PIN PB8 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_TX_PIN PE8 +#define UART7_RX_PIN PE7 + +#define USE_UART8 +#define UART8_TX_PIN PE1 +#define UART8_RX_PIN PE0 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART6 + +// SD Card +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PA15 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// ADC +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC5 +#define ADC_CHANNEL_4_PIN PC4 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +#define VBAT_SCALE_DEFAULT 2100 + +// PINIO +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PD10 +#define PINIO2_PIN PD11 + +// *************** LEDSTRIP ************************ +// #define USE_LED_STRIP +// #define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | 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 12 +#define USE_DSHOT +#define USE_ESC_SENSOR + diff --git a/src/main/target/IFLIGHT_BLITZ_ATF435/target.h b/src/main/target/IFLIGHT_BLITZ_ATF435/target.h index 7518bbe13e..b29112d525 100644 --- a/src/main/target/IFLIGHT_BLITZ_ATF435/target.h +++ b/src/main/target/IFLIGHT_BLITZ_ATF435/target.h @@ -69,6 +69,13 @@ #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN PA4 +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + + // Other sensors #define USE_BARO diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.h b/src/main/target/IFLIGHT_BLITZ_F722/target.h index 0ced96ad5f..cea6b4422a 100644 --- a/src/main/target/IFLIGHT_BLITZ_F722/target.h +++ b/src/main/target/IFLIGHT_BLITZ_F722/target.h @@ -42,6 +42,11 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + // *************** I2C /Baro/Mag ********************* #define USE_I2C #define USE_I2C_DEVICE_1 diff --git a/src/main/target/IFLIGHT_BLITZ_F722_X1/CMakeLists.txt b/src/main/target/IFLIGHT_BLITZ_F722_X1/CMakeLists.txt new file mode 100644 index 0000000000..2d52bdb52e --- /dev/null +++ b/src/main/target/IFLIGHT_BLITZ_F722_X1/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f722xe(IFLIGHT_BLITZ_F722_X1) +target_stm32f722xe(IFLIGHT_BLITZ_F722_X1_OSD) + diff --git a/src/main/target/IFLIGHT_BLITZ_F722_X1/config.c b/src/main/target/IFLIGHT_BLITZ_F722_X1/config.c new file mode 100644 index 0000000000..b8796a0d2f --- /dev/null +++ b/src/main/target/IFLIGHT_BLITZ_F722_X1/config.c @@ -0,0 +1,29 @@ +/* + * 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 . + */ + +#include +#include "platform.h" + +#include "config/config_master.h" +#include "config/feature.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/IFLIGHT_BLITZ_F722_X1/target.c b/src/main/target/IFLIGHT_BLITZ_F722_X1/target.c new file mode 100644 index 0000000000..5a20c88ff2 --- /dev/null +++ b/src/main/target/IFLIGHT_BLITZ_F722_X1/target.c @@ -0,0 +1,37 @@ +/* + * 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 . + */ + +#include +#include "platform.h" +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 DMA1_S2_CH5 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 DMA1_S7_CH5 + + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 DMA2_S4_CH7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 DMA2_S7_CH7 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 DMA1_S0_CH2 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DMA1_S3_CH2 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // WS2812B +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_BLITZ_F722_X1/target.h b/src/main/target/IFLIGHT_BLITZ_F722_X1/target.h new file mode 100644 index 0000000000..0319625442 --- /dev/null +++ b/src/main/target/IFLIGHT_BLITZ_F722_X1/target.h @@ -0,0 +1,167 @@ +/* + * 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 . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "I7X1" +#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_F722_X1" + +#define LED0 PC15 +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ******************* +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW90_DEG_FLIP +#define BMI270_CS_PIN PA4 +#define BMI270_SPI_BUS BUS_SPI1 + +// ICM42605 +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG_FLIP +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_ALL + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_ALL + +#define TEMPERATURE_I2C_BUS BUS_I2C2 + +#define PITOT_I2C_BUS BUS_I2C2 + +#define RANGEFINDER_I2C_BUS BUS_I2C2 + +// *************** SPI2 OSD*********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_OSD + +#ifdef IFLIGHT_BLITZ_F722_X1_OSD + #define USE_MAX7456 + #define MAX7456_SPI_BUS BUS_SPI2 + #define MAX7456_CS_PIN PB12 +#endif + +// *************** SPI3 Flash *********************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define USE_FLASHFS + +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN PA15 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP +#define USB_DETECT_PIN PB2 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PC11 +#define UART3_TX_PIN PC10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL) +#define CURRENT_METER_SCALE 200 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 7 +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR + +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC0 +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED +#define PINIO2_PIN PC14 \ No newline at end of file diff --git a/src/main/target/JHEMCUF405WING/CMakeLists.txt b/src/main/target/JHEMCUF405WING/CMakeLists.txt new file mode 100644 index 0000000000..fb99881c9b --- /dev/null +++ b/src/main/target/JHEMCUF405WING/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(JHEMCUF405WING) diff --git a/src/main/target/JHEMCUF405WING/config.c b/src/main/target/JHEMCUF405WING/config.c new file mode 100644 index 0000000000..07f44ab29f --- /dev/null +++ b/src/main/target/JHEMCUF405WING/config.c @@ -0,0 +1,42 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" +#include "io/serial.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_GPS; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_MSP; + + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} diff --git a/src/main/target/JHEMCUF405WING/target.c b/src/main/target/JHEMCUF405WING/target.c new file mode 100644 index 0000000000..e8187f936b --- /dev/null +++ b/src/main/target/JHEMCUF405WING/target.c @@ -0,0 +1,47 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ +#include +#include +#include + +#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(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 1, 0), // S1 D(1,3,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 1, 0), // S2 D(1,0,2) + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S4 D(1,2,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // S6 D(2,7,7) + + DEF_TIM(TIM8, CH2N,PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 + DEF_TIM(TIM12, CH2,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // 2812LED + DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), // TX2 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/JHEMCUF405WING/target.h b/src/main/target/JHEMCUF405WING/target.h new file mode 100644 index 0000000000..fd64ff153d --- /dev/null +++ b/src/main/target/JHEMCUF405WING/target.h @@ -0,0 +1,163 @@ +/* + * 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 . + */ + +#pragma once + +#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "JH45" +#define USBD_PRODUCT_STRING "JHEMCUF405WING" + +// LEDs +#define LED0 PA14 //Blue +#define LED1 PA13 //Green + +// Beeper +#define BEEPER PC15 +#define BEEPER_INVERTED + +// SPI1 +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +// SPI2 +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +// SPI3 +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// Serial ports +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +// Optional Softserial on UART2 TX Pin PA2 +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA2 +#define SOFTSERIAL_1_RX_PIN PA2 + +#define SERIAL_PORT_COUNT 8 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_CS_PIN PA4 +#define ICM42605_SPI_BUS BUS_SPI1 + +// Baro +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_ALL + +// Mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +#define RANGEFINDER_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +// OSD +#define USE_MAX7456 +#define MAX7456_CS_PIN PB12 +#define MAX7456_SPI_BUS BUS_SPI2 + +// SD Card +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PC14 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART1 + +// ADC +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC5 +#define ADC_CHANNEL_4_PIN PC4 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_4 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_3 + +// LED2812 +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +// PINIO +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC13 // 2xCamera switcher + +// OTHERS +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_BLACKBOX | FEATURE_AIRMODE) +#define CURRENT_METER_SCALE 175 + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 11 \ No newline at end of file diff --git a/src/main/target/JHEMCUF745/CMakeLists.txt b/src/main/target/JHEMCUF745/CMakeLists.txt new file mode 100644 index 0000000000..5f5a85e7c5 --- /dev/null +++ b/src/main/target/JHEMCUF745/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f745xg(JHEMCUF745) diff --git a/src/main/target/JHEMCUF745/config.c b/src/main/target/JHEMCUF745/config.c new file mode 100644 index 0000000000..fb2fe04f96 --- /dev/null +++ b/src/main/target/JHEMCUF745/config.c @@ -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 . + */ + +#include +#include + +#include + +#include "drivers/pwm_mapping.h" + +void targetConfiguration(void) +{ + timerOverridesMutable(timer2id(TIM1))->outputMode = OUTPUT_MODE_MOTORS; + timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; +} diff --git a/src/main/target/JHEMCUF745/target.c b/src/main/target/JHEMCUF745/target.c new file mode 100644 index 0000000000..f603cbe43b --- /dev/null +++ b/src/main/target/JHEMCUF745/target.c @@ -0,0 +1,44 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/bus.h" +#include "drivers/pinio.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1, DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2, DMA1_ST2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 0), // M3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 1), // M4, DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // M5, DMA2_ST7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // M6, DMA1_ST1 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/JHEMCUF745/target.h b/src/main/target/JHEMCUF745/target.h new file mode 100644 index 0000000000..dfd45749d2 --- /dev/null +++ b/src/main/target/JHEMCUF745/target.h @@ -0,0 +1,157 @@ +/* + * This file is part of INAV. + * + * Cleanflight and Betaflight 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. + * + * Cleanflight and Betaflight 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "JHF7" +#define USBD_PRODUCT_STRING "JHEMCUF745" + +#define LED0 PA2 + +#define BEEPER PD15 +#define BEEPER_INVERTED + +#define USE_DSHOT +#define USE_DSHOT_DMAR +#define USE_ESC_SENSOR + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG +#define GYRO_INT_EXTI PE1 +#define MPU6000_CS_PIN SPI4_NSS_PIN +#define MPU6000_SPI_BUS BUS_SPI4 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_CS_PIN SPI4_NSS_PIN +#define ICM42605_SPI_BUS BUS_SPI4 +#define ICM42605_EXTI_PIN PE1 + +#define USB_IO +#define USE_VCP +#define VBUS_SENSING_ENABLED +#define VBUS_SENSING_PIN PA8 + +#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 PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_RX_PIN PE7 +#define UART7_TX_PIN PE8 + +#define SERIAL_PORT_COUNT 8 // VCP,UART1,UART2,UART3,UART4,UART5,UART6 + +#define USE_SPI +#define USE_SPI_DEVICE_1 // FLASH +#define USE_SPI_DEVICE_2 // OSD +#define USE_SPI_DEVICE_4 // ICM20689 + +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define SPI4_NSS_PIN PE4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +#define M25P16_CS_PIN SPI1_NSS_PIN +#define M25P16_SPI_BUS BUS_SPI1 +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +// External I2C bus is the same as interal one +#define MAG_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define RANGEFINDER_I2C_BUS BUS_I2C1 +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define USE_BARO_ALL +#define BARO_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define USE_MAG_ALL + +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC5 + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_VBAT | FEATURE_BLACKBOX) +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART1 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define USE_LED_STRIP +#define WS2811_PIN PD12 + +#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 diff --git a/src/main/target/JHEMCUH743HD/CMakeLists.txt b/src/main/target/JHEMCUH743HD/CMakeLists.txt new file mode 100644 index 0000000000..b0192886d6 --- /dev/null +++ b/src/main/target/JHEMCUH743HD/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(JHEMCUH743HD) \ No newline at end of file diff --git a/src/main/target/JHEMCUH743HD/config.c b/src/main/target/JHEMCUH743HD/config.c new file mode 100644 index 0000000000..4f0aea919e --- /dev/null +++ b/src/main/target/JHEMCUH743HD/config.c @@ -0,0 +1,66 @@ +/* + * 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 . + */ + +#include +#include + +#include + +#include "common/axis.h" + +#include "config/config_master.h" +#include "config/feature.h" + +#include "drivers/sensor.h" +#include "drivers/pwm_esc_detect.h" +#include "drivers/pwm_output.h" +#include "drivers/serial.h" + +#include "fc/rc_controls.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" + +#include "rx/rx.h" + +#include "io/serial.h" + +#include "sensors/battery.h" +#include "sensors/sensors.h" + +#include "telemetry/telemetry.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + + + /* + * UART1 is SerialRX + */ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; + + /* + * Enable MSP at 115200 at UART4 + */ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_115200; +} diff --git a/src/main/target/JHEMCUH743HD/target.c b/src/main/target/JHEMCUH743HD/target.c new file mode 100644 index 0000000000..adb753b9d1 --- /dev/null +++ b/src/main/target/JHEMCUH743HD/target.c @@ -0,0 +1,49 @@ +/* + * 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 . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); + + +timerHardware_t timerHardware[] = { + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM3, CH4, PB1, 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(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/JHEMCUH743HD/target.h b/src/main/target/JHEMCUH743HD/target.h new file mode 100644 index 0000000000..92300b5256 --- /dev/null +++ b/src/main/target/JHEMCUH743HD/target.h @@ -0,0 +1,205 @@ +/* + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "JHEH743HD" +#define USBD_PRODUCT_STRING "JHEMCUH743HD" + +#define USE_TARGET_CONFIG + +#define LED0 PE5 +#define LED1 PE4 + +#define BEEPER PE3 +#define BEEPER_INVERTED + +// *************** IMU generic *********************** +#define USE_DUAL_GYRO +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +// *************** SPI1 IMU0 MPU6000 **************** +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW180_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + +// *************** SPI2 OSD *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** SPI3 FLASH *********************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB2 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_AF GPIO_AF6_SPI3 +#define SPI3_MISO_AF GPIO_AF6_SPI3 +#define SPI3_MOSI_AF GPIO_AF7_SPI3 + +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN SPI3_NSS_PIN + +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN SPI3_NSS_PIN + +#define USE_BLACKBOX +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_ALL + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +#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_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_TX_PIN PE8 +#define UART7_RX_PIN PE7 + +#define USE_UART8 +#define UART8_TX_PIN PE1 +#define UART8_RX_PIN PE0 + +#define SERIAL_PORT_COUNT 9 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC3 + +#ifdef MAMBAH743_2022B + +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC0 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_3 + +#else + +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC2 +#define ADC_CHANNEL_4_PIN PC0 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +#endif + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX + +#define PINIO1_PIN PC2 +#define PINIO2_PIN PC5 + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL) +#define CURRENT_METER_SCALE 250 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR \ No newline at end of file diff --git a/src/main/target/MAMBAH743/CMakeLists.txt b/src/main/target/MAMBAH743/CMakeLists.txt index 61b073da93..801467cdb8 100644 --- a/src/main/target/MAMBAH743/CMakeLists.txt +++ b/src/main/target/MAMBAH743/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32h743xi(MAMBAH743) -target_stm32h743xi(MAMBAH743_2022B) \ No newline at end of file +target_stm32h743xi(MAMBAH743_2022B) +target_stm32h743xi(MAMBAH743_2022B_GYRO2) diff --git a/src/main/target/MAMBAH743/target.c b/src/main/target/MAMBAH743/target.c index 46231fdbd7..1e4f8fe246 100644 --- a/src/main/target/MAMBAH743/target.c +++ b/src/main/target/MAMBAH743/target.c @@ -29,7 +29,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); -#ifdef MAMBAH743_2022B +#ifdef USE_IMU_ICM42605 BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); #endif diff --git a/src/main/target/MAMBAH743/target.h b/src/main/target/MAMBAH743/target.h index 7fcea85f48..bc4a73979e 100644 --- a/src/main/target/MAMBAH743/target.h +++ b/src/main/target/MAMBAH743/target.h @@ -22,6 +22,11 @@ #define TARGET_BOARD_IDENTIFIER "M743" #define USBD_PRODUCT_STRING "MAMBAH743_2022B" +#elif defined(MAMBAH743_2022B_GYRO2) + +#define TARGET_BOARD_IDENTIFIER "M743" +#define USBD_PRODUCT_STRING "MAMBAH743_2022B_GYRO2" + #else #define TARGET_BOARD_IDENTIFIER "M743" @@ -58,13 +63,22 @@ #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN PA4 -#ifdef MAMBAH743_2022B - #define USE_SPI_DEVICE_4 #define SPI4_SCK_PIN PE12 #define SPI4_MISO_PIN PE13 #define SPI4_MOSI_PIN PE14 +#ifdef MAMBAH743_2022B + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + +#endif + +#ifdef MAMBAH743_2022B_GYRO2 + #define USE_IMU_ICM42605 #define IMU_ICM42605_ALIGN CW270_DEG #define ICM42605_SPI_BUS BUS_SPI4 @@ -175,7 +189,7 @@ #define USE_ADC #define ADC_INSTANCE ADC3 -#ifdef MAMBAH743_2022B +#if defined(MAMBAH743_2022B) || defined(MAMBAH743_2022B_GYRO2) #define ADC_CHANNEL_1_PIN PC1 #define ADC_CHANNEL_2_PIN PC3 @@ -203,7 +217,7 @@ #define USE_PINIO #define USE_PINIOBOX -#ifdef MAMBAH743_2022B +#if defined(MAMBAH743_2022B) || defined(MAMBAH743_2022B_GYRO2) #define PINIO1_PIN PC2 #define PINIO2_PIN PC5 diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index 0a686f6061..e8861eec56 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -342,11 +342,6 @@ void IOConfigGPIO(IO_t io, ioConfig_t cfg) UNUSED(cfg); } -void systemClockSetup(uint8_t cpuUnderclock) -{ - UNUSED(cpuUnderclock); -} - void timerInit(void) { // NOP } diff --git a/src/main/target/SKYSTARSF405HD/CMakeLists.txt b/src/main/target/SKYSTARSF405HD/CMakeLists.txt index cc9515d9e0..b097558284 100644 --- a/src/main/target/SKYSTARSF405HD/CMakeLists.txt +++ b/src/main/target/SKYSTARSF405HD/CMakeLists.txt @@ -1 +1,2 @@ target_stm32f405xg(SKYSTARSF405HD) +target_stm32f405xg(SKYSTARSF405HD2) \ No newline at end of file diff --git a/src/main/target/SKYSTARSF405HD/target.c b/src/main/target/SKYSTARSF405HD/target.c index 3da0f45db9..cc4ff1c5a8 100644 --- a/src/main/target/SKYSTARSF405HD/target.c +++ b/src/main/target/SKYSTARSF405HD/target.c @@ -28,6 +28,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), +#if defined(SKYSTARSF405HD2) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), +#endif DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/SKYSTARSF405HD/target.h b/src/main/target/SKYSTARSF405HD/target.h index c5ab2d49fe..9b9805084f 100644 --- a/src/main/target/SKYSTARSF405HD/target.h +++ b/src/main/target/SKYSTARSF405HD/target.h @@ -156,4 +156,8 @@ #define USE_DSHOT #define USE_ESC_SENSOR +#if defined(SKYSTARSF405HD2) +#define MAX_PWM_OUTPUT_PORTS 6 +#else #define MAX_PWM_OUTPUT_PORTS 4 +#endif diff --git a/src/main/target/SPEEDYBEEF405WING/target.h b/src/main/target/SPEEDYBEEF405WING/target.h index 1684faabce..9da5b11582 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.h +++ b/src/main/target/SPEEDYBEEF405WING/target.h @@ -148,8 +148,8 @@ #define ADC_CHANNEL_4_PIN PC4 #define VBAT_ADC_CHANNEL ADC_CHN_1 #define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 -#define RSSI_ADC_CHANNEL ADC_CHN_4 -#define AIRSPEED_ADC_CHANNEL ADC_CHN_3 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 // *************** LED2812 ************************ #define USE_LED_STRIP @@ -172,4 +172,4 @@ #define USE_PINIO #define USE_PINIOBOX -#define PINIO1_PIN PC13 \ No newline at end of file +#define PINIO1_PIN PC13 diff --git a/src/main/target/TAKERF722SE/CMakeLists.txt b/src/main/target/TAKERF722SE/CMakeLists.txt new file mode 100644 index 0000000000..c4716f616e --- /dev/null +++ b/src/main/target/TAKERF722SE/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(TAKERF722SE) \ No newline at end of file diff --git a/src/main/target/TAKERF722SE/target.c b/src/main/target/TAKERF722SE/target.c new file mode 100644 index 0000000000..d67062a9fb --- /dev/null +++ b/src/main/target/TAKERF722SE/target.c @@ -0,0 +1,48 @@ +/* +* This file is part of INAV Project. +* +* 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 . +*/ + +#include + +#include "platform.h" +#include "drivers/io.h" + +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + + + + + +timerHardware_t timerHardware[] = { + + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 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(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH2, PB7, 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_LED, 0, 0), +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); + + diff --git a/src/main/target/TAKERF722SE/target.h b/src/main/target/TAKERF722SE/target.h new file mode 100644 index 0000000000..817dc535f0 --- /dev/null +++ b/src/main/target/TAKERF722SE/target.h @@ -0,0 +1,186 @@ +/* + * This file is part of INAV Project. + * + * 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. + * + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "GEPR" + +#define USBD_PRODUCT_STRING "TAKERF722SE" + +#define LED0 PC14 + + +// *************** BEEPER ************************ + +#define BEEPER PC13 +#define BEEPER_INVERTED + + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + + +// *************** SPI Bus ********************** + +#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_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB2 +#define SPI3_SCK_AF GPIO_AF6_SPI3 +#define SPI3_MISO_AF GPIO_AF6_SPI3 +#define SPI3_MOSI_AF GPIO_AF7_SPI3 + + +// *************** Gyro & ACC ********************** + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 + + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_CS_PIN PA4 +#define ICM42605_SPI_BUS BUS_SPI1 + +// *************** I2C/Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + + +//*************************************************** +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_BARO_MS5611 + +#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 TEMPERATURE_I2C_BUS BUS_I2C1 + +#define PITOT_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 +#define BNO055_I2C_BUS BUS_I2C1 + +// *************** FLASH ************************** + +#define USE_FLASHFS + +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PA15 +#define M25P16_SPI_BUS BUS_SPI3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** OSD ***************************** + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** ADC ***************************** + +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC3 +#define ADC_CHANNEL_2_PIN PC0 +#define ADC_CHANNEL_3_PIN PC2 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define RSSI_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 + + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) + + + + +//************************************************** + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + + +#define MAX_PWM_OUTPUT_PORTS 8 + +#define USE_DSHOT +#define USE_ESC_SENSOR diff --git a/src/main/target/TMOTORF7V2/target.h b/src/main/target/TMOTORF7V2/target.h index 2691812f2f..f5def98a40 100644 --- a/src/main/target/TMOTORF7V2/target.h +++ b/src/main/target/TMOTORF7V2/target.h @@ -67,6 +67,11 @@ #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW0_DEG +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_CS_PIN PA4 +#define ICM42605_SPI_BUS BUS_SPI1 + // OSD -- SPI2 #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 diff --git a/src/main/target/TUNERCF405/CMakeLists.txt b/src/main/target/TUNERCF405/CMakeLists.txt new file mode 100644 index 0000000000..ba4e9fd3cd --- /dev/null +++ b/src/main/target/TUNERCF405/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(TUNERCF405) diff --git a/src/main/target/TUNERCF405/target.c b/src/main/target/TUNERCF405/target.c new file mode 100644 index 0000000000..bc0b4e86f6 --- /dev/null +++ b/src/main/target/TUNERCF405/target.c @@ -0,0 +1,39 @@ +/* + * This file is part of INAV Project. + * + * 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 . + */ + +#include + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR, 0, 0), //D2s6 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), //D2s6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), //D1s7 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), //D1s5 + + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), //D2s7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), //D2s2 / D2s4 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), //D2s2 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), //D2s2 + + DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/TUNERCF405/target.h b/src/main/target/TUNERCF405/target.h new file mode 100644 index 0000000000..f193377c6e --- /dev/null +++ b/src/main/target/TUNERCF405/target.h @@ -0,0 +1,137 @@ +/* + * This file is part of INAV Project. + * + * 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 . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "TURC" + +#define USBD_PRODUCT_STRING "TUNERCF405" + +// Indicators +#define LED0 PB9 + +#define BEEPER PB2 +#define BEEPER_INVERTED + +// WS2812 +#define USE_LED_STRIP +#define WS2811_PIN PB1 + +// Gyro & ACC +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN SPI1_NSS_PIN +#define BMI270_SPI_BUS BUS_SPI1 + +// OSD +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +// Onboard Flash +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 //W25Q32JVXGIQ TR +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PB6 + +// IIC +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C1_SCL PB10 +#define I2C1_SDA PB11 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_ALL + +// Serial ports +#define USE_VCP +#define VBUS_SENSING_PIN PB7 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PC11 +#define UART3_TX_PIN PC10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF + +// ADC +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_SCALE 453 + +// SET +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT ) +#define USE_DSHOT +#define USE_DSHOT_DMAR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define MAX_PWM_OUTPUT_PORTS 8 +#define TARGET_MOTOR_COUNT 8 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff diff --git a/src/main/target/common.h b/src/main/target/common.h index 8bbaadef71..d146ebb979 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -83,6 +83,7 @@ #define USE_RANGEFINDER_VL53L1X #define USE_RANGEFINDER_US42 #define USE_RANGEFINDER_TOF10120_I2C +#define USE_RANGEFINDER_TERARANGER_EVO_I2C // Allow default optic flow boards #define USE_OPFLOW @@ -111,7 +112,6 @@ #define USE_FRSKYOSD #define USE_DJI_HD_OSD #define USE_MSP_OSD -#define USE_SMARTPORT_MASTER #define NAV_NON_VOLATILE_WAYPOINT_CLI @@ -199,7 +199,15 @@ #define USE_HOTT_TEXTMODE #define USE_24CHANNELS #define MAX_MIXER_PROFILE_COUNT 2 +#define USE_SMARTPORT_MASTER #elif !defined(STM32F7) #define MAX_MIXER_PROFILE_COUNT 1 #endif + +#if (MCU_FLASH_SIZE <= 512) + #define SKIP_CLI_COMMAND_HELP + #undef USE_SERIALRX_SPEKTRUM + #undef USE_TELEMETRY_SRXL +#endif + #define USE_EZ_TUNE diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index 76ffbf1942..0169e8099b 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -91,7 +91,10 @@ #if !defined(BMP085_I2C_BUS) #define BMP085_I2C_BUS BARO_I2C_BUS #endif - BUSDEV_REGISTER_I2C(busdev_bmp085, DEVHW_BMP085, BMP085_I2C_BUS, 0x77, NONE, DEVFLAGS_NONE, 0); + #if !defined(BMP085_I2C_ADDR) + #define BMP085_I2C_ADDR (0x77) + #endif + BUSDEV_REGISTER_I2C(busdev_bmp085, DEVHW_BMP085, BMP085_I2C_BUS, BMP085_I2C_ADDR, NONE, DEVFLAGS_NONE, 0); #endif #if defined(USE_BARO_BMP280) @@ -115,7 +118,10 @@ #if !defined(BMP388_I2C_BUS) #define BMP388_I2C_BUS BARO_I2C_BUS #endif - BUSDEV_REGISTER_I2C(busdev_bmp388, DEVHW_BMP388, BMP388_I2C_BUS, 0x76, NONE, DEVFLAGS_NONE, 0); + #if !defined(BMP388_I2C_ADDR) + #define BMP388_I2C_ADDR (0x76) + #endif + BUSDEV_REGISTER_I2C(busdev_bmp388, DEVHW_BMP388, BMP388_I2C_BUS, BMP388_I2C_ADDR, NONE, DEVFLAGS_NONE, 0); #endif #endif @@ -126,7 +132,10 @@ #if !defined(SPL06_I2C_BUS) #define SPL06_I2C_BUS BARO_I2C_BUS #endif - BUSDEV_REGISTER_I2C(busdev_spl06, DEVHW_SPL06, SPL06_I2C_BUS, 0x76, NONE, DEVFLAGS_NONE, 0); + #if !defined(SPL06_I2C_ADDR) + #define SPL06_I2C_ADDR (0x76) + #endif + BUSDEV_REGISTER_I2C(busdev_spl06, DEVHW_SPL06, SPL06_I2C_BUS, SPL06_I2C_ADDR, NONE, DEVFLAGS_NONE, 0); #endif #endif @@ -140,7 +149,10 @@ #if !defined(MS5607_I2C_BUS) #define MS5607_I2C_BUS BARO_I2C_BUS #endif - BUSDEV_REGISTER_I2C(busdev_ms5607, DEVHW_MS5607, MS5607_I2C_BUS, 0x77, NONE, DEVFLAGS_USE_RAW_REGISTERS, 0); + #if !defined(MS5607_I2C_ADDR) + #define MS5607_I2C_ADDR (0x77) + #endif + BUSDEV_REGISTER_I2C(busdev_ms5607, DEVHW_MS5607, MS5607_I2C_BUS, MS5607_I2C_ADDR, NONE, DEVFLAGS_USE_RAW_REGISTERS, 0); #endif #if defined(USE_BARO_MS5611) @@ -150,7 +162,10 @@ #if !defined(MS5611_I2C_BUS) #define MS5611_I2C_BUS BARO_I2C_BUS #endif - BUSDEV_REGISTER_I2C(busdev_ms5611, DEVHW_MS5611, MS5611_I2C_BUS, 0x77, NONE, DEVFLAGS_USE_RAW_REGISTERS, 0); + #if !defined(MS5611_I2C_ADDR) + #define MS5611_I2C_ADDR (0x77) + #endif + BUSDEV_REGISTER_I2C(busdev_ms5611, DEVHW_MS5611, MS5611_I2C_BUS, MS5611_I2C_ADDR, NONE, DEVFLAGS_USE_RAW_REGISTERS, 0); #endif #endif @@ -161,18 +176,24 @@ #if !defined(DPS310_I2C_BUS) #define DPS310_I2C_BUS BARO_I2C_BUS #endif - BUSDEV_REGISTER_I2C(busdev_dps310, DEVHW_DPS310, DPS310_I2C_BUS, 0x76, NONE, DEVFLAGS_NONE, 0); + #if !defined(DPS310_I2C_ADDR) + #define DPS310_I2C_ADDR (0x76) + #endif + BUSDEV_REGISTER_I2C(busdev_dps310, DEVHW_DPS310, DPS310_I2C_BUS, DPS310_I2C_ADDR, NONE, DEVFLAGS_NONE, 0); #endif #endif #if defined(USE_BARO_B2SMPB) #if defined(B2SMPB_SPI_BUS) - BUSDEV_REGISTER_SPI(busdev_b2smpb, DEVHW_B2SMPB, B2SMPB_SPI_BUS, B2SMPB_CS_PIN, NONE, DEVFLAGS_NONE, 0); + BUSDEV_REGISTER_SPI(busdev_b2smpb, DEVHW_B2SMPB, B2SMPB_SPI_BUS, B2SMPB_CS_PIN, NONE, DEVFLAGS_NONE, 0); #elif defined(B2SMPB_I2C_BUS) || defined(BARO_I2C_BUS) #if !defined(B2SMPB_I2C_BUS) #define B2SMPB_I2C_BUS BARO_I2C_BUS #endif - BUSDEV_REGISTER_I2C(busdev_b2smpb, DEVHW_B2SMPB, B2SMPB_I2C_BUS, 0x70, NONE, DEVFLAGS_NONE, 0); + #if !defined(B2SMPB_I2C_ADDR) + #define B2SMPB_I2C_ADDR (0x70) + #endif + BUSDEV_REGISTER_I2C(busdev_b2smpb, DEVHW_B2SMPB, B2SMPB_I2C_BUS, B2SMPB_I2C_ADDR, NONE, DEVFLAGS_NONE, 0); #endif #endif @@ -341,6 +362,15 @@ #endif #endif +#if defined(USE_RANGEFINDER_TERARANGER_EVO_I2C) + #if !defined(TERARANGER_EVO_I2C_BUS) && defined(RANGEFINDER_I2C_BUS) + #define TERARANGER_EVO_I2C_BUS RANGEFINDER_I2C_BUS + #endif + #if defined(TERARANGER_EVO_I2C_BUS) + BUSDEV_REGISTER_I2C(busdev_teraranger_evo, DEVHW_TERARANGER_EVO_I2C, TERARANGER_EVO_I2C_BUS, 0x31, NONE, DEVFLAGS_NONE, 0); + #endif +#endif + #if defined(USE_RANGEFINDER_TOF10120_I2C) && (defined(TOF10120_I2C_BUS) || defined(RANGEFINDER_I2C_BUS)) #if !defined(TOF10120_I2C_BUS) #define TOF10120_I2C_BUS RANGEFINDER_I2C_BUS diff --git a/src/main/telemetry/crsf.c b/src/main/telemetry/crsf.c index af9f278659..5ed25de73b 100755 --- a/src/main/telemetry/crsf.c +++ b/src/main/telemetry/crsf.c @@ -57,7 +57,7 @@ #include "sensors/battery.h" #include "sensors/sensors.h" -#include "sensors/barometer.h" + #include "telemetry/crsf.h" #include "telemetry/telemetry.h" #include "telemetry/msp_shared.h" @@ -258,22 +258,6 @@ static void crsfFrameBatterySensor(sbuf_t *dst) crsfSerialize8(dst, batteryRemainingPercentage); } -/* -0x09 Baro+Vario sensor -Payload: -uint16 Altitude -int16 Vertical speed ( cm/s ) -*/ -static void crsfFrameBaroVarioSensor(sbuf_t *dst) -{ - // use sbufWrite since CRC does not include frame length - sbufWriteU8(dst, CRSF_FRAME_BAROVARIO_SENSOR_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC); - crsfSerialize8(dst, CRSF_FRAMETYPE_BAROVARIO_SENSOR); - int32_t altitude = baroGetLatestAltitude() / 10; // Altitude in decimeters - crsfSerialize16(dst, altitude + 10000 < 0x8000 ? altitude + 10000 : 0x8000 + altitude / 10); - crsfSerialize16(dst, lrintf(getEstimatedActualVelocity(Z))); -} - typedef enum { CRSF_ACTIVE_ANTENNA1 = 0, CRSF_ACTIVE_ANTENNA2 = 1 @@ -371,6 +355,10 @@ static void crsfFrameFlightMode(sbuf_t *dst) } else if (FLIGHT_MODE(ANGLEHOLD_MODE)) { flightMode = "ANGH"; } +#ifdef USE_FW_AUTOLAND + } else if (FLIGHT_MODE(NAV_FW_AUTOLAND)) { + flightMode = "LAND"; +#endif #ifdef USE_GPS } else if (feature(FEATURE_GPS) && navConfig()->general.flags.extra_arming_safety && (!STATE(GPS_FIX) || !STATE(GPS_FIX_HOME))) { flightMode = "WAIT"; // Waiting for GPS lock @@ -427,7 +415,6 @@ typedef enum { CRSF_FRAME_FLIGHT_MODE_INDEX, CRSF_FRAME_GPS_INDEX, CRSF_FRAME_VARIO_SENSOR_INDEX, - CRSF_FRAME_BAROVARIO_SENSOR_INDEX, CRSF_SCHEDULE_COUNT_MAX } crsfFrameTypeIndex_e; @@ -487,18 +474,13 @@ static void processCrsf(void) crsfFrameGps(dst); crsfFinalize(dst); } +#endif +#if defined(USE_BARO) || defined(USE_GPS) if (currentSchedule & BV(CRSF_FRAME_VARIO_SENSOR_INDEX)) { crsfInitializeFrame(dst); crsfFrameVarioSensor(dst); crsfFinalize(dst); } -#endif -#if defined(USE_BARO) - if (currentSchedule & BV(CRSF_FRAME_BAROVARIO_SENSOR_INDEX)) { - crsfInitializeFrame(dst); - crsfFrameBaroVarioSensor(dst); - crsfFinalize(dst); - } #endif crsfScheduleIndex = (crsfScheduleIndex + 1) % crsfScheduleCount; } @@ -523,23 +505,14 @@ void initCrsfTelemetry(void) crsfSchedule[index++] = BV(CRSF_FRAME_ATTITUDE_INDEX); crsfSchedule[index++] = BV(CRSF_FRAME_BATTERY_SENSOR_INDEX); crsfSchedule[index++] = BV(CRSF_FRAME_FLIGHT_MODE_INDEX); -#if defined(USE_GPS) +#ifdef USE_GPS if (feature(FEATURE_GPS)) { crsfSchedule[index++] = BV(CRSF_FRAME_GPS_INDEX); - #if !defined(USE_BARO) - crsfSchedule[index++] = BV(CRSF_FRAME_VARIO_SENSOR_INDEX); - #endif } #endif -#if defined(USE_BARO) - if (sensors(SENSOR_BARO)) { - crsfSchedule[index++] = BV(CRSF_FRAME_BAROVARIO_SENSOR_INDEX); - } else { - #if defined(USE_GPS) - if (feature(FEATURE_GPS)) { - crsfSchedule[index++] = BV(CRSF_FRAME_VARIO_SENSOR_INDEX); - } - #endif +#if defined(USE_BARO) || defined(USE_GPS) + if (sensors(SENSOR_BARO) || (STATE(FIXED_WING_LEGACY) && feature(FEATURE_GPS))) { + crsfSchedule[index++] = BV(CRSF_FRAME_VARIO_SENSOR_INDEX); } #endif crsfScheduleCount = (uint8_t)index; @@ -618,11 +591,7 @@ int getCrsfFrame(uint8_t *frame, crsfFrameType_e frameType) case CRSF_FRAMETYPE_VARIO_SENSOR: crsfFrameVarioSensor(sbuf); break; - case CRSF_FRAMETYPE_BAROVARIO_SENSOR: - crsfFrameBaroVarioSensor(sbuf); - break; } - const int frameSize = crsfFinalizeBuf(sbuf, frame); return frameSize; } diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index 84dccddb86..45ab37deec 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -71,6 +71,7 @@ #include "sensors/gyro.h" #include "sensors/sensors.h" #include "sensors/pitotmeter.h" +#include "sensors/diagnostics.h" #include "telemetry/ltm.h" #include "telemetry/telemetry.h" @@ -182,6 +183,10 @@ void ltm_sframe(sbuf_t *dst) lt_flightmode = LTM_MODE_ANGLE; else if (FLIGHT_MODE(HORIZON_MODE)) lt_flightmode = LTM_MODE_HORIZON; +#ifdef USE_FW_AUTOLAND + else if (FLIGHT_MODE(NAV_FW_AUTOLAND)) + lt_flightmode = LTM_MODE_LAND; +#endif else lt_flightmode = LTM_MODE_RATE; // Rate mode diff --git a/src/main/vcp_hal/usbd_cdc_interface.c b/src/main/vcp_hal/usbd_cdc_interface.c index 8fd3abc655..2489d74fb2 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.c +++ b/src/main/vcp_hal/usbd_cdc_interface.c @@ -54,6 +54,8 @@ #include "usbd_cdc_interface.h" #include "stdbool.h" #include "drivers/time.h" +#include "drivers/nvic.h" +#include "build/atomic.h" /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ @@ -366,14 +368,13 @@ uint32_t CDC_Receive_BytesAvailable(void) uint32_t CDC_Send_FreeBytes(void) { - /* - return the bytes free in the circular buffer + uint32_t freeBytes; - functionally equivalent to: - (APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in) - but without the impact of the condition check. - */ - return ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1; + ATOMIC_BLOCK(NVIC_PRIO_VCP) { + freeBytes = ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1; + } + + return freeBytes; } /** diff --git a/src/test/unit/flight_failsafe_unittest.cc.txt b/src/test/unit/flight_failsafe_unittest.cc.txt index eb4aacef72..895cbd15d7 100644 --- a/src/test/unit/flight_failsafe_unittest.cc.txt +++ b/src/test/unit/flight_failsafe_unittest.cc.txt @@ -297,62 +297,6 @@ TEST(FlightFailsafeTest, TestFailsafeDetectsRxLossAndJustDisarms) EXPECT_FALSE(ARMING_FLAG(PREVENT_ARMING)); } -/****************************************************************************************/ -TEST(FlightFailsafeTest, TestFailsafeDetectsKillswitchEvent) -{ - // given - ENABLE_ARMING_FLAG(ARMED); - resetCallCounters(); - failsafeStartMonitoring(); - - // and - throttleStatus = THROTTLE_HIGH; // throttle HIGH to go for a failsafe landing procedure - failsafeConfig.failsafe_kill_switch = 1; // configure AUX switch as kill switch - ACTIVATE_RC_MODE(BOXFAILSAFE); // and activate it - sysTickUptime = 0; // restart time from 0 - failsafeOnValidDataReceived(); // set last valid sample at current time - sysTickUptime = PERIOD_RXDATA_FAILURE + 1; // adjust time to point just past the failure time to - failsafeOnValidDataFailed(); // cause a lost link - - // when - failsafeUpdateState(); // kill switch handling should come first - - // then - EXPECT_EQ(true, failsafeIsActive()); - EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING)); - EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM)); - EXPECT_EQ(FAILSAFE_RX_LOSS_MONITORING, failsafePhase()); - - // given - failsafeOnValidDataFailed(); // set last invalid sample at current time - sysTickUptime += PERIOD_RXDATA_RECOVERY + 1; // adjust time to point just past the recovery time to - failsafeOnValidDataReceived(); // cause a recovered link - - rcModeActivationMask = DE_ACTIVATE_ALL_BOXES; // BOXFAILSAFE must be off (kill switch) - - // when - failsafeUpdateState(); - - // then - EXPECT_EQ(true, failsafeIsActive()); - EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING)); - EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM)); - EXPECT_EQ(FAILSAFE_RX_LOSS_MONITORING, failsafePhase()); - - // given - sysTickUptime += PERIOD_OF_1_SECONDS + 1; // adjust time to point just past the required additional recovery time - failsafeOnValidDataReceived(); - - // when - failsafeUpdateState(); - - // then - EXPECT_EQ(false, failsafeIsActive()); - EXPECT_EQ(FAILSAFE_IDLE, failsafePhase()); - EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM)); // disarm not called repeatedly. - EXPECT_FALSE(ARMING_FLAG(PREVENT_ARMING)); -} - /****************************************************************************************/ // // Additional non-stepwise tests diff --git a/src/utils/compiler.rb b/src/utils/compiler.rb index 29b8f10418..fe2868acd1 100644 --- a/src/utils/compiler.rb +++ b/src/utils/compiler.rb @@ -47,7 +47,7 @@ class Compiler dirs.each do |dir| p = File.join(dir, bin) ['', '.exe'].each do |suffix| - f = p + suffix + f = File.expand_path(p + suffix) if File.executable?(f) if @verbose puts "Found #{bin} at #{f}" diff --git a/src/utils/declination.py b/src/utils/declination.py old mode 100644 new mode 100755 index 8608ffda95..44f5c9f21d --- a/src/utils/declination.py +++ b/src/utils/declination.py @@ -14,7 +14,7 @@ import datetime import pathlib import sys -import igrf12 +import igrf import numpy as np SAMPLING_RES = 10 @@ -73,7 +73,7 @@ def declination_tables(query): for i, lat in enumerate(lats): for j, lon in enumerate(lons): - mag = igrf12.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1) + mag = igrf.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1) intensity[i][j] = mag.total / 1e5 inclination[i][j] = mag.incl declination[i][j] = mag.decl