Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/master' into mmosca-mavlink-gimbal
Browse files Browse the repository at this point in the history
  • Loading branch information
mmosca committed Sep 10, 2024
2 parents 446e25c + bb856c0 commit bc830ef
Show file tree
Hide file tree
Showing 37 changed files with 902 additions and 86 deletions.
13 changes: 9 additions & 4 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ jobs:
runs-on: ubuntu-latest
strategy:
matrix:
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16]
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15]

steps:
- uses: actions/checkout@v4
Expand All @@ -40,12 +40,13 @@ jobs:
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
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
- uses: actions/cache@v4
with:
path: downloads
key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}}
- 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 }} -DMAIN_COMPILE_OPTIONS=-pipe -G Ninja .. && ninja -j4 ci
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 }} -DMAIN_COMPILE_OPTIONS=-pipe -G Ninja .. && ninja -j${{ env.NUM_CORES }} ci
- name: Upload artifacts
uses: actions/upload-artifact@v4
with:
Expand Down Expand Up @@ -74,6 +75,7 @@ jobs:
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
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
- name: Download artifacts
uses: actions/download-artifact@v4
with:
Expand Down Expand Up @@ -116,8 +118,9 @@ jobs:
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
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
- name: Build SITL
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja -j4
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja .. && ninja -j${{ env.NUM_CORES }}
- name: Upload artifacts
uses: actions/upload-artifact@v4
with:
Expand Down Expand Up @@ -148,11 +151,12 @@ jobs:
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
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
- name: Build SITL
run: |
mkdir -p build_SITL && cd build_SITL
cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DCMAKE_OSX_ARCHITECTURES="arm64;x86_64" -G Ninja ..
ninja -j3
ninja -j4
- name: Upload artifacts
uses: actions/upload-artifact@v4
Expand Down Expand Up @@ -187,6 +191,7 @@ jobs:
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 -j4
- name: Upload artifacts
Expand Down
12 changes: 7 additions & 5 deletions .github/workflows/dev-builds.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ jobs:
runs-on: ubuntu-latest
strategy:
matrix:
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16]
id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15]

steps:
- uses: actions/checkout@v4
Expand All @@ -42,12 +42,13 @@ jobs:
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
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
- uses: actions/cache@v4
with:
path: downloads
key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}}
- 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 }} -DVERSION_TYPE=dev -G Ninja .. && ninja ci
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 }} -DVERSION_TYPE=dev -G Ninja .. && ninja -j${{ env.NUM_CORES }} ci
- name: Upload artifacts
uses: actions/upload-artifact@v4
with:
Expand Down Expand Up @@ -76,8 +77,9 @@ jobs:
VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/[ \t\)]+/, "", $2); print $2 }')
echo "BUILD_SUFFIX=${BUILD_SUFFIX}" >> $GITHUB_ENV
echo "BUILD_NAME=inav-${VERSION}-${BUILD_SUFFIX}" >> $GITHUB_ENV
echo "NUM_CORES=$(grep processor /proc/cpuinfo | wc -l)" >> $GITHUB_ENV
- name: Build SITL
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja -DVERSION_TYPE=dev .. && ninja
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -G Ninja -DVERSION_TYPE=dev .. && ninja -j${{ env.NUM_CORES }}
- name: Upload artifacts
uses: actions/upload-artifact@v4
with:
Expand Down Expand Up @@ -112,7 +114,7 @@ jobs:
run: |
mkdir -p build_SITL && cd build_SITL
cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DCMAKE_OSX_ARCHITECTURES="arm64;x86_64" -DVERSION_TYPE=dev -G Ninja ..
ninja
ninja -j4
- name: Upload artifacts
uses: actions/upload-artifact@v4
Expand Down Expand Up @@ -150,7 +152,7 @@ jobs:
#echo "VERSION_TAG=-$(date '+%Y%m%d')" >> $GITHUB_ENV
echo "version=${VERSION}" >> $GITHUB_OUTPUT
- name: Build SITL
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DVERSION_TYPE=dev -G Ninja .. && ninja
run: mkdir -p build_SITL && cd build_SITL && cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -DVERSION_TYPE=dev -G Ninja .. && ninja -j4
- name: Upload artifacts
uses: actions/upload-artifact@v4
with:
Expand Down
4 changes: 2 additions & 2 deletions docs/Fixed Wing Landing.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

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

Expand All @@ -15,7 +15,7 @@ This enables up to 4 different approach directions, based on the landing site an
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".
6. Final Appraoch: The engine power is reduced using "Pitch2throttle modifier" to reduce speed and the altitude is gradually reduced towards "Land Altitude" while approaching the Safehome coordinates.
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`.
Expand Down
2 changes: 2 additions & 0 deletions docs/MixerProfile.md
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ The default `mmix` throttle value is 0.0, It will not show in `diff` command whe
- -1.0<throttle<=0.0 : motor stop, default value 0, set to -1 to use a place holder for subsequent motor rules
- -2.0<throttle<-1.0 : spin regardless of throttle position at speed `abs(throttle)-1` when Mixer Transition is activated.

Airmode type should be set to "STICK_CENTER". Airmode type must NOT be set to "THROTTLE_THRESHOLD". If set to throttle threshold the (-) motor will spin till throttle threshold is passed.

Example: This will spin motor number 5 (counting from 1) at 20%, in transition mode only, to gain speed for a "4 rotor 1 pusher" setup:

```
Expand Down
2 changes: 1 addition & 1 deletion docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -3534,7 +3534,7 @@ Pitch Angle deadband when soaring mode enabled (deg). Angle mode inactive within

### nav_fw_wp_tracking_accuracy

Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Settings 1 to 10 adjust the course tracking response. Higher values dampen the response reducing possible overshoot. A value of 5 is a good starting point. Set to 0 to disable.
Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Setting adjusts tracking deadband distance fom waypoint courseline [m]. Tracking isn't actively controlled within the deadband providing smoother flight adjustments but less accurate tracking. A 2m deadband should work OK in most cases. Setting to 0 disables waypoint tracking accuracy.

| Default | Min | Max |
| --- | --- | --- |
Expand Down
2 changes: 1 addition & 1 deletion docs/USB Flashing.md
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ With the board connected and in bootloader mode (reset it by sending the charact

* If you are using a device with only USB-C ports such as a Mac-OS device, you will need a dongle.
* A USB-C to USB-C cable is identical on both ends and thus requires extra hardware to let them be auto detected as devices instead of hosts.
* Using a USB-A to C cable or dongle is usually the easiest way to get a working connection but an USB-OTG adapter also works.
* Using either a hub with USB-A ports, or a USB-A to C cable or dongle is usually the easiest way to get a working connection but an USB-OTG adapter also works.

## Using `dfu-util`

Expand Down
5 changes: 3 additions & 2 deletions docs/VTOL.md
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,8 @@ Add new servo mixer rules, and select 'Mixer Transition' in input. Set the weigh
## Motor 'Transition Mixing': Dedicated forward motor configuration
In motor mixer set:
- -2.0 < throttle < -1.0: The motor will spin regardless of the radio's throttle position at a speed of `abs(throttle) - 1` multiplied by throttle range only when Mixer Transition is activated.
- Airmode type should be set to "STICK_CENTER". Airmode type must NOT be set to "THROTTLE_THRESHOLD". If set to throttle threshold the (-) motor will spin till throttle threshold is passed.
![Alt text](Screenshots/mixerprofile_4puls1_mix.png)
## TailSitter 'Transition Mixing':
Expand Down Expand Up @@ -233,4 +234,4 @@ If you set `mixer_automated_switch` to `OFF` for all mixer profiles (the default
2. In addition to 1. Add a little yaw mixing(about 0.2) in tilt motors.
- There will be a time window that tilting motors is providing up lift but rear motor isn't. Result in a sudden pitch raise on the entering of the mode. Use the max speed or faster speed in tiling servo to reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect.
## Dedicated forward motor
- Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight
- Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight
4 changes: 0 additions & 4 deletions src/main/drivers/headtracker_common.c
Original file line number Diff line number Diff line change
Expand Up @@ -157,10 +157,6 @@ void taskUpdateHeadTracker(timeUs_t currentTimeUs)
#else
void taskUpdateHeadTracker(timeUs_t currentTimeUs)
{
if (cliMode) {
return;
}

headTrackerDevice_t *headTrackerDevice = headTrackerCommonDevice();

if(headTrackerDevice) {
Expand Down
3 changes: 2 additions & 1 deletion src/main/drivers/headtracker_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#define HEADTRACKER_RANGE_MIN -2048
#define HEADTRACKER_RANGE_MAX 2047

#ifdef USE_HEADTRACKER

#include <stdint.h>

Expand Down Expand Up @@ -81,6 +80,8 @@ typedef struct headTrackerConfig_s {
float roll_ratio;
} headTrackerConfig_t;

#ifdef USE_HEADTRACKER

PG_DECLARE(headTrackerConfig_t, headTrackerConfig);

void headTrackerCommonInit(void);
Expand Down
4 changes: 3 additions & 1 deletion src/main/drivers/serial_uart.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@ typedef enum {
UARTDEV_5 = 4,
UARTDEV_6 = 5,
UARTDEV_7 = 6,
UARTDEV_8 = 7
UARTDEV_8 = 7,
UARTDEV_MAX
} UARTDevice_e;

typedef struct {
Expand All @@ -69,6 +70,7 @@ typedef struct {

void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins);
void uartClearIdleFlag(uartPort_t *s);
void uartConfigurePinSwap(uartPort_t *uartPort);
#if defined(AT32F43x)
serialPort_t *uartOpen(usart_type *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options);
#else
Expand Down
81 changes: 73 additions & 8 deletions src/main/drivers/serial_uart_at32f43x.c
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ typedef struct uartDevice_s {
uint8_t af;
uint8_t irq;
uint32_t irqPriority;
bool pinSwap;
} uartDevice_t;

#ifdef USE_UART1
Expand All @@ -59,7 +60,12 @@ static uartDevice_t uart1 =
#endif
.rcc_apb2 = RCC_APB2(USART1),
.irq = USART1_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART
.irqPriority = NVIC_PRIO_SERIALUART,
#ifdef USE_UART1_PIN_SWAP
.pinSwap = true,
#else
.pinSwap = false,
#endif
};
#endif

Expand All @@ -75,7 +81,12 @@ static uartDevice_t uart2 =
#endif
.rcc_apb1 = RCC_APB1(USART2),
.irq = USART2_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART
.irqPriority = NVIC_PRIO_SERIALUART,
#ifdef USE_UART2_PIN_SWAP
.pinSwap = true,
#else
.pinSwap = false,
#endif
};
#endif

Expand All @@ -91,7 +102,12 @@ static uartDevice_t uart3 =
#endif
.rcc_apb1 = RCC_APB1(USART3),
.irq = USART3_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART
.irqPriority = NVIC_PRIO_SERIALUART,
#ifdef USE_UART3_PIN_SWAP
.pinSwap = true,
#else
.pinSwap = false,
#endif
};
#endif

Expand All @@ -107,7 +123,12 @@ static uartDevice_t uart4 =
#endif
.rcc_apb1 = RCC_APB1(UART4),
.irq = UART4_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART
.irqPriority = NVIC_PRIO_SERIALUART,
#ifdef USE_UART4_PIN_SWAP
.pinSwap = true,
#else
.pinSwap = false,
#endif
};
#endif

Expand All @@ -123,7 +144,12 @@ static uartDevice_t uart5 =
#endif
.rcc_apb1 = RCC_APB1(UART5),
.irq = UART5_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART
.irqPriority = NVIC_PRIO_SERIALUART,
#ifdef USE_UART5_PIN_SWAP
.pinSwap = true,
#else
.pinSwap = false,
#endif
};
#endif

Expand All @@ -139,7 +165,12 @@ static uartDevice_t uart6 =
#endif
.rcc_apb2 = RCC_APB2(USART6),
.irq = USART6_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART
.irqPriority = NVIC_PRIO_SERIALUART,
#ifdef USE_UART6_PIN_SWAP
.pinSwap = true,
#else
.pinSwap = false,
#endif
};
#endif

Expand All @@ -152,7 +183,12 @@ static uartDevice_t uart7 =
.af = GPIO_MUX_8,
.rcc_apb1 = RCC_APB1(UART7),
.irq = UART7_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART
.irqPriority = NVIC_PRIO_SERIALUART,
#ifdef USE_UART7_PIN_SWAP
.pinSwap = true,
#else
.pinSwap = false,
#endif
};
#endif

Expand All @@ -165,7 +201,12 @@ static uartDevice_t uart8 =
.af = GPIO_MUX_8,
.rcc_apb1 = RCC_APB1(UART8),
.irq = UART8_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART
.irqPriority = NVIC_PRIO_SERIALUART,
#ifdef USE_UART8_PIN_SWAP
.pinSwap = true,
#else
.pinSwap = false,
#endif
};
#endif

Expand Down Expand Up @@ -258,6 +299,30 @@ void uartClearIdleFlag(uartPort_t *s)
(void) s->USARTx->dt;
}

static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
{
for (uint32_t i = 0; i < UARTDEV_MAX; i++) {
uartDevice_t *pDevice = uartHardwareMap[i];

if (pDevice->dev == uartPort->USARTx) {
return pDevice;
}
}
return NULL;
}

void uartConfigurePinSwap(uartPort_t *uartPort)
{
uartDevice_t *uartDevice = uartFindDevice(uartPort);
if (!uartDevice) {
return;
}

if (uartDevice->pinSwap) {
usart_transmit_receive_pin_swap(uartPort->USARTx, TRUE);
}
}

uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options)
{
uartPort_t *s;
Expand Down
1 change: 1 addition & 0 deletions src/main/drivers/serial_uart_hal_at32f43x.c
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@ static void uartReconfigure(uartPort_t *uartPort)
usart_transmitter_enable(uartPort->USARTx, TRUE);

usartConfigurePinInversion(uartPort);
uartConfigurePinSwap(uartPort);

if (uartPort->port.options & SERIAL_BIDIR)
usart_single_line_halfduplex_select(uartPort->USARTx, TRUE);
Expand Down
Loading

0 comments on commit bc830ef

Please sign in to comment.