Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/master' into release_6.1.1
Browse files Browse the repository at this point in the history
  • Loading branch information
DzikuVx committed Jun 14, 2023
2 parents 42ced25 + 12e13da commit ed095ef
Show file tree
Hide file tree
Showing 165 changed files with 3,014 additions and 2,744 deletions.
49 changes: 43 additions & 6 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@ jobs:
- name: Build targets (${{ matrix.id }})
run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -G Ninja .. && ninja ci
- name: Upload artifacts
uses: actions/upload-artifact@v2-preview
uses: actions/upload-artifact@v3
with:
name: ${{ env.BUILD_NAME }}.zip
name: ${{ env.BUILD_NAME }}
path: ./build/*.hex

build-SITL-Linux:
Expand Down Expand Up @@ -68,9 +68,46 @@ jobs:
- name: Build SITL
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja
- name: Upload artifacts
uses: actions/upload-artifact@v2-preview
uses: actions/upload-artifact@v3
with:
name: ${{ env.BUILD_NAME }}_SITL.zip
name: ${{ env.BUILD_NAME }}_SITL
path: ./build_SITL/*_SITL

build-SITL-Mac:
runs-on: macos-latest
steps:
- uses: actions/checkout@v3
- name: Install dependencies
run: |
brew update
brew install cmake ninja ruby
- name: Setup environment
env:
ACTIONS_ALLOW_UNSECURE_COMMANDS: true
run: |
# This is the hash of the commit for the PR
# when the action is triggered by PR, empty otherwise
COMMIT_ID=${{ github.event.pull_request.head.sha }}
# This is the hash of the commit when triggered by push
# but the hash of refs/pull/<n>/merge, which is different
# from the hash of the latest commit in the PR, that's
# why we try github.event.pull_request.head.sha first
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }')
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
- name: Build SITL
run: |
mkdir -p build_SITL && cd build_SITL
cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja ..
ninja
- name: Upload artifacts
uses: actions/upload-artifact@v3
with:
name: ${{ env.BUILD_NAME }}_SITL-MacOS
path: ./build_SITL/*_SITL

build-SITL-Windows:
Expand Down Expand Up @@ -103,9 +140,9 @@ jobs:
- name: Build SITL
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja
- name: Upload artifacts
uses: actions/upload-artifact@v2-preview
uses: actions/upload-artifact@v3
with:
name: ${{ env.BUILD_NAME }}_SITL-WIN.zip
name: ${{ env.BUILD_NAME }}_SITL-WIN
path: ./build_SITL/*.exe


Expand Down
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,10 @@ option(SITL "SITL build for host system" OFF)

set(TOOLCHAIN_OPTIONS none arm-none-eabi host)
if (SITL)
set(TOOLCHAIN "host" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}")
if (${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
if (CMAKE_HOST_APPLE)
set(MACOSX TRUE)
endif()
set(TOOLCHAIN "host" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}")
else()
set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}")
endif()
Expand Down Expand Up @@ -51,7 +51,7 @@ else()
endif()
endif()

project(INAV VERSION 6.1.1)
project(INAV VERSION 7.0.0)

enable_language(ASM)

Expand Down
12 changes: 6 additions & 6 deletions cmake/arm-none-eabi-checks.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,13 @@ 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.2.1")
set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/10-2020q4/gcc-arm-none-eabi-10-2020-q4-major")
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")
# suffix and checksum
set(arm_none_eabi_win32 "win32.zip" 5ee6542a2af847934177bc8fa1294c0d)
set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 8312c4c91799885f222f663fc81f9a31)
set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" 1c3b8944c026d50362eef1f01f329a8e)
set(arm_none_eabi_gcc_macos "mac.tar.bz2" e588d21be5a0cc9caa60938d2422b058)
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})
Expand Down
2 changes: 2 additions & 0 deletions cmake/at32.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ set(CMSIS_DSP_DIR "${MAIN_LIB_DIR}/main/CMSIS/DSP")
set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include")

set(CMSIS_DSP_SRC
BasicMathFunctions/arm_scale_f32.c
BasicMathFunctions/arm_sub_f32.c
BasicMathFunctions/arm_mult_f32.c
TransformFunctions/arm_rfft_fast_f32.c
TransformFunctions/arm_cfft_f32.c
Expand Down
12 changes: 10 additions & 2 deletions cmake/host.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,23 @@ set(CMAKE_CXX_COMPILER "g++${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++ compil
set(CMAKE_OBJCOPY "objcopy${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objcopy tool")
set(CMAKE_OBJDUMP "objdump${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objdump tool")
set(CMAKE_SIZE "size${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "size tool")
set(CMAKE_DEBUGGER "gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debugger")
if(CMAKE_HOST_APPLE)
set(CMAKE_DEBUGGER "lldb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debugger")
else()
set(CMAKE_DEBUGGER "gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debugger")
endif()
set(CMAKE_CPPFILT "c++filt${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++filt")

set(CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} CACHE STRING "Build Type" FORCE)
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS ${CMAKE_CONFIGURATION_TYPES})

set(debug_options "-Og -O0 -g")
set(release_options "-Os -DNDEBUG")
set(relwithdebinfo_options "-ggdb3 ${release_options}")
if(CMAKE_HOST_APPLE)
set(relwithdebinfo_options "-g ${release_options}")
else()
set(relwithdebinfo_options "-ggdb3 ${release_options}")
endif()

set(CMAKE_C_FLAGS_DEBUG ${debug_options} CACHE INTERNAL "c compiler flags debug")
set(CMAKE_CXX_FLAGS_DEBUG ${debug_options} CACHE INTERNAL "c++ compiler flags debug")
Expand Down
2 changes: 1 addition & 1 deletion cmake/main.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ function(setup_executable exe name)
set_target_properties(${exe} PROPERTIES
RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin"
)
if(IS_RELEASE_BUILD)
if(IS_RELEASE_BUILD AND NOT CMAKE_HOST_APPLE)
set_target_properties(${exe} PROPERTIES
INTERPROCEDURAL_OPTIMIZATION ON
)
Expand Down
5 changes: 4 additions & 1 deletion cmake/sitl.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ main_sources(SITL_SRC
)


if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
if(CMAKE_HOST_APPLE)
set(MACOSX ON)
endif()

Expand Down Expand Up @@ -59,6 +59,9 @@ if(NOT MACOSX)
-Wno-error=maybe-uninitialized
-fsingle-precision-constant
)
else()
set(SITL_COMPILE_OPTIONS ${SITL_COMPILE_OPTIONS}
)
endif()

set(SITL_DEFINITIONS
Expand Down
2 changes: 2 additions & 0 deletions cmake/stm32.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@ set(CMSIS_DSP_DIR "${MAIN_LIB_DIR}/main/CMSIS/DSP")
set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include")

set(CMSIS_DSP_SRC
BasicMathFunctions/arm_scale_f32.c
BasicMathFunctions/arm_sub_f32.c
BasicMathFunctions/arm_mult_f32.c
TransformFunctions/arm_rfft_fast_f32.c
TransformFunctions/arm_cfft_f32.c
Expand Down
2 changes: 2 additions & 0 deletions cmake/stm32h7.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,8 @@ main_sources(STM32H7_SRC
drivers/bus_i2c_hal.c
drivers/dma_stm32h7xx.c
drivers/bus_spi_hal_ll.c
drivers/bus_quadspi.c
drivers/bus_quadspi_hal.c
drivers/memprot.h
drivers/memprot_hal.c
drivers/memprot_stm32h7xx.c
Expand Down
4 changes: 3 additions & 1 deletion docs/Battery.md
Original file line number Diff line number Diff line change
Expand Up @@ -206,9 +206,11 @@ Up to 3 battery profiles are supported. You can select the battery profile from
- `battery_capacity_warning`
- `battery_capacity_critical`
- `throttle_idle`
- `fw_min_throttle_down_pitch`
- `throttle_scale`
- `turtle_mode_power_factor`
- `nav_fw_cruise_thr`
- `nav_fw_min_thr`
- `nav_fw_max_thr`
- `nav_fw_pitch2thr`
- `nav_fw_launch_thr`
- `nav_fw_launch_idle_thr`
Expand Down
4 changes: 4 additions & 0 deletions docs/Controls.md
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,10 @@ The stick positions are combined to activate different functions:
| Bypass Nav Arm disable | LOW | HIGH | CENTER | CENTER |
| Save setting | LOW | LOW | LOW | HIGH |
| Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER |
| Enter Camera OSD(RuncamDevice)| RIGHT | CENTER | CENTER | CENTER |
| Exit Camera OSD (RuncamDevice)| LEFT | CENTER | CENTER | CENTER |
| Confirm - Camera OSD | RIGHT | CENTER | CENTER | CENTER |
| Navigation - Camera OSD | CENTER | CENTER | * | * |

For graphical stick position in all transmitter modes, check out [this page](https://www.mrd-rc.com/tutorials-tools-and-testing/inav-flight/inav-stick-commands-for-all-transmitter-modes/).
![Stick Positions](assets/images/StickPositions.png)
Expand Down
14 changes: 9 additions & 5 deletions docs/Navigation.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,14 @@ The navigation system in INAV is responsible for assisting the pilot allowing al

## NAV ALTHOLD mode - altitude hold

Altitude hold requires a valid source of altitude - barometer, GPS or rangefinder. The best source is chosen automatically. GPS is available as an altitude source for airplanes only.
Altitude hold requires a valid source of altitude - barometer, GPS or rangefinder. The best source is chosen automatically.
In this mode THROTTLE stick controls climb rate (vertical velocity). When pilot moves stick up - quad goes up, pilot moves stick down - quad descends, you keep stick at neutral position - quad hovers.

By default, GPS is available as an altitude source for airplanes only. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled.

### CLI parameters affecting ALTHOLD mode:
* *nav_use_midthr_for_althold* - when set to "0", firmware will remember where your throttle stick was when ALTHOLD was activated - this will be considered neutral position. When set to "1" - 50% throttle will be considered neutral position.
* *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF.

### Related PIDs
PIDs affecting altitude hold: ALT & VEL
Expand All @@ -22,12 +25,13 @@ Throttle tilt compensation attempts to maintain constant vertical thrust when co

## NAV POSHOLD mode - position hold

Position hold requires GPS, accelerometer and compass sensors. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
Position hold requires GPS, accelerometer and compass sensors. Multirotor requires barometer, unless *inav_use_gps_no_baro* is enabled. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From INAV 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically.

### CLI parameters affecting POSHOLD mode:
* *nav_user_control_mode* - can be set to "0" (GPS_ATTI) or "1" (GPS_CRUISE), controls how firmware will respond to roll/pitch stick movement. When in GPS_ATTI mode, right stick controls attitude, when it is released, new position is recorded and held. When in GPS_CRUISE mode right stick controls velocity and firmware calculates required attitude on its own.

* *inav_use_gps_no_baro* - Multirotor only: enable althold based on GPS only, without baromemer installed. Default is OFF.

### Related PIDs
PIDs affecting position hold: POS, POSR
PID meaning:
Expand All @@ -38,9 +42,9 @@ PID meaning:

Home for RTH is the position where vehicle was first armed. This position may be offset by the CLI settings `nav_rth_home_offset_distance` and `nav_rth_home_offset_direction`. This position may also be overridden with Safehomes. RTH requires accelerometer, compass and GPS sensors.

If barometer is NOT present, RTH will fly directly to home, altitude control here is up to pilot.
RTH requires barometer for multirotor, unless unless *inav_use_gps_no_baro* is enabled.

If barometer is present, RTH will maintain altitude during the return. When home is reached, a copter will attempt automated landing. An airplane will either loiter around the home position, or attempt an automated landing, depending on your settings.
RTH will maintain altitude during the return. When home is reached, a copter will attempt automated landing. An airplane will either loiter around the home position, or attempt an automated landing, depending on your settings.
When deciding what altitude to maintain, RTH has 6 different modes of operation (controlled by *nav_rth_alt_mode* and *nav_rth_altitude* cli variables):
* 0 (NAV_RTH_NO_ALT) - keep current altitude during whole RTH sequence (*nav_rth_altitude* is ignored)
* 1 (NAV_RTH_EXTRA_ALT) - climb to current altitude plus extra margin prior to heading home (*nav_rth_altitude* defines the extra altitude (cm))
Expand Down
2 changes: 0 additions & 2 deletions docs/Profiles.md
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,6 @@ set max_angle_inclination_rll = 300
set max_angle_inclination_pit = 300
set dterm_lpf_hz = 110
set dterm_lpf_type = PT2
set dterm_lpf2_hz = 0
set dterm_lpf2_type = PT1
set yaw_lpf_hz = 0
set fw_iterm_throw_limit = 165
set fw_loiter_direction = RIGHT
Expand Down
3 changes: 2 additions & 1 deletion docs/Programming Framework.md
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,8 @@ IPF can be edited using INAV Configurator user interface, or via CLI
| 15 | SUB | Substract `Operand B` from `Operand A` and returns the result |
| 16 | MUL | Multiply `Operand A` by `Operand B` and returns the result |
| 17 | DIV | Divide `Operand A` by `Operand B` and returns the result |
| 18 | GVAR SET | Store value from `Operand B` into the Global Variable addressed by `Operand B`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` |
| 18 | GVAR SET | Store value from `Operand B` into the Global Variable addressed by
`Operand A`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` |
| 19 | GVAR INC | Increase the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` |
| 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` (use `Value 1` for Global Variable 1) with value from `Operand B` |
| 21 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` |
Expand Down
Loading

0 comments on commit ed095ef

Please sign in to comment.