diff --git a/.gitignore b/.gitignore index b2c3b9ff546..ab82cc0fcd4 100644 --- a/.gitignore +++ b/.gitignore @@ -22,6 +22,7 @@ cov-int* /downloads/ /debug/ /release/ +/*_SITL/ # script-generated files docs/Manual.pdf @@ -35,3 +36,4 @@ make/local.mk launch.json .vscode/tasks.json .vscode/c_cpp_properties.json +/cmake-build-debug/ diff --git a/.vscode/settings.json b/.vscode/settings.json index 2cece3ee127..d1eb2357c02 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -2,11 +2,17 @@ "files.associations": { "chrono": "c", "cmath": "c", - "ranges": "c" + "ranges": "c", + "navigation.h": "c", + "rth_trackback.h": "c" + "platform.h": "c", + "timer.h": "c", + "bus.h": "c" }, "editor.tabSize": 4, "editor.insertSpaces": true, "editor.detectIndentation": false, "editor.expandTabs": true, "C_Cpp.clang_format_fallbackStyle": "{ BasedOnStyle: Google, IndentWidth: 4, BreakBeforeBraces: Mozilla }" + } diff --git a/.vscode/tasks.json b/.vscode/tasks.json index 3ca90b787d3..7be2cd3d176 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/CMakeLists.txt b/CMakeLists.txt index af42e31d7c1..db8ec36897b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -51,7 +51,7 @@ else() endif() endif() -project(INAV VERSION 7.0.0) +project(INAV VERSION 8.0.0) enable_language(ASM) diff --git a/Dockerfile b/Dockerfile index 71077c8ed96..4d2c144f57d 100644 --- a/Dockerfile +++ b/Dockerfile @@ -4,15 +4,18 @@ ARG USER_ID ARG GROUP_ID ENV DEBIAN_FRONTEND noninteractive -RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip gcc-arm-none-eabi ninja-build gdb +RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip gcc-arm-none-eabi ninja-build + +RUN if [ "$GDB" = "yes" ]; then apt-get install -y gdb; fi RUN pip install pyyaml # if either of these are already set the same as the user's machine, leave them be and ignore the error -RUN if [ -n "$USER_ID" ]; then RUN addgroup --gid $GROUP_ID inav; exit 0; fi -RUN if [ -n "$USER_ID" ]; then RUN adduser --disabled-password --gecos '' --uid $USER_ID --gid $GROUP_ID inav; exit 0; fi +RUN addgroup --gid $GROUP_ID inav; exit 0; +RUN adduser --disabled-password --gecos '' --uid $USER_ID --gid $GROUP_ID inav; exit 0; + +USER inav -RUN if [ -n "$USER_ID" ]; then USER inav; fi RUN git config --global --add safe.directory /src VOLUME /src diff --git a/build_docs.sh b/build_docs.sh index 70c2cc45cfb..9711d8775cf 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 497828088a1..f31a26c3e3a 100644 --- a/cmake/arm-none-eabi-checks.cmake +++ b/cmake/arm-none-eabi-checks.cmake @@ -2,21 +2,18 @@ include(gcc) set(arm_none_eabi_triplet "arm-none-eabi") # Keep version in sync with the distribution files below -set(arm_none_eabi_gcc_version "10.3.1") -set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/10.3-2021.10/gcc-arm-none-eabi-10.3-2021.10") +set(arm_none_eabi_gcc_version "13.2.1") +# This is the output directory "pretty" name and URI name prefix +set(base_dir_name "arm-gnu-toolchain-13.2.rel1") +# This is the name inside the archive, which is no longer evincible from URI, alas +set(archive_base_dir_name "arm-gnu-toolchain-13.2.Rel1") +set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu/13.2.rel1/binrel/${base_dir_name}") # suffix and checksum -set(arm_none_eabi_win32 "win32.zip" 2bc8f0c4c4659f8259c8176223eeafc1) -set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 2383e4eb4ea23f248d33adc70dc3227e) -set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 3fe3d8bb693bd0a6e4615b6569443d0d) -set(arm_none_eabi_gcc_macos "mac.tar.bz2" 7f2a7b7b23797302a9d6182c6e482449) - -function(arm_none_eabi_gcc_distname var) - string(REPLACE "/" ";" url_parts ${arm_none_eabi_base_url}) - list(LENGTH url_parts n) - math(EXPR last "${n} - 1") - list(GET url_parts ${last} basename) - set(${var} ${basename} PARENT_SCOPE) -endfunction() +set(arm_none_eabi_win32 "mingw-w64-i686-arm-none-eabi.zip" 7fd677088038cdf82f33f149e2e943ee) +set(arm_none_eabi_linux_amd64 "x86_64-arm-none-eabi.tar.xz" 791754852f8c18ea04da7139f153a5b7) +set(arm_none_eabi_linux_aarch64 "aarch64-arm-none-eabi.tar.xz" 5a08122e6d4caf97c6ccd1d29e62599c) +set(arm_none_eabi_darwin_amd64 "darwin-x86_64-arm-none-eabi.tar.xz" 41d49840b0fc676d2ae35aab21a58693) +set(arm_none_eabi_darwin_aarch64 "darwin-arm64-arm-none-eabi.tar.xz" 2c43e9d72206c1f81227b0a685df5ea6) function(host_uname_machine var) # We need to call uname -m manually, since at the point @@ -47,7 +44,14 @@ function(arm_none_eabi_gcc_install) message("-- no precompiled ${arm_none_eabi_triplet} toolchain for machine ${machine}") endif() elseif(CMAKE_HOST_SYSTEM_NAME STREQUAL "Darwin") - set(dist ${arm_none_eabi_gcc_macos}) + host_uname_machine(machine) + if(machine STREQUAL "x86_64" OR machine STREQUAL "amd64") + set(dist ${arm_none_eabi_darwin_amd64}) + 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}") + endif() endif() if(dist STREQUAL "") @@ -83,11 +87,27 @@ function(arm_none_eabi_gcc_install) if(NOT status EQUAL 0) message(FATAL_ERROR "error extracting ${basename}: ${status}") endif() + string(REPLACE "." ";" url_parts ${dist_suffix}) + list(GET url_parts 0 host_dir_name) + set(dir_name "${archive_base_dir_name}-${host_dir_name}") + file(REMOVE_RECURSE "${TOOLS_DIR}/${base_dir_name}") + file(RENAME "${TOOLS_DIR}/${dir_name}" "${TOOLS_DIR}/${base_dir_name}") + # This is **somewhat ugly** + # the newlib distributed by ARM generates suprious warnings from re-entrant POSIX functions + # that INAV doesn't use. These "harmless" warnings can be surpressed by removing the + # errant section from the only libnosys used by INAV ... + # So look the other way ... while this is "fixed" + execute_process(COMMAND arm-none-eabi-objcopy -w -R .gnu.warning.* "${TOOLS_DIR}/${base_dir_name}/arm-none-eabi/lib/thumb/v7e-m+fp/hard/libnosys.a" + RESULT_VARIABLE status + WORKING_DIRECTORY ${TOOLS_DIR} + ) + if(NOT status EQUAL 0) + message(FATAL_ERROR "error fixing libnosys.a: ${status}") + endif() endfunction() function(arm_none_eabi_gcc_add_path) - arm_none_eabi_gcc_distname(dist_name) - set(gcc_path "${TOOLS_DIR}/${dist_name}/bin") + set(gcc_path "${TOOLS_DIR}/${base_dir_name}/bin") if(CMAKE_HOST_SYSTEM MATCHES ".*Windows.*") set(sep "\\;") else() @@ -110,7 +130,7 @@ function(arm_none_eabi_gcc_check) message("-- found ${prog} ${version} at ${prog_path}") if(COMPILER_VERSION_CHECK AND NOT arm_none_eabi_gcc_version STREQUAL version) message("-- expecting ${prog} version ${arm_none_eabi_gcc_version}, but got version ${version} instead") - arm_none_eabi_gcc_install() + arm_none_eabi_gcc_install() return() endif() endfunction() diff --git a/cmake/at32.cmake b/cmake/at32.cmake index aa902593e94..54e178deb7b 100644 --- a/cmake/at32.cmake +++ b/cmake/at32.cmake @@ -9,7 +9,7 @@ option(SEMIHOSTING "Enable semihosting") message("-- DEBUG_HARDFAULTS: ${DEBUG_HARDFAULTS}, SEMIHOSTING: ${SEMIHOSTING}") set(CMSIS_DIR "${MAIN_LIB_DIR}/lib/main/AT32F43x/Drivers/CMSIS") -set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/cm4/core_support") +set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/cm4/core_support") # DSP use common set(CMSIS_DSP_DIR "${MAIN_LIB_DIR}/main/CMSIS/DSP") set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include") @@ -50,8 +50,8 @@ main_sources(AT32_ASYNCFATFS_SRC ) main_sources(AT32_MSC_SRC - msc/at32_msc_diskio.c - msc/emfat.c + msc/at32_msc_diskio.c + msc/emfat.c msc/emfat_file.c ) @@ -92,6 +92,7 @@ set(AT32_LINK_OPTIONS -Wl,--cref -Wl,--no-wchar-size-warning -Wl,--print-memory-usage + -Wl,--no-warn-rwx-segments ) # Get target features macro(get_at32_target_features output_var dir target_name) @@ -264,7 +265,7 @@ function(add_at32_executable) endif() endfunction() -# Main function of AT32 +# Main function of AT32 function(target_at32) if(NOT arm-none-eabi STREQUAL TOOLCHAIN) return() diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake index 78697f98a9d..ee43aa9a93a 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/ADSB.md b/docs/ADSB.md new file mode 100644 index 00000000000..345af30a97e --- /dev/null +++ b/docs/ADSB.md @@ -0,0 +1,17 @@ +# ADS-B + +[Automatic Dependent Surveillance Broadcast](https://en.wikipedia.org/wiki/Automatic_Dependent_Surveillance%E2%80%93Broadcast) +is an air traffic surveillance technology that enables aircraft to be accurately tracked by air traffic controllers and other pilots without the need for conventional radar. + +## Current state + +OSD can be configured to shows the closest aircraft. + +## Hardware + +All ADSB receivers which can send Mavlink [ADSB_VEHICLE](https://mavlink.io/en/messages/common.html#ADSB_VEHICLE) message are supported + +* [PINGRX](https://uavionix.com/product/pingrx-pro/) (not tested) +* [TT-SC1](https://www.aerobits.pl/product/aero/) (tested) + + diff --git a/docs/API/MSP_extensions.md b/docs/API/MSP_extensions.md index 357c6239e87..2ac8dd989f9 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/Boards.md b/docs/Boards.md index 9440058758c..f61f3a2fd4a 100644 --- a/docs/Boards.md +++ b/docs/Boards.md @@ -12,6 +12,9 @@ These boards are well tested with INAV and are known to be of good quality and r | [Holybro Kakute H7](https://inavflight.com/shop/s/bg/1914066) | H7 | KAKUTEH7 | All | All | All | All | All | SERIAL, SD | It's possible to find more supported and tested boards [here](https://github.com/iNavFlight/inav/wiki/Welcome-to-INAV,-useful-links-and-products) + +There is also a [full list of all supported boards](https://github.com/iNavFlight/inav/wiki/Boards,-Targets-and-PWM-allocations). + ### Boards documentation See the [docs/boards](https://github.com/iNavFlight/inav/tree/master/docs/boards) folder for additional information regards to many targets in INAV, to example help in finding pinout and features. _Feel free to help improve the docs._ diff --git a/docs/ESC and servo outputs.md b/docs/ESC and servo outputs.md index a9821603c06..eba8187ca56 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 @@ -28,23 +28,8 @@ While motors are usually ordered sequentially, here is no standard output layout ## Modifying output mapping -### Modifying all outputs at the same time - -Since INAV 5, it has been possible to force *ALL* outputs to be `MOTORS` or `SERVOS`. - -Traditional ESCs usually can be controlled via a servo output, but would require calibration. - -This can be done with the `output_mode` CLI setting. Allowed values: - -* `AUTO` assigns outputs according to the default mapping -* `SERVOS` assigns all outputs to servos -* `MOTORS` assigns all outputs to motors - -### Modifying only some outputs - INAV 7 introduced extra functionality that let you force only some outputs to be either *MOTORS* or *SERVOS*, with some restrictions dictated by the hardware. -The mains restrictions is that outputs need to be associated with timers, which are usually shared between multiple outputs. Two outputs on the same timer need to have the same function. +The main restrictions is that outputs are associated with timers, which can be shared between multiple outputs and two outputs on the same timer need to have the same function. The easiest way to modify outputs, is to use the Mixer tab in the Configurator, as it will clearly show you which timer is used by all outputs, but you can also use `timer_output_mode` on the cli. -This can be used in conjunction to the previous method, in that cass all outputs will follow `output_mode` and `timer_output_mode` overrides are applied after that. diff --git a/docs/Fixed Wing Landing.md b/docs/Fixed Wing Landing.md new file mode 100644 index 00000000000..c89a5ee2075 --- /dev/null +++ b/docs/Fixed Wing Landing.md @@ -0,0 +1,119 @@ +# Fixed Wing Landing + +## Introducion + +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: + +1. After reaching Safehome/LAND Waypoint the altitude is corrected to "Approach Altitude". +2. The aircraft circles for at least 30 seconds to determine the wind direction and strength. +3. The landing direction and the approach waypoints are calculated on the basis of the measured wind parameters. If no headwind landing is possible or the wind strength is greater than "Max. tailwind" (see Global Parameters), return to point 2. +4. The landing is initiated. The aircraft flies the downwind course, "Approach Altitude" is held. +5. Base Leg: the altitude is reduced from 2/3 of "Approach Altitude". +6. Final Appraoch: The engine power is reduced using "Pitch2throttle modifier" to reduce speed and the altitude is reduced to "Land Altitude". +7. Glide: When "Glide Altitude" is reached, the motor is switched off and the pitch angle of "Glide Pitch" is held. +7. Flare: Only if a LIDAR/Rangefinder sensor is present: the motor remains switched off and the pitch angle of "Flare Pitch" is held +8. Landing: As soon as INAV has detected the landing, it is automatically disarmed, see setting `nav_disarm_on_landing`. + +To activate the automatic landing, the parameter `nav_rth_allow_landing` must be set to `ALWAYS` or `FAILSAFE`. + +> [!WARNING] +> If landing is activated and no parameters are set for the landing site (Safehome and/or landing waypoint), the old landing procedure (circling until close to the ground, then hovering out) is performed. +> This is probably not what you want. + +The following graphics illustrate the process: + +![Approach Drawing Up](/docs/assets/images/Approach-Drawing-Up.png "Approach Drawing Up") + +![Approach Drawing Side](/docs/assets/images/Approach-Drawing-Side.png "Approach Drawing Side") + +## Landing site parameters + +### The following parameters are set for each landing site (Safefome/LAND waypoint): + +All settings can also be conveniently made in the Configurator via Mission Control. + +CLI command `fwapproach`: +`fwapproach ` + +`fwapproach` has 17 slots in which landing parameters can be stored. In slot 0-7 the landing parameters for Safehome are stored, in 8 - 16 the parameters for waypoint missions. Only one landing point per mission can be saved. + +* index: 0 - 17, 0 - 7 Safehome, 8 - 16 Mission +* Approach direction: 0 - Left, 1 - Right. Always seen from the primary landing direction (positive value), i.e. whether the aircraft flies left or right turns on approach. +* Approach Altitude: Initial altitude of the approach, the altitude at which the wind direction is determined and the downwind approach, in cm +* Land Altitude: Altitude of the landing site, in cm +* Approach heading 1 and 2: Two landing directions can be set, values: 0 - +/-360. 0 = landing direction is deactivated. +A positive value means that you can approach in both directions, a negative value means that this direction is exclusive. +Example: 90 degrees: It is possible to land in 90 degrees as well as in 270 degrees. -90 means that you can only land in a 90 degree direction. +This means that practically 4 landing directions can be saved. +* Sea Level: 0 - Deactivated, 1 - Activated. If activated, approach and land altitude refer to normal zero (sea level), otherwise relative altitude to the altitude during first GPS fix. + +> [!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 parameters + +All settings are available via “Advanced Tuning” in the Configurator. + +* `nav_fw_land_approach_length`: Length of the final approach, measured from the land site (Safehome/Waypoint) to the last turning point. +In cm. Max: 100000, Min: 100, Default: 35000 + +* `nav_fw_land_final_approach_pitch2throttle_mod`: Modifier for pitch to throttle ratio at final approach. This parameter can be used to reduce speed during the final approach. +Example: If the parameter is set to 200% and Pitch To Throttle Ratio is set to 15, Pitch To Throttle Ratio is set to 30 on the final approach. This causes a reduction in engine power on approach when the nose is pointing downwards. +In Percent. Min: 100, Max: 400, Default: 100 + +* `nav_fw_land_glide_alt`: Initial altitude of the glide phase. The altitude refers to "Landing Altitude", see above under "Landing site parameters" +In cm. Min: 100, Max: 5000, Default: 200 + +* `nav_fw_land_flare_alt`: Initial altitude of the flare phase. The altitude refers to "Landing Altitude", see above under "Landing site parameters" +In cm. Min: 0, Max: 5000, Default: 200 + +* `nav_fw_land_glide_pitch`: Pitch value for glide phase. +In degrees. Min: 0, Max: 45, Default: 0 + +* `nav_fw_land_flare_pitch`: Pitch value for flare phase. + In degrees. Min: 0, Max: 45, Default: 8 + +* `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. +If the altitude of the waypoint and the "Approach Altitude" are different, the altitude of the waypoint is approached first and then the altitude is corrected to "Approach Altitude". + +## 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. deployment of the landing flaps. + +| Returned value | State | +| --- | --- | +| 0 | Idle/Inactive | +| 1 | Loiter | +| 2 | Downwind | +| 3 | Base Leg | +| 4 | Final Approach | +| 5 | Glide | +| 6 | Flare | diff --git a/docs/GPS_fix_estimation.md b/docs/GPS_fix_estimation.md new file mode 100644 index 00000000000..5d11e626097 --- /dev/null +++ b/docs/GPS_fix_estimation.md @@ -0,0 +1,132 @@ +# GPS Fix estimation (dead reconing, RTH without GPS) for fixed wing + +Video demonstration + +[![IMAGE ALT TEXT HERE](https://img.youtube.com/vi/wzvgRpXCS4U/0.jpg)](https://www.youtube.com/watch?v=wzvgRpXCS4U) + +There is possibility to allow plane to estimate it's position when GPS fix is lost. +The main purpose is RTH without GPS. +It works for fixed wing only. + +Plane should have the following sensors: +- acceleromenter, gyroscope +- barometer +- GPS +- magnethometer (optional, highly recommended) +- pitot (optional) + +By befault, all navigation modes are disabled when GPS fix is lost. If RC signal is lost also, plane will not be able to enable RTH. Plane will switch to LANDING instead. When flying above unreachable spaces, plane will be lost. + +GPS fix estimation allows to recover plane using magnetometer and baromener only. + +GPS Fix is also estimated on GPS Sensor timeouts (hardware failures). + +Note, that GPS fix estimation is not a solution for navigation without GPS. Without GPS fix, position error accumulates quickly. But it is acceptable for RTH. This is not a solution for flying under spoofing also. GPS is the most trusted sensor in Inav. It's output is not validated. + +# How it works ? + +In normal situation, plane is receiving it's position from GPS sensor. This way it is able to hold course, RTH or navigate by waypoints. + +Without GPS fix, plane has nose heading from magnetometer and height from barometer only. + +To navigate without GPS fix, we make the following assumptions: +- plane is flying in the direction where nose is pointing +- (if pitot tube is not installed) plane is flying with constant airspeed, specified in settings + +It is possible to roughly estimate position using theese assumptions. To increase accuracy, plane will use information about wind direction and speed, estimated before GPS fix was lost. To increase groundspeed estimation accuracy, plane will use pitot tube data(if available). + +From estimated heading direction and speed, plane is able to **roughly** estimate it's position. + +It is assumed, that plane will fly in roughly estimated direction to home position untill either GPS fix or RC signal is recovered. + +*Plane has to acquire GPS fix and store home position before takeoff. Estimation completely without GPS fix will not work*. + +# Estimation without magnethometer + +Without magnethometer, navigation accuracy is very poor. The problem is heading drift. + +The longer plane flies without magnethometer or GPS, the bigger is course estimation error. + +After few minutes and few turns, "North" direction estimation can be completely broken. +In general, accuracy is enough to perform RTH U-turn when both RC controls and GPS are lost, and roughtly keep RTH direction in areas with occasional GPS outages. + +![image](https://github.com/RomanLut/inav/assets/11955117/3d5c5d10-f43a-45f9-a647-af3cca87c4da) + +(purple line - estimated position, black line - real position). + +It is recommened to use GPS fix estimation without magnethometer as last resort only. For example, if plane is flying above lake, landing means loss of plane. With GPS Fix estimation, plane will try to do RTH in very rought direction, instead of landing. + +It is up to user to estimate the risk of fly-away. + + +# Settings + +GPS Fix estimation is enabled with CLI command: + +```set inav_allow_gps_fix_estimation=ON``` + +Also you have to specify cruise airspeed of the plane. + +To find out cruise airspeed, make a test flight. Enable ground speed display on OSD. Flight in CRUISE mode in two opposite directions. Take average speed. + +Cruise airspeed is specified in cm/s. + +To convert km/h to m/s, multiply by 27.77. + + +Example: 100 km/h = 100 * 27.77 = 2777 cm/s + +```set fw_reference_airspeed=2777``` + +*It is important, that plane fly with specified speed in CRUISE mode. If you have set option "Increase cruise speed with throttle" - do not use it without GPS Fix.* + +*If pitot is available, pitot sensor data will be used instead of constant. It is not necessary to specify fw_reference_airspeed. However, it is still adviced to specify for the case of pitot failure.* + +*Note related command: to continue mission without RC signal, see command ```set failsafe_mission_delay=-1```.* + +**After entering CLI command, make sure that settings are saved:** + +```save``` + +# Disabling GPS sensor from RC controller + +![](Screenshots/programming_disable_gps_sensor_fix.png) + +For testing purposes, it is possible to disable GPS sensor fix from RC controller in programming tab: + +*GPS can be disabled only after: 1) initial GPS fix is acquired 2) in ARMED mode.* + +# Allowing wp missions with GPS Fix estimation + +```failsafe_gps_fix_estimation_delay``` + +Controls whether waypoint mission is allowed to proceed with gps fix estimation. Sets the time delay in seconds between gps fix lost event and RTH activation. Minimum delay is 7 seconds. If set to -1 the mission will continue until the end. With default setting(7), waypoint mission is aborted and switched to RTH with 7 seconds delay. RTH is done with GPS Fix estimation. RTH is trigerred regradless of failsafe procedure selected in configurator. + +# Expected error (mag + baro) + +Realistic expected error is up to 200m per 1km of flight path. In tests, 500m drift per 5km path was seen. + +To dicrease drift: +- fly one large circle with GPS available to get good wind estimation +- use airspeed sensor. If airspeed sensor is not installed, fly in cruise mode without throttle override. +- do smooth, large turns +- make sure compass is pointing in nose direction precicely +- calibrate compass correctly + +This video shows real world test where GPS was disabled occasionally. Wind is 10km/h south-west: + + +https://github.com/RomanLut/inav/assets/11955117/0599a3c3-df06-4d40-a32a-4d8f96140592 + + +Purple line shows estimated position. Black line shows real position. "EST ERR" sensor shows estimation error in metters. Estimation is running when satellite icon displays "ES". Estimated position snaps to real position when GPS fix is reaquired. + + +# Is it possible to implement this for multirotor ? + +There are some ideas, but there is no solution now. We can not make assumptions with multirotor which we can make with a fixed wing. + + +# Links + +INAV HITL https://github.com/RomanLut/INAV-X-Plane-HITL diff --git a/docs/Getting Started.md b/docs/Getting Started.md index 2faa8e33234..f49ca32cc44 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/LedStrip.md b/docs/LedStrip.md index d19660530a2..cecd630ecc9 100644 --- a/docs/LedStrip.md +++ b/docs/LedStrip.md @@ -7,7 +7,7 @@ require that all the LEDs in the strip show the same color. Addressable LED strips can be used to show information from the flight controller system, the current implementation supports the following: -* Up to 32 LEDs. +* Up to 128 LEDs. _If using more than 20 LEDs, you should look to use a separate power supply._ * Indicators showing pitch/roll stick positions. * Heading/Orientation lights. * Flight mode specific color schemes. @@ -17,12 +17,12 @@ supports the following: * RSSI level. * Battery level. -Support for more than 32 LEDs is possible, it just requires additional development. +Support for more than 128 LEDs is possible, it just requires additional development. ## Supported hardware -Only strips of 32 WS2811/WS2812 LEDs are supported currently. If the strip is longer than 32 LEDs it does not matter, -but only the first 32 are used. +Only strips of 128 WS2811/WS2812 LEDs are supported currently. If the strip is longer than 128 LEDs it does not matter, +but only the first 128 are used. WS2812 LEDs require an 800khz signal and precise timings and thus requires the use of a dedicated hardware timer. @@ -42,11 +42,11 @@ It could be possible to be able to specify the timings required via CLI if users WS2812 LED strips generally require a single data line, 5V and GND. -WS2812 LEDs on full brightness can consume quite a bit of current. It is recommended to verify the current draw and ensure your -supply can cope with the load. On a multirotor that uses multiple BEC ESC's you can try use a different BEC to the one the FC -uses. e.g. ESC1/BEC1 -> FC, ESC2/BEC2 -> LED strip. It's also possible to power one half of the strip from one BEC and the other half -from another BEC. Just ensure that the GROUND is the same for all BEC outputs and LEDs. +WS2812 LEDs on full brightness can consume quite a bit of current. **It is recommended to verify the current draw of you LEDs and ensure your supply can cope with the load. Remember, your flight controller will likely be using the same BEC to operate.** Check the specs of the LED chips. Some are more power hungry than others. Remember that if using the flight controller's 5v supply. This is also powering other components on your flight controller. Make sure there is enough overhead so that they don't brownout. +On a multirotor that uses multiple BEC ESC's you can try use a different BEC to the one the FC uses. e.g. ESC1/BEC1 -> FC, ESC2/BEC2 -> LED strip. It's also possible to power one half of the strip from one BEC and the other half from another BEC. Just ensure that the GROUND is the same for all BEC outputs and LEDs. + +If using a large number of LEDs. It would be more efficient to use 12v LEDs and power them with a separate regulated supply. Especially if using long strips. You would use the data line (LED pad) from the flight controller. Make sure there is continuity between the ground on the LEDS and the ground on the flight controller. | Target | Pin | LED Strip | Signal | | --------------------- | ---- | --------- | -------| @@ -605,4 +605,4 @@ This also means that you can make sure that each R,G and B LED in each LED modul After a short delay the LEDs will show the unarmed color sequence and or low-battery warning sequence. -Also check that the feature `LED_STRIP` was correctly enabled and that it does not conflict with other features, as above. +Also check that the feature `LED_STRIP` was correctly enabled and that it does not conflict with other features, as above. \ No newline at end of file diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index f6688feaeec..55aedd3a30b 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -1,80 +1,30 @@ # MixerProfile -A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings to enable VTOL transitions. +A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings. It is designed for experienced inav users. -Currently two profiles are supported on targets other than F411 and F722 (due to resource constraints on these FC). i.e VTOL transition is not available on F411 and F722 targets. +### For a tutorial of vtol setup, Read https://github.com/iNavFlight/inav/blob/master/docs/VTOL.md -By default, switching between profiles requires reboot to take affect. However, when all conditions are met, and a suitable [configuration](#configuration) has been applied, `mixer_profile` also allows in-flight profile [switching](#rc-mode-settings) to allow things like VTOL operation. This is the recommended operating mode. +Not limited to VTOL. air/land/sea mixed vehicle is also achievable with this feature. Model behaves according to current mixer_profile's platform_type and configured custom motor/servo mixer -Please note that this is an emerging / experimental capability that will require some effort by the pilot to implement. - -## Setup for VTOL -- A VTOL specific FC target or `timer_output_mode` overrides was required in the early stage of the development, But since unified mapping introduced in INAV 7.0 It is not needed anymore. -- ~~For mixer profile switching it is necessary to keep motor and servo PWM mapping consistent between Fixed-Wing (FW) and Multi-rotor (MR) profiles~~ -- ~~Traditionally, FW and MR have had different enumerations to define the PWM mappings. For VTOL operation it is necessary to set the `timer_output_mode` overrides to allow a consistent enumeration and thus mapping between MR and FW modes.~~ -- ~~In operation, it is necessary to set the `mixer_profile` and the `pid_profile` separately and to set a [RC mode](#rc-mode-settings) to switch between them.~~ -## Configuration -### Timer overrides -Set the timer overrides for the outputs that you are intended to use. -For SITL builds, is not necessary to set timer overrides. -Please note that there are some display issues on the configurator that will show wrong mapping on the mixer_profile which has less motor/servo compared with the another -### Profile Switch - -Setup the FW mode and MR mode separately in two different mixer profiles: - -In this example, FW mode is `mixer_profile` 1 and MR mode is `mixer_profile` 2. - -Currently, the INAV Configurator does not fully support `mixer_profile`, so some of the settings have to be done in CLI. - -Add `set mixer_pid_profile_linking = ON` in order to enable `pid_profile` auto handling. It will change the `pid profile` index according to the `mixer_profile` index on FC boot and allow `mixer_profile` hot switching (this is recommended usage). - -The following 2 `mixer_profile` sections are added in the CLI: - -``` -#switch to mixer_profile by cli -mixer_profile 1 - -set platform_type = AIRPLANE -set model_preview_type = 26 -# motor stop feature have been moved to here -set motorstop_on_low = ON -# enable pid_profile auto handling (recommended). -set mixer_pid_profile_linking = ON -save -``` -Then finish the aeroplane setting on mixer_profile 1 - -``` -mixer_profile 2 - -set platform_type = TRICOPTER -set model_preview_type = 1 -# also enable pid_profile auto handling -set mixer_pid_profile_linking = ON -save -``` -Then finish the multi-rotor setting on `mixer_profile` 2. +Currently two profiles are supported on targets other than F411(due to resource constraints on F411). i.e VTOL transition is not available on F411. -Note that default profile is profile `1`. +For VTOL setup. one mixer_profile is used for multi-rotor(MR) and the other is used for fixed-wing(FW) +By default, switching between profiles requires reboot to take affect. However, using the RC mode: `MIXER PROFILE 2` will allow in flight switching for things like VTOL operation +. And will re-initialize pid and navigation controllers for current MC or FW flying mode. -You can use `MAX` servo input to set a fixed input for the tilting servo. Speed setting for `MAX` input is available in the CLI. - -It is recommended to have some amount of control surface (elevon / elevator) mapped for stabilization even in MR mode to get improved authority when airspeed is high. - -**Double check all settings in CLI with the `diff all` command**; make sure you have set the correct settings. Also check what will change with `mixer_profile`. For example servo output min / max range will not change. But `smix` and `mmix` will change. +Please note that this is an emerging / experimental capability that will require some effort by the pilot to implement. -### Mixer Transition input +## Mixer Transition input Typically, 'transition input' will be useful in MR mode to gain airspeed. -Both the servo mixer and motor mixer can accept transition mode as an input. The associated motor or servo will then move accordingly when transition mode is activated. Transition input is disabled when navigation mode is activate The use of Transition Mode is recommended to enable further features and future developments like fail-safe support. Mapping motor to servo output, or servo with logic conditions is **not** recommended -#### Servo +## Servo -38 is the input source for transition input; use this to tilt motor to gain airspeed. +`Mixer Transition` is the input source for transition input; use this to tilt motor to gain airspeed. Example: Increase servo 1 output by +45 with speed of 150 when transition mode is activated for tilted motor setup: @@ -82,15 +32,14 @@ Example: Increase servo 1 output by +45 with speed of 150 when transition mode i # rule no; servo index; input source; rate; speed; activate logic function number smix 6 1 38 45 150 -1 ``` -Please note there will be a time window that tilting motors is providing up lift but rear motor isn't. Result in a sudden pitch raise on the entering of the mode. More forward tilting servo position on transition input(you can use 'speed' in servo rules to slowly move to this position), A faster tilting servo speed on `MAX` servo input will reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect. -#### Motor +## Motor -The default `mmix` throttle value is 0.0, It will not show in `diff` command when throttle value is 0.0 (unused); this causes the motor to stop. +The default `mmix` throttle value is 0.0, It will not show in `diff` command when throttle value is 0.0 (unused); - 0.0