mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 16:55:29 +03:00
Merge remote-tracking branch 'origin/master' into mmosca-mavlinkrc
This commit is contained in:
commit
dabdeeab55
46 changed files with 958 additions and 113 deletions
13
.github/workflows/ci.yml
vendored
13
.github/workflows/ci.yml
vendored
|
@ -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
|
||||
|
@ -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:
|
||||
|
@ -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:
|
||||
|
@ -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:
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
|
12
.github/workflows/dev-builds.yml
vendored
12
.github/workflows/dev-builds.yml
vendored
|
@ -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
|
||||
|
@ -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:
|
||||
|
@ -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:
|
||||
|
@ -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
|
||||
|
@ -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:
|
||||
|
|
|
@ -14,4 +14,13 @@ All ADSB receivers which can send Mavlink [ADSB_VEHICLE](https://mavlink.io/en/m
|
|||
* [PINGRX](https://uavionix.com/product/pingrx-pro/) (not tested)
|
||||
* [TT-SC1](https://www.aerobits.pl/product/aero/) (tested)
|
||||
|
||||
## TT-SC1 settings
|
||||
* download software for ADSB TT-SC1 from https://www.aerobits.pl/product/aero/ , file Micro_ADSB_App-vX.XX.X_win_setup.zip and install it
|
||||
* connect your ADSB to FC, connect both RX and TX pins
|
||||
* in INAV configurator ports TAB set telemetry MAVLINK, and baudrate 115200
|
||||
* go to CLI in inav configurator and set serialpassthrough for port you connected ADSB ```serialpassthrough [PORT_YOU_SELECTED - 1] 115200 rxtx``` and close configurator
|
||||
* open ADSB program you installed, got to settings and set "telemetry" = MAVLINK,
|
||||
|
||||
PCB board for TT-SC1-B module https://oshwlab.com/error414/adsb-power-board
|
||||

|
||||
|
||||
|
|
|
@ -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.
|
||||
|
||||
|
@ -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`.
|
||||
|
|
|
@ -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:
|
||||
|
||||
```
|
||||
|
|
BIN
docs/Screenshots/ADSB_TTSC01_settings.png
Normal file
BIN
docs/Screenshots/ADSB_TTSC01_settings.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 94 KiB |
|
@ -3544,7 +3544,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 |
|
||||
| --- | --- | --- |
|
||||
|
|
|
@ -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`
|
||||
|
||||
|
|
|
@ -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.
|
||||
|
||||

|
||||
|
||||
## TailSitter 'Transition Mixing':
|
||||
|
@ -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
|
||||
|
|
|
@ -353,24 +353,24 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
|||
{"servo", 15, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_16)},
|
||||
{"servo", 16, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_17)},
|
||||
{"servo", 17, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_18)},
|
||||
{"servo", 18, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_18)},
|
||||
{"servo", 19, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_19)},
|
||||
{"servo", 20, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_20)},
|
||||
{"servo", 21, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_21)},
|
||||
{"servo", 22, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_22)},
|
||||
{"servo", 23, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_23)},
|
||||
{"servo", 24, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_24)},
|
||||
{"servo", 25, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_25)},
|
||||
{"servo", 18, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_19)},
|
||||
{"servo", 19, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_20)},
|
||||
{"servo", 20, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_21)},
|
||||
{"servo", 21, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_22)},
|
||||
{"servo", 22, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_23)},
|
||||
{"servo", 23, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_24)},
|
||||
{"servo", 24, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_25)},
|
||||
{"servo", 25, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_26)},
|
||||
/*
|
||||
{"servo", 26, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_26)},
|
||||
{"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_27)},
|
||||
{"servo", 26, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_27)},
|
||||
{"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_28)},
|
||||
{"servo", 28, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_29)},
|
||||
{"servo", 29, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_30)},
|
||||
{"servo", 30, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_31)},
|
||||
{"servo", 31, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_32)},
|
||||
{"servo", 32, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_33)},
|
||||
{"servo", 33, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_34)},
|
||||
{"servo", 27, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_29)},
|
||||
{"servo", 28, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_30)},
|
||||
{"servo", 29, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_31)},
|
||||
{"servo", 30, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_32)},
|
||||
{"servo", 31, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_33)},
|
||||
{"servo", 32, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_34)},
|
||||
{"servo", 33, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_SERVOS_35)},
|
||||
*/
|
||||
|
||||
{"navState", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
|
@ -712,7 +712,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_33:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_34:
|
||||
*/
|
||||
return ((FlightLogFieldCondition)MIN(getServoCount(), 26) >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS);
|
||||
return ((FlightLogFieldCondition)getServoCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1 + 1) && blackboxIncludeFlag(BLACKBOX_FEATURE_SERVOS);
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
|
||||
|
|
|
@ -157,10 +157,6 @@ void taskUpdateHeadTracker(timeUs_t currentTimeUs)
|
|||
#else
|
||||
void taskUpdateHeadTracker(timeUs_t currentTimeUs)
|
||||
{
|
||||
if (cliMode) {
|
||||
return;
|
||||
}
|
||||
|
||||
headTrackerDevice_t *headTrackerDevice = headTrackerCommonDevice();
|
||||
|
||||
if(headTrackerDevice) {
|
||||
|
|
|
@ -23,7 +23,6 @@
|
|||
#define HEADTRACKER_RANGE_MIN -2048
|
||||
#define HEADTRACKER_RANGE_MAX 2047
|
||||
|
||||
#ifdef USE_HEADTRACKER
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
|
@ -81,6 +80,8 @@ typedef struct headTrackerConfig_s {
|
|||
float roll_ratio;
|
||||
} headTrackerConfig_t;
|
||||
|
||||
#ifdef USE_HEADTRACKER
|
||||
|
||||
PG_DECLARE(headTrackerConfig_t, headTrackerConfig);
|
||||
|
||||
void headTrackerCommonInit(void);
|
||||
|
|
|
@ -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 {
|
||||
|
@ -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
|
||||
|
|
|
@ -45,6 +45,7 @@ typedef struct uartDevice_s {
|
|||
uint8_t af;
|
||||
uint8_t irq;
|
||||
uint32_t irqPriority;
|
||||
bool pinSwap;
|
||||
} uartDevice_t;
|
||||
|
||||
#ifdef USE_UART1
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
@ -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;
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -19,6 +19,9 @@
|
|||
|
||||
#include <stdint.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
#include "common/time.h"
|
||||
|
||||
extern uint32_t usTicks;
|
||||
|
@ -32,3 +35,7 @@ timeUs_t microsISR(void);
|
|||
timeMs_t millis(void);
|
||||
|
||||
uint32_t ticks(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
|
@ -956,6 +956,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#ifdef USE_ADSB
|
||||
sbufWriteU8(dst, MAX_ADSB_VEHICLES);
|
||||
sbufWriteU8(dst, ADSB_CALL_SIGN_MAX_LENGTH);
|
||||
sbufWriteU32(dst, getAdsbStatus()->vehiclesMessagesTotal);
|
||||
sbufWriteU32(dst, getAdsbStatus()->heartbeatMessagesTotal);
|
||||
|
||||
for(uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++){
|
||||
|
||||
|
@ -977,6 +979,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#else
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU32(dst, 0);
|
||||
sbufWriteU32(dst, 0);
|
||||
#endif
|
||||
break;
|
||||
case MSP_DEBUG:
|
||||
|
@ -1034,7 +1038,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
case MSP_MIXER:
|
||||
sbufWriteU8(dst, 3); // mixerMode no longer supported, send 3 (QuadX) as fallback
|
||||
break;
|
||||
|
||||
|
||||
|
||||
case MSP_RX_CONFIG:
|
||||
sbufWriteU8(dst, rxConfig()->serialrx_provider);
|
||||
|
@ -1274,7 +1278,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
|
||||
|
@ -1618,7 +1622,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
}
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
|
||||
case MSP2_INAV_MC_BRAKING:
|
||||
#ifdef USE_MR_BRAKING_MODE
|
||||
|
@ -2892,7 +2896,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
|
||||
case MSP_SET_FAILSAFE_CONFIG:
|
||||
if (dataSize == 20) {
|
||||
failsafeConfigMutable()->failsafe_delay = sbufReadU8(src);
|
||||
|
@ -3291,11 +3295,9 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
#endif
|
||||
case MSP2_INAV_GPS_UBLOX_COMMAND:
|
||||
if(dataSize < 8 || !isGpsUblox()) {
|
||||
SD(fprintf(stderr, "[GPS] Not ublox!\n"));
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
||||
SD(fprintf(stderr, "[GPS] Sending ubx command: %i!\n", dataSize));
|
||||
gpsUbloxSendCommand(src->ptr, dataSize, 0);
|
||||
break;
|
||||
|
||||
|
@ -4145,7 +4147,6 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro
|
|||
// initialize reply by default
|
||||
reply->cmd = cmd->cmd;
|
||||
|
||||
SD(fprintf(stderr, "[MSP] CommandId: 0x%04x bytes: %i!\n", cmdMSP, sbufBytesRemaining(src)));
|
||||
if (MSP2_IS_SENSOR_MESSAGE(cmdMSP)) {
|
||||
ret = mspProcessSensorCommand(cmdMSP, src);
|
||||
} else if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) {
|
||||
|
|
|
@ -83,7 +83,7 @@ tables:
|
|||
values: ["NONE", "AGL", "FLOW_RAW", "FLOW", "ALWAYS", "SAG_COMP_VOLTAGE",
|
||||
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
|
||||
"NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "ALTITUDE",
|
||||
"AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST",
|
||||
"AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST",
|
||||
"ADAPTIVE_FILTER", "HEADTRACKER", "GPS", "LULU", "SBUS2"]
|
||||
- name: aux_operator
|
||||
values: ["OR", "AND"]
|
||||
|
@ -2548,7 +2548,7 @@ groups:
|
|||
min: 1
|
||||
max: 9
|
||||
- name: nav_fw_wp_tracking_accuracy
|
||||
description: "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."
|
||||
description: "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_value: 0
|
||||
field: fw.wp_tracking_accuracy
|
||||
min: 0
|
||||
|
|
|
@ -131,6 +131,11 @@ void gpsDistanceCmBearing(int32_t currentLat1, int32_t currentLon1, int32_t dest
|
|||
*bearing = wrap_36000(*bearing);
|
||||
};
|
||||
|
||||
bool adsbHeartbeat(void){
|
||||
adsbVehiclesStatus.heartbeatMessagesTotal++;
|
||||
return true;
|
||||
}
|
||||
|
||||
void adsbNewVehicle(adsbVehicleValues_t* vehicleValuesLocal) {
|
||||
|
||||
// no valid lat lon or altitude
|
||||
|
@ -139,6 +144,7 @@ void adsbNewVehicle(adsbVehicleValues_t* vehicleValuesLocal) {
|
|||
}
|
||||
|
||||
adsbVehiclesStatus.vehiclesMessagesTotal++;
|
||||
|
||||
adsbVehicle_t *vehicle = NULL;
|
||||
|
||||
vehicle = findVehicleByIcao(vehicleValuesLocal->icao);
|
||||
|
|
|
@ -54,9 +54,11 @@ typedef struct {
|
|||
|
||||
typedef struct {
|
||||
uint32_t vehiclesMessagesTotal;
|
||||
uint32_t heartbeatMessagesTotal;
|
||||
} adsbVehicleStatus_t;
|
||||
|
||||
void adsbNewVehicle(adsbVehicleValues_t* vehicleValuesLocal);
|
||||
bool adsbHeartbeat(void);
|
||||
adsbVehicle_t * findVehicleClosest(void);
|
||||
adsbVehicle_t * findVehicle(uint8_t index);
|
||||
uint8_t getActiveVehiclesCount(void);
|
||||
|
|
|
@ -63,11 +63,11 @@ static gimbalSerialHtrkState_t headTrackerState = {
|
|||
.attitude = {},
|
||||
.state = WAITING_HDR1,
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
static serialPort_t *headTrackerPort = NULL;
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
static serialPort_t *gimbalPort = NULL;
|
||||
|
||||
gimbalVTable_t gimbalSerialVTable = {
|
||||
|
@ -116,7 +116,9 @@ bool gimbalSerialIsReady(const gimbalDevice_t *gimbalDevice)
|
|||
bool gimbalSerialHasHeadTracker(const gimbalDevice_t *gimbalDevice)
|
||||
{
|
||||
UNUSED(gimbalDevice);
|
||||
return headTrackerPort || (gimbalSerialConfig()->singleUart && gimbalPort);
|
||||
|
||||
headTrackerDevice_t *htrk = headTrackerCommonDevice();
|
||||
return htrk != NULL && headTrackerCommonIsReady(htrk);
|
||||
}
|
||||
|
||||
bool gimbalSerialInit(void)
|
||||
|
@ -251,7 +253,7 @@ void gimbalSerialProcess(gimbalDevice_t *gimbalDevice, timeUs_t currentTime)
|
|||
#else
|
||||
{
|
||||
#endif
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 4, 0);
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 4, 2);
|
||||
// Radio endpoints may need to be adjusted, as it seems ot go a bit
|
||||
// bananas at the extremes
|
||||
attitude.pan = gimbal_scale12(PWM_RANGE_MIN, PWM_RANGE_MAX, panPWM);
|
||||
|
|
|
@ -30,10 +30,11 @@
|
|||
|
||||
#include "io/headtracker_msp.h"
|
||||
|
||||
static bool isReady = false;
|
||||
static headTrackerVTable_t headTrackerMspVTable = {
|
||||
.process = NULL,
|
||||
.getDeviceType = heatTrackerMspGetDeviceType,
|
||||
.isReady = NULL,
|
||||
.isReady = heatTrackerMspIsReady,
|
||||
.isValid = NULL,
|
||||
};
|
||||
|
||||
|
@ -52,12 +53,18 @@ void mspHeadTrackerInit(void)
|
|||
}
|
||||
}
|
||||
|
||||
void mspHeadTrackerReceiverNewData(uint8_t *data, int dataSize)
|
||||
void mspHeadTrackerReceiverNewData(uint8_t *data, unsigned int dataSize)
|
||||
{
|
||||
if(dataSize != sizeof(headtrackerMspMessage_t)) {
|
||||
SD(fprintf(stderr, "[headTracker]: invalid data size %d\n", dataSize));
|
||||
static int errorCount = 0;
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 7, errorCount++);
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 5, (sizeof(headtrackerMspMessage_t)));
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 6, dataSize);
|
||||
return;
|
||||
}
|
||||
isReady = true;
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 6, dataSize);
|
||||
|
||||
headtrackerMspMessage_t *status = (headtrackerMspMessage_t *)data;
|
||||
|
||||
|
@ -66,7 +73,10 @@ void mspHeadTrackerReceiverNewData(uint8_t *data, int dataSize)
|
|||
headTrackerMspDevice.roll = constrain(status->roll, HEADTRACKER_RANGE_MIN, HEADTRACKER_RANGE_MAX);
|
||||
headTrackerMspDevice.expires = micros() + MAX_HEADTRACKER_DATA_AGE_US;
|
||||
|
||||
UNUSED(status);
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 0, headTrackerMspDevice.pan);
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 1, headTrackerMspDevice.tilt);
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 2, headTrackerMspDevice.roll);
|
||||
DEBUG_SET(DEBUG_HEADTRACKING, 3, headTrackerMspDevice.expires);
|
||||
}
|
||||
|
||||
headTrackerDevType_e heatTrackerMspGetDeviceType(const headTrackerDevice_t *headTrackerDevice) {
|
||||
|
@ -74,4 +84,11 @@ headTrackerDevType_e heatTrackerMspGetDeviceType(const headTrackerDevice_t *head
|
|||
return HEADTRACKER_MSP;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
bool heatTrackerMspIsReady(const headTrackerDevice_t *headTrackerDevice)
|
||||
{
|
||||
UNUSED(headTrackerDevice);
|
||||
return headTrackerConfig()->devType == HEADTRACKER_MSP && isReady;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -37,8 +37,9 @@ typedef struct headtrackerMspMessage_s {
|
|||
|
||||
void mspHeadTrackerInit(void);
|
||||
|
||||
void mspHeadTrackerReceiverNewData(uint8_t *data, int dataSize);
|
||||
void mspHeadTrackerReceiverNewData(uint8_t *data, unsigned int dataSize);
|
||||
|
||||
headTrackerDevType_e heatTrackerMspGetDeviceType(const headTrackerDevice_t *headTrackerDevice);
|
||||
bool heatTrackerMspIsReady(const headTrackerDevice_t *headTrackerDevice);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -2136,7 +2136,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
case OSD_ADSB_INFO:
|
||||
{
|
||||
buff[0] = SYM_ADSB;
|
||||
if(getAdsbStatus()->vehiclesMessagesTotal > 0){
|
||||
if(getAdsbStatus()->vehiclesMessagesTotal > 0 || getAdsbStatus()->heartbeatMessagesTotal > 0){
|
||||
tfp_sprintf(buff + 1, "%2d", getActiveVehiclesCount());
|
||||
}else{
|
||||
buff[1] = '-';
|
||||
|
|
|
@ -173,10 +173,8 @@ static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c)
|
|||
case MSP_CHECKSUM_V1:
|
||||
if (mspPort->checksum1 == c) {
|
||||
mspPort->c_state = MSP_COMMAND_RECEIVED;
|
||||
SD(fprintf(stderr, "[MSPV1] Command received\n"));
|
||||
} else {
|
||||
mspPort->c_state = MSP_IDLE;
|
||||
SD(fprintf(stderr, "[MSPV1] Checksum error!\n"));
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -229,7 +227,6 @@ static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c)
|
|||
// Check for potential buffer overflow
|
||||
if (hdrv2->size > MSP_PORT_INBUF_SIZE) {
|
||||
mspPort->c_state = MSP_IDLE;
|
||||
SD(fprintf(stderr, "[MSPV2] Potential buffer overflow!\n"));
|
||||
}
|
||||
else {
|
||||
mspPort->dataSize = hdrv2->size;
|
||||
|
@ -253,9 +250,7 @@ static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c)
|
|||
case MSP_CHECKSUM_V2_NATIVE:
|
||||
if (mspPort->checksum2 == c) {
|
||||
mspPort->c_state = MSP_COMMAND_RECEIVED;
|
||||
SD(fprintf(stderr, "[MSPV2] command received!\n"));
|
||||
} else {
|
||||
SD(fprintf(stderr, "[MSPV2] Checksum error!\n"));
|
||||
mspPort->c_state = MSP_IDLE;
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -1859,6 +1859,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(nav
|
|||
case NAV_WP_ACTION_LAND:
|
||||
calculateAndSetActiveWaypoint(&posControl.waypointList[posControl.activeWaypointIndex]);
|
||||
posControl.wpInitialDistance = calculateDistanceToDestination(&posControl.activeWaypoint.pos);
|
||||
posControl.wpInitialAltitude = posControl.actualState.abs.pos.z;
|
||||
posControl.wpAltitudeReached = false;
|
||||
return NAV_FSM_EVENT_SUCCESS; // will switch to NAV_STATE_WAYPOINT_IN_PROGRESS
|
||||
|
||||
|
@ -1922,16 +1923,12 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na
|
|||
fpVector3_t tmpWaypoint;
|
||||
tmpWaypoint.x = posControl.activeWaypoint.pos.x;
|
||||
tmpWaypoint.y = posControl.activeWaypoint.pos.y;
|
||||
setDesiredPosition(&tmpWaypoint, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_BEARING);
|
||||
/* Use linear climb/descent between WPs arriving at WP altitude when within 10% of total distance to WP */
|
||||
tmpWaypoint.z = scaleRangef(constrainf(posControl.wpDistance, 0.1f * posControl.wpInitialDistance, posControl.wpInitialDistance),
|
||||
posControl.wpInitialDistance, 0.1f * posControl.wpInitialDistance,
|
||||
posControl.wpInitialAltitude, posControl.activeWaypoint.pos.z);
|
||||
|
||||
// Use linear climb between WPs arriving at WP altitude when within 10% of total distance to WP
|
||||
// Update climb rate until within 100cm of total climb xy distance to WP
|
||||
float climbRate = 0.0f;
|
||||
if (posControl.wpDistance - 0.1f * posControl.wpInitialDistance > 100.0f) {
|
||||
climbRate = posControl.actualState.velXY * (posControl.activeWaypoint.pos.z - posControl.actualState.abs.pos.z) /
|
||||
(posControl.wpDistance - 0.1f * posControl.wpInitialDistance);
|
||||
}
|
||||
updateClimbRateToAltitudeController(climbRate, posControl.activeWaypoint.pos.z, ROC_TO_ALT_TARGET);
|
||||
setDesiredPosition(&tmpWaypoint, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_BEARING);
|
||||
|
||||
if(STATE(MULTIROTOR)) {
|
||||
switch (wpHeadingControl.mode) {
|
||||
|
@ -3703,7 +3700,7 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData)
|
|||
setDesiredPosition(&wpPos.pos, DEGREES_TO_CENTIDEGREES(wpData->p1), waypointUpdateFlags);
|
||||
}
|
||||
// WP #1 - #NAV_MAX_WAYPOINTS - common waypoints - pre-programmed mission
|
||||
else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !FLIGHT_MODE(NAV_WP_MODE)) {
|
||||
else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !FLIGHT_MODE(NAV_WP_MODE)) {
|
||||
// WP upload is not allowed why WP mode is active
|
||||
if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) {
|
||||
// Only allow upload next waypoint (continue upload mission) or first waypoint (new mission)
|
||||
|
|
|
@ -399,38 +399,52 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta
|
|||
virtualTargetBearing = calculateBearingToDestination(&virtualDesiredPosition);
|
||||
}
|
||||
|
||||
/* If waypoint tracking enabled quickly force craft toward waypoint course line and closely track along it */
|
||||
if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) {
|
||||
// courseVirtualCorrection initially used to determine current position relative to course line for later use
|
||||
int32_t courseVirtualCorrection = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing);
|
||||
navCrossTrackError = ABS(posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(courseVirtualCorrection)));
|
||||
if (isWaypointNavTrackingActive()) {
|
||||
/* Calculate cross track error */
|
||||
posControl.wpDistance = calculateDistanceToDestination(&posControl.activeWaypoint.pos);
|
||||
|
||||
// tracking only active when certain distance and heading conditions are met
|
||||
if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200) {
|
||||
int32_t courseHeadingError = wrap_18000(posControl.activeWaypoint.bearing - posControl.actualState.cog);
|
||||
fpVector3_t virtualCoursePoint;
|
||||
virtualCoursePoint.x = posControl.activeWaypoint.pos.x -
|
||||
posControl.wpDistance * cos_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing));
|
||||
virtualCoursePoint.y = posControl.activeWaypoint.pos.y -
|
||||
posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(posControl.activeWaypoint.bearing));
|
||||
navCrossTrackError = calculateDistanceToDestination(&virtualCoursePoint);
|
||||
|
||||
// captureFactor adjusts distance/heading sensitivity balance when closing in on course line.
|
||||
// Closing distance threashold based on speed and an assumed 1 second response time.
|
||||
float captureFactor = navCrossTrackError < posControl.actualState.velXY ? constrainf(2.0f - ABS(courseHeadingError) / 500.0f, 0.0f, 2.0f) : 1.0f;
|
||||
/* If waypoint tracking enabled force craft toward and closely track along waypoint course line */
|
||||
if (navConfig()->fw.wp_tracking_accuracy && !needToCalculateCircularLoiter) {
|
||||
static float crossTrackErrorRate;
|
||||
static timeUs_t previousCrossTrackErrorUpdateTime;
|
||||
static float previousCrossTrackError = 0.0f;
|
||||
static pt1Filter_t fwCrossTrackErrorRateFilterState;
|
||||
|
||||
// bias between reducing distance to course line and aligning with course heading adjusted by waypoint_tracking_accuracy
|
||||
// initial courseCorrectionFactor based on distance to course line
|
||||
float courseCorrectionFactor = constrainf(captureFactor * navCrossTrackError / (1000.0f * navConfig()->fw.wp_tracking_accuracy), 0.0f, 1.0f);
|
||||
courseCorrectionFactor = courseVirtualCorrection < 0 ? -courseCorrectionFactor : courseCorrectionFactor;
|
||||
if ((currentTimeUs - previousCrossTrackErrorUpdateTime) >= HZ2US(20) && fabsf(previousCrossTrackError - navCrossTrackError) > 10.0f) {
|
||||
const float crossTrackErrorDtSec = US2S(currentTimeUs - previousCrossTrackErrorUpdateTime);
|
||||
if (fabsf(previousCrossTrackError - navCrossTrackError) < 500.0f) {
|
||||
crossTrackErrorRate = (previousCrossTrackError - navCrossTrackError) / crossTrackErrorDtSec;
|
||||
}
|
||||
crossTrackErrorRate = pt1FilterApply4(&fwCrossTrackErrorRateFilterState, crossTrackErrorRate, 3.0f, crossTrackErrorDtSec);
|
||||
previousCrossTrackErrorUpdateTime = currentTimeUs;
|
||||
previousCrossTrackError = navCrossTrackError;
|
||||
}
|
||||
|
||||
// course heading alignment factor
|
||||
float courseHeadingFactor = constrainf(courseHeadingError / 18000.0f, 0.0f, 1.0f);
|
||||
courseHeadingFactor = courseHeadingError < 0 ? -courseHeadingFactor : courseHeadingFactor;
|
||||
uint16_t trackingDeadband = METERS_TO_CENTIMETERS(navConfig()->fw.wp_tracking_accuracy);
|
||||
|
||||
// final courseCorrectionFactor combining distance and heading factors
|
||||
courseCorrectionFactor = constrainf(courseCorrectionFactor - courseHeadingFactor, -1.0f, 1.0f);
|
||||
if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.cog)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > trackingDeadband) {
|
||||
float adjustmentFactor = wrap_18000(posControl.activeWaypoint.bearing - virtualTargetBearing);
|
||||
uint16_t angleLimit = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle);
|
||||
|
||||
// final courseVirtualCorrection value
|
||||
courseVirtualCorrection = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle) * courseCorrectionFactor;
|
||||
virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - courseVirtualCorrection);
|
||||
/* Apply heading adjustment to match crossTrackErrorRate with fixed convergence speed profile */
|
||||
float maxApproachSpeed = posControl.actualState.velXY * sin_approx(CENTIDEGREES_TO_RADIANS(angleLimit));
|
||||
float desiredApproachSpeed = constrainf(navCrossTrackError / 3.0f, 50.0f, maxApproachSpeed);
|
||||
adjustmentFactor = SIGN(adjustmentFactor) * navCrossTrackError * ((desiredApproachSpeed - crossTrackErrorRate) / desiredApproachSpeed);
|
||||
|
||||
/* Calculate final adjusted virtualTargetBearing */
|
||||
uint16_t limit = constrainf(navCrossTrackError, 1000.0f, angleLimit);
|
||||
adjustmentFactor = constrainf(adjustmentFactor, -limit, limit);
|
||||
virtualTargetBearing = wrap_36000(posControl.activeWaypoint.bearing - adjustmentFactor);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Calculate NAV heading error
|
||||
* Units are centidegrees
|
||||
|
|
1
src/main/target/AIKONF7/CMakeLists.txt
Normal file
1
src/main/target/AIKONF7/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32f722xe(AIKONF7 SKIP_RELEASES)
|
60
src/main/target/AIKONF7/target.c
Normal file
60
src/main/target/AIKONF7/target.c
Normal file
|
@ -0,0 +1,60 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* This target has been autgenerated by bf2inav.py
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pinio.h"
|
||||
//#include "drivers/sensor.h"
|
||||
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM10, CH1, PB8, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
//DEF_TIM(TIM8, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0),
|
||||
|
||||
DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0),
|
||||
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
144
src/main/target/AIKONF7/target.h
Normal file
144
src/main/target/AIKONF7/target.h
Normal file
|
@ -0,0 +1,144 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* This target has been autgenerated by bf2inav.py
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
//#define USE_TARGET_CONFIG
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY )
|
||||
|
||||
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "RPTY"
|
||||
#define USBD_PRODUCT_STRING "AIKONF7"
|
||||
// Beeper
|
||||
#define USE_BEEPER
|
||||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
// Leds
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA15
|
||||
#define LED0 PC13
|
||||
// UARTs
|
||||
#define USB_IO
|
||||
#define USE_VCP
|
||||
#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
|
||||
// SPI
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA7
|
||||
#define SPI1_MOSI_PIN PA6
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB15
|
||||
#define SPI2_MOSI_PIN PC2
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB5
|
||||
#define SPI3_MOSI_PIN PB4
|
||||
// I2C
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C2_SCL PB10
|
||||
#define I2C2_SDA PB11
|
||||
// ADC
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
#define ADC_CHANNEL_3_PIN PC3
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
// Gyro & ACC
|
||||
#define USE_IMU_BMI270
|
||||
#define BMI270_CS_PIN PA4
|
||||
#define BMI270_SPI_BUS BUS_SPI1
|
||||
#define IMU_BMI270_ALIGN CW0_DEG
|
||||
#define USE_IMU_MPU6000
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define IMU_MPU6000_ALIGN CW0_DEG
|
||||
// BARO
|
||||
#define USE_BARO
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_SPI_BMP280
|
||||
#define BMP280_SPI_BUS BUS_SPI3
|
||||
#define BMP280_CS_PIN PB2
|
||||
// OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_CS_PIN PB12
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
// Blackbox
|
||||
#define USE_FLASHFS
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PB0
|
||||
#define USE_FLASH_W25M
|
||||
#define W25M_SPI_BUS BUS_SPI3
|
||||
#define W25M_CS_PIN PB0
|
||||
#define USE_FLASH_W25M02G
|
||||
#define W25M02G_SPI_BUS BUS_SPI3
|
||||
#define W25M02G_CS_PIN PB0
|
||||
#define USE_FLASH_W25M512
|
||||
#define W25M512_SPI_BUS BUS_SPI3
|
||||
#define W25M512_CS_PIN PB0
|
||||
#define USE_FLASH_W25N01G
|
||||
#define W25N01G_SPI_BUS BUS_SPI3
|
||||
#define W25N01G_CS_PIN PB0
|
||||
|
||||
// PINIO
|
||||
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PC14
|
||||
|
||||
|
||||
// Others
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
||||
#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 TARGET_IO_PORTF 0xffff
|
1
src/main/target/FLYWOOH743PRO/CMakeLists.txt
Normal file
1
src/main/target/FLYWOOH743PRO/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_stm32h743xi(FLYWOOH743PRO)
|
31
src/main/target/FLYWOOH743PRO/config.c
Normal file
31
src/main/target/FLYWOOH743PRO/config.c
Normal file
|
@ -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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "fc/fc_msp_box.h"
|
||||
#include "fc/config.h"
|
||||
|
||||
#include "io/piniobox.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
|
||||
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
|
||||
}
|
48
src/main/target/FLYWOOH743PRO/target.c
Normal file
48
src/main/target/FLYWOOH743PRO/target.c
Normal file
|
@ -0,0 +1,48 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pinio.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_1, DEVHW_ICM42605, ICM42605_1_SPI_BUS, ICM42605_1_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_2, DEVHW_ICM42605, ICM42605_2_SPI_BUS, ICM42605_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
|
||||
|
||||
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
|
||||
DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11
|
||||
DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S12
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
189
src/main/target/FLYWOOH743PRO/target.h
Normal file
189
src/main/target/FLYWOOH743PRO/target.h
Normal file
|
@ -0,0 +1,189 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "FWH7"
|
||||
#define USBD_PRODUCT_STRING "FLYWOOH743PRO"
|
||||
|
||||
#define USE_TARGET_CONFIG
|
||||
|
||||
#define LED0 PE3
|
||||
#define LED1 PE4
|
||||
|
||||
#define BEEPER PA15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// *************** IMU generic ***********************
|
||||
#define USE_DUAL_GYRO
|
||||
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
|
||||
|
||||
#define USE_IMU_ICM42605
|
||||
// *************** SPI1 IMU0 ICM42605_1 ****************
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PD7
|
||||
|
||||
#define IMU_ICM42605_ALIGN CW270_DEG
|
||||
#define ICM42605_1_SPI_BUS BUS_SPI1
|
||||
#define ICM42605_1_CS_PIN PC15
|
||||
|
||||
// *************** SPI4 IMU1 ICM42605_2 **************
|
||||
#define USE_SPI_DEVICE_4
|
||||
#define SPI4_SCK_PIN PE12
|
||||
#define SPI4_MISO_PIN PE13
|
||||
#define SPI4_MOSI_PIN PE14
|
||||
|
||||
#define IMU_ICM42605_ALIGN CW270_DEG
|
||||
#define ICM42605_2_SPI_BUS BUS_SPI4
|
||||
#define ICM42605_2_CS_PIN PE11
|
||||
|
||||
// *************** 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 SPARE for external RM3100 ***********
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define USE_MAG_RM3100
|
||||
#define RM3100_CS_PIN PE2 //CS2 pad
|
||||
#define RM3100_SPI_BUS BUS_SPI3
|
||||
|
||||
// *************** 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_I2C2
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define USE_BARO_DPS310
|
||||
#define USE_BARO_SPL06
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_ALL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C2
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
|
||||
#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 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
|
||||
|
||||
// *************** SDIO SD BLACKBOX*******************
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SDIO
|
||||
#define SDCARD_SDIO_DEVICE SDIODEV_1
|
||||
#define SDCARD_SDIO_4BIT
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
|
||||
#define ADC_CHANNEL_1_PIN PC0 //ADC123 VBAT1
|
||||
#define ADC_CHANNEL_2_PIN PC1 //ADC123 CURR1
|
||||
#define ADC_CHANNEL_3_PIN PC5 //ADC12 RSSI
|
||||
#define ADC_CHANNEL_4_PIN PC4 //ADC12 AirS
|
||||
#define ADC_CHANNEL_6_PIN PA7 //ADC12 CU2
|
||||
|
||||
#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
|
||||
|
||||
// *************** PINIO ***************************
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PD10 // VTX power switcher
|
||||
#define PINIO2_PIN PD11 // 2xCamera switcher
|
||||
|
||||
// *************** 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
|
||||
|
|
@ -1 +1,2 @@
|
|||
target_stm32f722xe(GEPRC_F722_AIO)
|
||||
target_stm32f722xe(GEPRC_F722_AIO_UART3)
|
||||
|
|
|
@ -17,7 +17,11 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef GEPRC_F722_AIO_UART3
|
||||
#define TARGET_BOARD_IDENTIFIER "GEP3"
|
||||
#else
|
||||
#define TARGET_BOARD_IDENTIFIER "GEPR"
|
||||
#endif
|
||||
|
||||
#define USBD_PRODUCT_STRING "GEPRC_F722_AIO"
|
||||
|
||||
|
@ -52,6 +56,7 @@
|
|||
#define ICM42605_SPI_BUS BUS_SPI1
|
||||
|
||||
// *************** I2C/Baro/Mag *********************
|
||||
#ifndef GEPRC_F722_AIO_UART3
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C2_SCL PB10
|
||||
|
@ -74,6 +79,7 @@
|
|||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C2
|
||||
#define BNO055_I2C_BUS BUS_I2C2
|
||||
#endif
|
||||
|
||||
// *************** FLASH **************************
|
||||
#define M25P16_CS_PIN PB9
|
||||
|
@ -108,9 +114,11 @@
|
|||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#ifdef GEPRC_F722_AIO_UART3
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
#endif
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PC11
|
||||
|
@ -120,7 +128,11 @@
|
|||
#define UART5_RX_PIN PD2
|
||||
#define UART5_TX_PIN PC12
|
||||
|
||||
#ifdef GEPRC_F722_AIO_UART3
|
||||
#define SERIAL_PORT_COUNT 6
|
||||
#else
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
#endif
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
|
|
@ -1 +1,2 @@
|
|||
target_stm32h743xi(IFLIGHT_BLITZ_H7_PRO)
|
||||
target_stm32h743xi(IFLIGHT_BLITZ_H7_PRO)
|
||||
target_stm32h743xi(IFLIGHT_BLITZ_H7_WING)
|
|
@ -20,7 +20,11 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "IB7P"
|
||||
|
||||
#ifdef IFLIGHT_BLITZ_H7_PRO
|
||||
#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_H7_PRO"
|
||||
#else
|
||||
#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_H7_WING"
|
||||
#endif
|
||||
|
||||
#define USE_TARGET_CONFIG
|
||||
|
||||
|
@ -161,7 +165,12 @@
|
|||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
|
||||
#define CURRENT_METER_SCALE 212
|
||||
#define VBAT_SCALE_DEFAULT 1135
|
||||
|
||||
#ifdef IFLIGHT_BLITZ_H7_PRO
|
||||
#define VBAT_SCALE_DEFAULT 2100
|
||||
#else
|
||||
#define VBAT_SCALE_DEFAULT 1100
|
||||
#endif
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "M72B"
|
||||
#define USBD_PRODUCT_STRING "MAMBAF722_2022B"
|
||||
#define USE_DSHOT_DMAR
|
||||
|
||||
#else
|
||||
|
||||
|
|
|
@ -144,8 +144,9 @@
|
|||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
#define USE_UART3_PIN_SWAP
|
||||
#define UART3_RX_PIN PB10
|
||||
#define UART3_TX_PIN PB11
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_RX_PIN PB8
|
||||
|
|
1
src/main/target/TBS_LUCID_FC/CMakeLists.txt
Normal file
1
src/main/target/TBS_LUCID_FC/CMakeLists.txt
Normal file
|
@ -0,0 +1 @@
|
|||
target_at32f43x_xMT7(TBS_LUCID_FC)
|
46
src/main/target/TBS_LUCID_FC/target.c
Normal file
46
src/main/target/TBS_LUCID_FC/target.c
Normal file
|
@ -0,0 +1,46 @@
|
|||
/*
|
||||
* 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 <stdint.h>
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "platform.h"
|
||||
|
||||
timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TMR3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1), // S1
|
||||
DEF_TIM(TMR3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 2), // S2
|
||||
DEF_TIM(TMR3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 3), // S3
|
||||
DEF_TIM(TMR3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 4), // S4
|
||||
|
||||
DEF_TIM(TMR4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 8), // S5
|
||||
DEF_TIM(TMR4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 9), // S6
|
||||
|
||||
DEF_TIM(TMR1, CH1, PA8, TIM_USE_LED, 0, 5), // LED Strip
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
151
src/main/target/TBS_LUCID_FC/target.h
Normal file
151
src/main/target/TBS_LUCID_FC/target.h
Normal file
|
@ -0,0 +1,151 @@
|
|||
/*
|
||||
* 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/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "LUFC"
|
||||
|
||||
#define USBD_PRODUCT_STRING "TBS Lucid FC"
|
||||
|
||||
#define LED0 PC14
|
||||
#define LED1 PC15
|
||||
|
||||
#define BEEPER_INVERTED
|
||||
#define BEEPER PC13
|
||||
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_TX_PIN NONE
|
||||
#define UART2_RX_PIN PB0
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_TX_PIN PB11
|
||||
#define UART3_RX_PIN PB10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PH3
|
||||
#define UART4_RX_PIN PH2
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_TX_PIN PB9
|
||||
#define UART5_RX_PIN PD2
|
||||
|
||||
#define USE_UART7
|
||||
#define UART7_TX_PIN PB4
|
||||
#define UART7_RX_PIN PB3
|
||||
|
||||
#define USE_UART8
|
||||
#define UART8_TX_PIN PC2
|
||||
#define UART8_RX_PIN PC3
|
||||
|
||||
#define SERIAL_PORT_COUNT 8
|
||||
|
||||
#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 PC12
|
||||
|
||||
#define USE_IMU_MPU6000
|
||||
#define IMU_MPU6000_ALIGN CW0_DEG_FLIP
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_CS_PIN PA4
|
||||
|
||||
#define USE_IMU_ICM42605
|
||||
#define IMU_ICM42605_ALIGN CW270_DEG_FLIP
|
||||
#define ICM42605_CS_PIN PA4
|
||||
#define ICM42605_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PA15
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB6
|
||||
#define I2C1_SDA PC7
|
||||
|
||||
#define USE_BARO
|
||||
#define USE_BARO_BMP388
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_MAG
|
||||
#define USE_MAG_ALL
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA8
|
||||
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PC5 // Camera Control
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_STREAM DMA2_CHANNEL7
|
||||
#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 TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2) | BIT(12) | BIT(13))
|
||||
#define TARGET_IO_PORTH (BIT(2) | BIT(3))
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define MAX_PWM_OUTPUT_PORTS 6
|
||||
|
||||
#define DEFAULT_FEATURES \
|
||||
(FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_OSD | \
|
||||
FEATURE_LED_STRIP)
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_CRSF
|
||||
#define SERIALRX_UART SERIAL_PORT_USART5
|
|
@ -1162,6 +1162,22 @@ static bool handleIncoming_RADIO_STATUS(void) {
|
|||
return true;
|
||||
}
|
||||
|
||||
static bool handleIncoming_HEARTBEAT(void) {
|
||||
mavlink_heartbeat_t msg;
|
||||
mavlink_msg_heartbeat_decode(&mavRecvMsg, &msg);
|
||||
|
||||
switch (msg.type) {
|
||||
#ifdef USE_ADSB
|
||||
case MAV_TYPE_ADSB:
|
||||
return adsbHeartbeat();
|
||||
#endif
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
#ifdef USE_ADSB
|
||||
static bool handleIncoming_ADSB_VEHICLE(void) {
|
||||
mavlink_adsb_vehicle_t msg;
|
||||
|
@ -1216,7 +1232,7 @@ static bool processMAVLinkIncomingTelemetry(void)
|
|||
if (result == MAVLINK_FRAMING_OK) {
|
||||
switch (mavRecvMsg.msgid) {
|
||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||
break;
|
||||
return handleIncoming_HEARTBEAT();
|
||||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||
return handleIncoming_PARAM_REQUEST_LIST();
|
||||
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
|
||||
|
|
|
@ -40,8 +40,8 @@ set_property(SOURCE osd_unittest.cc PROPERTY definitions OSD_UNIT_TEST USE_MSP_D
|
|||
set_property(SOURCE gps_ublox_unittest.cc PROPERTY depends "io/gps_ublox_utils.c")
|
||||
set_property(SOURCE gps_ublox_unittest.cc PROPERTY definitions GPS_UBLOX_UNIT_TEST)
|
||||
|
||||
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial.c" "drivers/gimbal_common.c" "common/maths.c")
|
||||
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST)
|
||||
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial.c" "drivers/gimbal_common.c" "common/maths.c" "drivers/headtracker_common.c")
|
||||
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST USE_HEADTRACKER)
|
||||
|
||||
function(unit_test src)
|
||||
get_filename_component(basename ${src} NAME)
|
||||
|
|
|
@ -34,6 +34,12 @@ void dumpMemory(uint8_t *mem, int size)
|
|||
printf("\n");
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
timeUs_t micros(void) {
|
||||
return 10;
|
||||
}
|
||||
}
|
||||
|
||||
TEST(GimbalSerialTest, TestGimbalSerialScale)
|
||||
{
|
||||
int16_t res16 = gimbal_scale12(1000, 2000, 2000);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue