1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 00:35:34 +03:00

Merge pull request #9355 from error414/adsb

Adsb support pingRX  / Aerobit TT-SC1
This commit is contained in:
Paweł Spychalski 2024-02-02 10:34:23 +01:00 committed by GitHub
commit bfdd1231ba
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
30 changed files with 735 additions and 17 deletions

1
.gitignore vendored
View file

@ -35,3 +35,4 @@ make/local.mk
launch.json launch.json
.vscode/tasks.json .vscode/tasks.json
.vscode/c_cpp_properties.json .vscode/c_cpp_properties.json
/cmake-build-debug/

17
docs/ADSB.md Normal file
View file

@ -0,0 +1,17 @@
# ADS-B
[Automatic Dependent Surveillance Broadcast](https://en.wikipedia.org/wiki/Automatic_Dependent_Surveillance%E2%80%93Broadcast)
is an air traffic surveillance technology that enables aircraft to be accurately tracked by air traffic controllers and other pilots without the need for conventional radar.
## Current state
OSD can be configured to shows the closest aircraft.
## Hardware
All ADSB receivers which can send Mavlink [ADSB_VEHICLE](https://mavlink.io/en/messages/common.html#ADSB_VEHICLE) message are supported
* [PINGRX](https://uavionix.com/product/pingrx-pro/) (not tested)
* [TT-SC1](https://www.aerobits.pl/product/aero/) (tested)

View file

@ -104,6 +104,9 @@ TailSitter is supported by add a 90deg offset to the board alignment. Set the bo
- Rate Settings - Rate Settings
- ······· - ·······
### TailSitter support
TailSitter is supported by add a 90deg offset to the board alignment. Set the board aliment normally in the mixer_profile for FW mode(`set platform_type = AIRPLANE`), The motor trust axis should be same direction as the airplane nose. Then, in the mixer_profile for takeoff and landing `set platform_type = TAILSITTER`. The `TAILSITTER` platform type is same as `MULTIROTOR` platform type, expect for a 90 deg board alignment offset. In `TAILSITTER` mixer_profile, when motor trust/airplane nose is pointing to the sky, 'airplane bottom'/'multi rotor front' should facing forward in model preview. Set the motor/servo mixer according to multirotor orientation, Model should roll around geography's longitudinal axis, the roll axis of `TAILSITTER` will be yaw axis of `AIRPLANE`. In addition, When `MIXER TRANSITION` input is activated, a 45deg offset will be add to the target angle for angle mode.
## Happy flying ## Happy flying
Remember that this is currently an emerging capability: Remember that this is currently an emerging capability:

View file

@ -4032,6 +4032,36 @@ _// TODO_
--- ---
### osd_adsb_distance_alert
Distance inside which ADSB data flashes for proximity warning
| Default | Min | Max |
| --- | --- | --- |
| 3000 | 1 | 64000 |
---
### osd_adsb_distance_warning
Distance in meters of ADSB aircraft that is displayed
| Default | Min | Max |
| --- | --- | --- |
| 20000 | 1 | 64000 |
---
### osd_adsb_ignore_plane_above_me_limit
Ignore adsb planes above, limit, 0 disabled (meters)
| Default | Min | Max |
| --- | --- | --- |
| 0 | 0 | 64000 |
---
### osd_ahi_bordered ### osd_ahi_bordered
Shows a border/corners around the AHI region (pixel OSD only) Shows a border/corners around the AHI region (pixel OSD only)
@ -5812,6 +5842,16 @@ Delay before disarming when requested by switch (ms) [0-1000]
--- ---
### tailsitter_orientation_offset
Apply a 90 deg pitch offset in sensor aliment for tailsitter flying mode
| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |
---
### telemetry_halfduplex ### telemetry_halfduplex
S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details

View file

@ -343,6 +343,12 @@ static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *
len--; len--;
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[2] = hmsc->bot_data[2] | (1 << 7);
}
return 0; return 0;
} }
@ -365,6 +371,12 @@ static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
len--; len--;
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[3] = hmsc->bot_data[3] | (1 << 7);
}
return 0; return 0;
} }

View file

@ -347,6 +347,12 @@ static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *
len--; len--;
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[2] = hmsc->bot_data[2] | (1 << 7);
}
return 0; return 0;
} }
@ -370,6 +376,12 @@ static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
len--; len--;
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[3] = hmsc->bot_data[3] | (1 << 7);
}
return 0; return 0;
} }

View file

@ -346,6 +346,12 @@ static int8_t SCSI_ModeSense6(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *p
len--; len--;
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[2] = hmsc->bot_data[2] | (1 << 7);
}
return 0; return 0;
} }
@ -371,6 +377,11 @@ static int8_t SCSI_ModeSense10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
} }
// set bit 7 of the device configuration byte to indicate write protection
if (((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) != 0) {
hmsc->bot_data[3] = hmsc->bot_data[3] | (1 << 7);
}
return 0; return 0;
} }

View file

@ -344,6 +344,7 @@ main_sources(COMMON_SRC
flight/ez_tune.c flight/ez_tune.c
flight/ez_tune.h flight/ez_tune.h
io/adsb.c
io/beeper.c io/beeper.c
io/beeper.h io/beeper.h
io/servo_sbus.c io/servo_sbus.c

View file

@ -180,6 +180,8 @@
#define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error #define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error
#define SYM_ADSB 0xFD // 253 ADSB
#define SYM_LOGO_START 0x101 // 257 to 297, INAV logo #define SYM_LOGO_START 0x101 // 257 to 297, INAV logo
#define SYM_LOGO_WIDTH 10 #define SYM_LOGO_WIDTH 10
#define SYM_LOGO_HEIGHT 4 #define SYM_LOGO_HEIGHT 4

View file

@ -83,6 +83,7 @@
#include "config/config_eeprom.h" #include "config/config_eeprom.h"
#include "config/feature.h" #include "config/feature.h"
#include "io/adsb.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/gps.h" #include "io/gps.h"
@ -948,6 +949,33 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, gpsSol.epv); sbufWriteU16(dst, gpsSol.epv);
break; break;
#endif #endif
case MSP2_ADSB_VEHICLE_LIST:
#ifdef USE_ADSB
sbufWriteU8(dst, MAX_ADSB_VEHICLES);
sbufWriteU8(dst, ADSB_CALL_SIGN_MAX_LENGTH);
for(uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++){
adsbVehicle_t *adsbVehicle = findVehicle(i);
for(uint8_t ii = 0; ii < ADSB_CALL_SIGN_MAX_LENGTH; ii++){
sbufWriteU8(dst, adsbVehicle->vehicleValues.callsign[ii]);
}
sbufWriteU32(dst, adsbVehicle->vehicleValues.icao);
sbufWriteU32(dst, adsbVehicle->vehicleValues.lat);
sbufWriteU32(dst, adsbVehicle->vehicleValues.lon);
sbufWriteU32(dst, adsbVehicle->vehicleValues.alt);
sbufWriteU16(dst, (uint16_t)CENTIDEGREES_TO_DEGREES(adsbVehicle->vehicleValues.heading));
sbufWriteU8(dst, adsbVehicle->vehicleValues.tslc);
sbufWriteU8(dst, adsbVehicle->vehicleValues.emitterType);
sbufWriteU8(dst, adsbVehicle->ttl);
}
#else
sbufWriteU8(dst, 0);
sbufWriteU8(dst, 0);
#endif
break;
case MSP_DEBUG: case MSP_DEBUG:
// output some useful QA statistics // output some useful QA statistics
// debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock] // debug[x] = ((hse_value / 1000000) * 1000) + (SystemCoreClock / 1000000); // XX0YY [crystal clock : core clock]
@ -1518,6 +1546,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#else #else
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
#endif
#ifdef USE_ADSB
sbufWriteU16(dst, osdConfig()->adsb_distance_warning);
sbufWriteU16(dst, osdConfig()->adsb_distance_alert);
#else
sbufWriteU16(dst, 0);
sbufWriteU16(dst, 0);
#endif #endif
break; break;

View file

@ -69,6 +69,7 @@
#include "io/osd_dji_hd.h" #include "io/osd_dji_hd.h"
#include "io/displayport_msp_osd.h" #include "io/displayport_msp_osd.h"
#include "io/servo_sbus.h" #include "io/servo_sbus.h"
#include "io/adsb.h"
#include "msp/msp_serial.h" #include "msp/msp_serial.h"
@ -181,6 +182,14 @@ void taskUpdateCompass(timeUs_t currentTimeUs)
} }
#endif #endif
#ifdef USE_ADSB
void taskAdsb(timeUs_t currentTimeUs)
{
UNUSED(currentTimeUs);
adsbTtlClean(currentTimeUs);
}
#endif
#ifdef USE_BARO #ifdef USE_BARO
void taskUpdateBaro(timeUs_t currentTimeUs) void taskUpdateBaro(timeUs_t currentTimeUs)
{ {
@ -360,6 +369,9 @@ void fcTasksInit(void)
#ifdef USE_PITOT #ifdef USE_PITOT
setTaskEnabled(TASK_PITOT, sensors(SENSOR_PITOT)); setTaskEnabled(TASK_PITOT, sensors(SENSOR_PITOT));
#endif #endif
#ifdef USE_ADSB
setTaskEnabled(TASK_ADSB, true);
#endif
#ifdef USE_RANGEFINDER #ifdef USE_RANGEFINDER
setTaskEnabled(TASK_RANGEFINDER, sensors(SENSOR_RANGEFINDER)); setTaskEnabled(TASK_RANGEFINDER, sensors(SENSOR_RANGEFINDER));
#endif #endif
@ -495,6 +507,15 @@ cfTask_t cfTasks[TASK_COUNT] = {
}, },
#endif #endif
#ifdef USE_ADSB
[TASK_ADSB] = {
.taskName = "ADSB",
.taskFunc = taskAdsb,
.desiredPeriod = TASK_PERIOD_HZ(1), // ADSB is updated at 1 Hz
.staticPriority = TASK_PRIORITY_IDLE,
},
#endif
#ifdef USE_BARO #ifdef USE_BARO
[TASK_BARO] = { [TASK_BARO] = {
.taskName = "BARO", .taskName = "BARO",

View file

@ -144,6 +144,7 @@ typedef enum {
ANTI_WINDUP_DEACTIVATED = (1 << 25), ANTI_WINDUP_DEACTIVATED = (1 << 25),
LANDING_DETECTED = (1 << 26), LANDING_DETECTED = (1 << 26),
IN_FLIGHT_EMERG_REARM = (1 << 27), IN_FLIGHT_EMERG_REARM = (1 << 27),
TAILSITTER = (1 << 28), //offset the pitch angle by 90 degrees
} stateFlags_t; } stateFlags_t;
#define DISABLE_STATE(mask) (stateFlags &= ~(mask)) #define DISABLE_STATE(mask) (stateFlags &= ~(mask))

View file

@ -1191,6 +1191,11 @@ groups:
field: mixer_config.switchTransitionTimer field: mixer_config.switchTransitionTimer
min: 0 min: 0
max: 200 max: 200
- name: tailsitter_orientation_offset
description: "Apply a 90 deg pitch offset in sensor aliment for tailsitter flying mode"
default_value: OFF
field: mixer_config.tailsitterOrientationOffset
type: bool
@ -3457,6 +3462,31 @@ groups:
max: 11 max: 11
default_value: 9 default_value: 9
- name: osd_adsb_distance_warning
description: "Distance in meters of ADSB aircraft that is displayed"
default_value: 20000
condition: USE_ADSB
field: adsb_distance_warning
min: 1
max: 64000
type: uint16_t
- name: osd_adsb_distance_alert
description: "Distance inside which ADSB data flashes for proximity warning"
default_value: 3000
condition: USE_ADSB
field: adsb_distance_alert
min: 1
max: 64000
type: uint16_t
- name: osd_adsb_ignore_plane_above_me_limit
description: "Ignore adsb planes above, limit, 0 disabled (meters)"
default_value: 0
condition: USE_ADSB
field: adsb_ignore_plane_above_me_limit
min: 0
max: 64000
type: uint16_t
- name: osd_estimations_wind_compensation - name: osd_estimations_wind_compensation
description: "Use wind estimation for remaining flight time/distance estimation" description: "Use wind estimation for remaining flight time/distance estimation"
default_value: ON default_value: ON

View file

@ -704,6 +704,33 @@ static void imuCalculateTurnRateacceleration(fpVector3_t *vEstcentrifugalAccelBF
lastspeed = currentspeed; lastspeed = currentspeed;
} }
fpQuaternion_t* getTailSitterQuaternion(bool normal2tail){
static bool firstRun = true;
static fpQuaternion_t qNormal2Tail;
static fpQuaternion_t qTail2Normal;
if(firstRun){
fpAxisAngle_t axisAngle;
axisAngle.axis.x = 0;
axisAngle.axis.y = 1;
axisAngle.axis.z = 0;
axisAngle.angle = DEGREES_TO_RADIANS(-90);
axisAngleToQuaternion(&qNormal2Tail, &axisAngle);
quaternionConjugate(&qTail2Normal, &qNormal2Tail);
firstRun = false;
}
return normal2tail ? &qNormal2Tail : &qTail2Normal;
}
void imuUpdateTailSitter(void)
{
static bool lastTailSitter=false;
if (((bool)STATE(TAILSITTER)) != lastTailSitter){
fpQuaternion_t* rotation_for_tailsitter= getTailSitterQuaternion(STATE(TAILSITTER));
quaternionMultiply(&orientation, &orientation, rotation_for_tailsitter);
}
lastTailSitter = STATE(TAILSITTER);
}
static void imuCalculateEstimatedAttitude(float dT) static void imuCalculateEstimatedAttitude(float dT)
{ {
#if defined(USE_MAG) #if defined(USE_MAG)
@ -800,6 +827,7 @@ static void imuCalculateEstimatedAttitude(float dT)
useCOG, courseOverGround, useCOG, courseOverGround,
accWeight, accWeight,
magWeight); magWeight);
imuUpdateTailSitter();
imuUpdateEulerAngles(); imuUpdateEulerAngles();
} }

View file

@ -161,6 +161,7 @@ void mixerUpdateStateFlags(void)
DISABLE_STATE(BOAT); DISABLE_STATE(BOAT);
DISABLE_STATE(AIRPLANE); DISABLE_STATE(AIRPLANE);
DISABLE_STATE(MOVE_FORWARD_ONLY); DISABLE_STATE(MOVE_FORWARD_ONLY);
DISABLE_STATE(TAILSITTER);
if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) { if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) {
ENABLE_STATE(FIXED_WING_LEGACY); ENABLE_STATE(FIXED_WING_LEGACY);
@ -186,6 +187,12 @@ void mixerUpdateStateFlags(void)
ENABLE_STATE(ALTITUDE_CONTROL); ENABLE_STATE(ALTITUDE_CONTROL);
} }
if (currentMixerConfig.tailsitterOrientationOffset) {
ENABLE_STATE(TAILSITTER);
} else {
DISABLE_STATE(TAILSITTER);
}
if (currentMixerConfig.hasFlaps) { if (currentMixerConfig.hasFlaps) {
ENABLE_STATE(FLAPERON_AVAILABLE); ENABLE_STATE(FLAPERON_AVAILABLE);
} else { } else {

View file

@ -53,6 +53,7 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance)
.PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT, .PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT,
.automated_switch = SETTING_MIXER_AUTOMATED_SWITCH_DEFAULT, .automated_switch = SETTING_MIXER_AUTOMATED_SWITCH_DEFAULT,
.switchTransitionTimer = SETTING_MIXER_SWITCH_TRANS_TIMER_DEFAULT, .switchTransitionTimer = SETTING_MIXER_SWITCH_TRANS_TIMER_DEFAULT,
.tailsitterOrientationOffset = SETTING_TAILSITTER_ORIENTATION_OFFSET_DEFAULT,
}); });
for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++)
{ {

View file

@ -18,6 +18,7 @@ typedef struct mixerConfig_s {
bool PIDProfileLinking; bool PIDProfileLinking;
bool automated_switch; bool automated_switch;
int16_t switchTransitionTimer; int16_t switchTransitionTimer;
bool tailsitterOrientationOffset;
} mixerConfig_t; } mixerConfig_t;
typedef struct mixerProfile_s { typedef struct mixerProfile_s {
mixerConfig_t mixer_config; mixerConfig_t mixer_config;

View file

@ -586,7 +586,11 @@ int16_t angleFreefloatDeadband(int16_t deadband, flight_dynamics_index_t axis)
static float computePidLevelTarget(flight_dynamics_index_t axis) { static float computePidLevelTarget(flight_dynamics_index_t axis) {
// This is ROLL/PITCH, run ANGLE/HORIZON controllers // This is ROLL/PITCH, run ANGLE/HORIZON controllers
#ifdef USE_PROGRAMMING_FRAMEWORK
float angleTarget = pidRcCommandToAngle(getRcCommandOverride(rcCommand, axis), pidProfile()->max_angle_inclination[axis]);
#else
float angleTarget = pidRcCommandToAngle(rcCommand[axis], pidProfile()->max_angle_inclination[axis]); float angleTarget = pidRcCommandToAngle(rcCommand[axis], pidProfile()->max_angle_inclination[axis]);
#endif
// Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle // Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle
if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) { if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) {
@ -1142,7 +1146,6 @@ void FAST_CODE pidController(float dT)
} }
for (int axis = 0; axis < 3; axis++) { for (int axis = 0; axis < 3; axis++) {
// Step 1: Calculate gyro rates
pidState[axis].gyroRate = gyro.gyroADCf[axis]; pidState[axis].gyroRate = gyro.gyroADCf[axis];
// Step 2: Read target // Step 2: Read target
@ -1179,6 +1182,11 @@ void FAST_CODE pidController(float dT)
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || FLIGHT_MODE(ANGLEHOLD_MODE) || isFlightAxisAngleOverrideActive(axis)) { if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || FLIGHT_MODE(ANGLEHOLD_MODE) || isFlightAxisAngleOverrideActive(axis)) {
// If axis angle override, get the correct angle from Logic Conditions // If axis angle override, get the correct angle from Logic Conditions
float angleTarget = getFlightAxisAngleOverride(axis, computePidLevelTarget(axis)); float angleTarget = getFlightAxisAngleOverride(axis, computePidLevelTarget(axis));
//apply 45 deg offset for tailsitter when isMixerTransitionMixing is activated
if (STATE(TAILSITTER) && isMixerTransitionMixing && axis == FD_PITCH){
angleTarget += DEGREES_TO_DECIDEGREES(45);
}
if (STATE(AIRPLANE)) { // update anglehold mode if (STATE(AIRPLANE)) { // update anglehold mode
updateAngleHold(&angleTarget, axis); updateAngleHold(&angleTarget, axis);

223
src/main/io/adsb.c Normal file
View file

@ -0,0 +1,223 @@
/*
* 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 <string.h>
#include "adsb.h"
#include "navigation/navigation.h"
#include "navigation/navigation_private.h"
#include "common/maths.h"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
#include "common/mavlink.h"
#pragma GCC diagnostic pop
#include "math.h"
#ifdef USE_ADSB
adsbVehicle_t adsbVehiclesList[MAX_ADSB_VEHICLES];
adsbVehicleStatus_t adsbVehiclesStatus;
adsbVehicleValues_t vehicleValues;
adsbVehicleValues_t* getVehicleForFill(void){
return &vehicleValues;
}
// use bsearch function
adsbVehicle_t *findVehicleByIcao(uint32_t avicao) {
for (uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++) {
if (avicao == adsbVehiclesList[i].vehicleValues.icao) {
return &adsbVehiclesList[i];
}
}
return NULL;
}
adsbVehicle_t *findVehicleFarthest(void) {
adsbVehicle_t *adsbLocal = NULL;
for (uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++) {
if (adsbVehiclesList[i].ttl > 0 && adsbVehiclesList[i].calculatedVehicleValues.valid && (adsbLocal == NULL || adsbLocal->calculatedVehicleValues.dist < adsbVehiclesList[i].calculatedVehicleValues.dist)) {
adsbLocal = &adsbVehiclesList[i];
}
}
return adsbLocal;
}
uint8_t getActiveVehiclesCount(void) {
uint8_t total = 0;
for (uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++) {
if (adsbVehiclesList[i].ttl > 0) {
total++;
}
}
return total;
}
adsbVehicle_t *findVehicleClosest(void) {
adsbVehicle_t *adsbLocal = NULL;
for (uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++) {
if (adsbVehiclesList[i].ttl > 0 && adsbVehiclesList[i].calculatedVehicleValues.valid && (adsbLocal == NULL || adsbLocal->calculatedVehicleValues.dist > adsbVehiclesList[i].calculatedVehicleValues.dist)) {
adsbLocal = &adsbVehiclesList[i];
}
}
return adsbLocal;
}
adsbVehicle_t *findFreeSpaceInList(void) {
//find expired first
for (uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++) {
if (adsbVehiclesList[i].ttl == 0) {
return &adsbVehiclesList[i];
}
}
return NULL;
}
adsbVehicle_t *findVehicleNotCalculated(void) {
//find expired first
for (uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++) {
if (adsbVehiclesList[i].calculatedVehicleValues.valid == false) {
return &adsbVehiclesList[i];
}
}
return NULL;
}
adsbVehicle_t* findVehicle(uint8_t index)
{
if (index < MAX_ADSB_VEHICLES){
return &adsbVehiclesList[index];
}
return NULL;
}
adsbVehicleStatus_t* getAdsbStatus(void){
return &adsbVehiclesStatus;
}
void gpsDistanceCmBearing(int32_t currentLat1, int32_t currentLon1, int32_t destinationLat2, int32_t destinationLon2, uint32_t *dist, int32_t *bearing) {
float GPS_scaleLonDown = cos_approx((fabsf((float) gpsSol.llh.lat) / 10000000.0f) * 0.0174532925f);
const float dLat = destinationLat2 - currentLat1; // difference of latitude in 1/10 000 000 degrees
const float dLon = (float) (destinationLon2 - currentLon1) * GPS_scaleLonDown;
*dist = sqrtf(sq(dLat) + sq(dLon)) * DISTANCE_BETWEEN_TWO_LONGITUDE_POINTS_AT_EQUATOR;
*bearing = 9000.0f + RADIANS_TO_CENTIDEGREES(atan2_approx(-dLat, dLon)); // Convert the output radians to 100xdeg
*bearing = wrap_36000(*bearing);
};
void adsbNewVehicle(adsbVehicleValues_t* vehicleValuesLocal) {
// no valid lat lon or altitude
if((vehicleValuesLocal->flags & (ADSB_FLAGS_VALID_ALTITUDE | ADSB_FLAGS_VALID_COORDS)) != (ADSB_FLAGS_VALID_ALTITUDE | ADSB_FLAGS_VALID_COORDS)){
return;
}
adsbVehiclesStatus.vehiclesMessagesTotal++;
adsbVehicle_t *vehicle = NULL;
vehicle = findVehicleByIcao(vehicleValuesLocal->icao);
if(vehicle != NULL && vehicleValuesLocal->tslc > ADSB_MAX_SECONDS_KEEP_INACTIVE_PLANE_IN_LIST){
vehicle->ttl = 0;
return;
}
// non GPS mode, GPS is not fix, just find free space in list or by icao and save vehicle without calculated values
if (!enviromentOkForCalculatingDistaceBearing()) {
if(vehicle == NULL){
vehicle = findFreeSpaceInList();
}
if (vehicle != NULL) {
memcpy(&(vehicle->vehicleValues), vehicleValuesLocal, sizeof(vehicle->vehicleValues));
vehicle->ttl = ADSB_MAX_SECONDS_KEEP_INACTIVE_PLANE_IN_LIST;
vehicle->calculatedVehicleValues.valid = false;
return;
}
} else {
// GPS mode, GPS is fixed and has enough sats
if(vehicle == NULL){
vehicle = findFreeSpaceInList();
}
if(vehicle == NULL){
vehicle = findVehicleNotCalculated();
}
if(vehicle == NULL){
vehicle = findVehicleFarthest();
}
if (vehicle != NULL) {
memcpy(&(vehicle->vehicleValues), vehicleValuesLocal, sizeof(vehicle->vehicleValues));
recalculateVehicle(vehicle);
vehicle->ttl = ADSB_MAX_SECONDS_KEEP_INACTIVE_PLANE_IN_LIST;
return;
}
}
};
void recalculateVehicle(adsbVehicle_t* vehicle){
gpsDistanceCmBearing(gpsSol.llh.lat, gpsSol.llh.lon, vehicle->vehicleValues.lat, vehicle->vehicleValues.lon, &(vehicle->calculatedVehicleValues.dist), &(vehicle->calculatedVehicleValues.dir));
if (vehicle != NULL && vehicle->calculatedVehicleValues.dist > ADSB_LIMIT_CM) {
vehicle->ttl = 0;
return;
}
vehicle->calculatedVehicleValues.verticalDistance = vehicle->vehicleValues.alt - (int32_t)getEstimatedActualPosition(Z) - GPS_home.alt;
vehicle->calculatedVehicleValues.valid = true;
}
void adsbTtlClean(timeUs_t currentTimeUs) {
static timeUs_t adsbTtlLastCleanServiced = 0;
timeDelta_t adsbTtlSinceLastCleanServiced = cmpTimeUs(currentTimeUs, adsbTtlLastCleanServiced);
if (adsbTtlSinceLastCleanServiced > 1000000) // 1s
{
for (uint8_t i = 0; i < MAX_ADSB_VEHICLES; i++) {
if (adsbVehiclesList[i].ttl > 0) {
adsbVehiclesList[i].ttl--;
}
}
adsbTtlLastCleanServiced = currentTimeUs;
}
};
bool enviromentOkForCalculatingDistaceBearing(void){
return (STATE(GPS_FIX) && gpsSol.numSat > 4);
}
#endif

67
src/main/io/adsb.h Normal file
View file

@ -0,0 +1,67 @@
/*
* 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/>.
*/
#pragma once
#include <stdint.h>
#include "common/time.h"
#include "fc/runtime_config.h"
#define ADSB_CALL_SIGN_MAX_LENGTH 9
#define ADSB_MAX_SECONDS_KEEP_INACTIVE_PLANE_IN_LIST 10
typedef struct {
bool valid;
int32_t dir; // centidegrees direction to plane, pivot is inav FC
uint32_t dist; // CM distance to plane, pivot is inav FC
int32_t verticalDistance; // CM, vertical distance to plane, pivot is inav FC
} adsbVehicleCalculatedValues_t;
typedef struct {
uint32_t icao; // ICAO address
int32_t lat; // Latitude, expressed as degrees * 1E7
int32_t lon; // Longitude, expressed as degrees * 1E7
int32_t alt; // Barometric/Geometric Altitude (ASL), in cm
uint16_t heading; // Course over ground in centidegrees
uint16_t flags; // Flags to indicate various statuses including valid data fields
uint8_t altitudeType; // Type from ADSB_ALTITUDE_TYPE enum
char callsign[ADSB_CALL_SIGN_MAX_LENGTH]; // The callsign, 8 chars + NULL
uint8_t emitterType; // Type from ADSB_EMITTER_TYPE enum
uint8_t tslc; // Time since last communication in seconds
} adsbVehicleValues_t;
typedef struct {
adsbVehicleValues_t vehicleValues;
adsbVehicleCalculatedValues_t calculatedVehicleValues;
uint8_t ttl;
} adsbVehicle_t;
typedef struct {
uint32_t vehiclesMessagesTotal;
} adsbVehicleStatus_t;
void adsbNewVehicle(adsbVehicleValues_t* vehicleValuesLocal);
adsbVehicle_t * findVehicleClosest(void);
adsbVehicle_t * findVehicle(uint8_t index);
uint8_t getActiveVehiclesCount(void);
void adsbTtlClean(timeUs_t currentTimeUs);
adsbVehicleStatus_t* getAdsbStatus(void);
adsbVehicleValues_t* getVehicleForFill(void);
bool enviromentOkForCalculatingDistaceBearing(void);
void recalculateVehicle(adsbVehicle_t* vehicle);

View file

@ -578,6 +578,48 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page)
case (SYM_AH_V_START+4): case (SYM_AH_V_START+4):
case (SYM_AH_V_START+5): case (SYM_AH_V_START+5):
return BF_SYM_AH_BAR9_4; return BF_SYM_AH_BAR9_4;
// BF for ESP_RADAR Symbols
case SYM_HUD_CARDINAL:
return BF_SYM_ARROW_SOUTH;
case SYM_HUD_CARDINAL + 1:
return BF_SYM_ARROW_16;
case SYM_HUD_CARDINAL + 2:
return BF_SYM_ARROW_15;
case SYM_HUD_CARDINAL + 3:
return BF_SYM_ARROW_WEST;
case SYM_HUD_CARDINAL + 4:
return BF_SYM_ARROW_12;
case SYM_HUD_CARDINAL + 5:
return BF_SYM_ARROW_11;
case SYM_HUD_CARDINAL + 6:
return BF_SYM_ARROW_NORTH;
case SYM_HUD_CARDINAL + 7:
return BF_SYM_ARROW_7;
case SYM_HUD_CARDINAL + 8:
return BF_SYM_ARROW_6;
case SYM_HUD_CARDINAL + 9:
return BF_SYM_ARROW_EAST;
case SYM_HUD_CARDINAL + 10:
return BF_SYM_ARROW_3;
case SYM_HUD_CARDINAL + 11:
return BF_SYM_ARROW_2;
case SYM_HUD_ARROWS_R3:
return BF_SYM_AH_RIGHT;
case SYM_HUD_ARROWS_L3:
return BF_SYM_AH_LEFT;
case SYM_HUD_SIGNAL_0:
return BF_SYM_AH_BAR9_1;
case SYM_HUD_SIGNAL_1:
return BF_SYM_AH_BAR9_3;
case SYM_HUD_SIGNAL_2:
return BF_SYM_AH_BAR9_4;
case SYM_HUD_SIGNAL_3:
return BF_SYM_AH_BAR9_5;
case SYM_HUD_SIGNAL_4:
return BF_SYM_AH_BAR9_7;
/* /*
case SYM_VARIO_UP_2A: case SYM_VARIO_UP_2A:
return BF_SYM_VARIO_UP_2A; return BF_SYM_VARIO_UP_2A;

View file

@ -62,6 +62,7 @@
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/vtx_common.h" #include "drivers/vtx_common.h"
#include "io/adsb.h"
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/osd.h" #include "io/osd.h"
@ -2085,7 +2086,73 @@ static bool osdDrawSingleElement(uint8_t item)
osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits, false); osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits, false);
break; break;
} }
#ifdef USE_ADSB
case OSD_ADSB_WARNING:
{
static uint8_t adsblen = 1;
uint8_t arrowPositionX = 0;
for (int i = 0; i <= adsblen; i++) {
buff[i] = SYM_BLANK;
}
buff[adsblen]='\0';
displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); // clear any previous chars because variable element size
adsblen=1;
adsbVehicle_t *vehicle = findVehicleClosest();
if(vehicle != NULL){
recalculateVehicle(vehicle);
}
if (
vehicle != NULL &&
(vehicle->calculatedVehicleValues.dist > 0) &&
vehicle->calculatedVehicleValues.dist < METERS_TO_CENTIMETERS(osdConfig()->adsb_distance_warning) &&
(osdConfig()->adsb_ignore_plane_above_me_limit == 0 || METERS_TO_CENTIMETERS(osdConfig()->adsb_ignore_plane_above_me_limit) > vehicle->calculatedVehicleValues.verticalDistance)
){
buff[0] = SYM_ADSB;
osdFormatDistanceStr(&buff[1], (int32_t)vehicle->calculatedVehicleValues.dist);
adsblen = strlen(buff);
buff[adsblen-1] = SYM_BLANK;
arrowPositionX = adsblen-1;
osdFormatDistanceStr(&buff[adsblen], vehicle->calculatedVehicleValues.verticalDistance);
adsblen = strlen(buff)-1;
if (vehicle->calculatedVehicleValues.dist < METERS_TO_CENTIMETERS(osdConfig()->adsb_distance_alert)) {
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
}
}
buff[adsblen]='\0';
displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr);
if (arrowPositionX > 0){
int16_t panHomeDirOffset = 0;
if (osdConfig()->pan_servo_pwm2centideg != 0){
panHomeDirOffset = osdGetPanServoOffset();
}
int16_t flightDirection = STATE(AIRPLANE) ? CENTIDEGREES_TO_DEGREES(posControl.actualState.cog) : DECIDEGREES_TO_DEGREES(osdGetHeading());
osdDrawDirArrow(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX + arrowPositionX, elemPosY), CENTIDEGREES_TO_DEGREES(vehicle->calculatedVehicleValues.dir) - flightDirection + panHomeDirOffset);
}
return true;
}
case OSD_ADSB_INFO:
{
buff[0] = SYM_ADSB;
if(getAdsbStatus()->vehiclesMessagesTotal > 0){
tfp_sprintf(buff + 1, "%2d", getActiveVehiclesCount());
}else{
buff[1] = '-';
}
break;
}
#endif
case OSD_MAP_NORTH: case OSD_MAP_NORTH:
{ {
static uint16_t drawn = 0; static uint16_t drawn = 0;
@ -3767,6 +3834,11 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
.baro_temp_alarm_min = SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT, .baro_temp_alarm_min = SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT,
.baro_temp_alarm_max = SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT, .baro_temp_alarm_max = SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT,
#endif #endif
#ifdef USE_ADSB
.adsb_distance_warning = SETTING_OSD_ADSB_DISTANCE_WARNING_DEFAULT,
.adsb_distance_alert = SETTING_OSD_ADSB_DISTANCE_ALERT_DEFAULT,
.adsb_ignore_plane_above_me_limit = SETTING_OSD_ADSB_IGNORE_PLANE_ABOVE_ME_LIMIT_DEFAULT,
#endif
#ifdef USE_SERIALRX_CRSF #ifdef USE_SERIALRX_CRSF
.snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT, .snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT,
.crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT, .crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT,
@ -4006,6 +4078,8 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_2] = OSD_POS(2, 9); osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_2] = OSD_POS(2, 9);
osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_3] = OSD_POS(2, 10); osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_3] = OSD_POS(2, 10);
osdLayoutsConfig->item_pos[0][OSD_ADSB_WARNING] = OSD_POS(2, 7);
osdLayoutsConfig->item_pos[0][OSD_ADSB_INFO] = OSD_POS(2, 8);
#if defined(USE_ESC_SENSOR) #if defined(USE_ESC_SENSOR)
osdLayoutsConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2); osdLayoutsConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2);
osdLayoutsConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3); osdLayoutsConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3);

View file

@ -280,6 +280,8 @@ typedef enum {
OSD_MULTI_FUNCTION, OSD_MULTI_FUNCTION,
OSD_ODOMETER, OSD_ODOMETER,
OSD_PILOT_LOGO, OSD_PILOT_LOGO,
OSD_ADSB_WARNING,
OSD_ADSB_INFO,
OSD_ITEM_COUNT // MUST BE LAST OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e; } osd_items_e;
@ -455,6 +457,11 @@ typedef struct osdConfig_s {
bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo. bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo.
uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width. uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width.
uint16_t arm_screen_display_time; // Length of time the arm screen is displayed uint16_t arm_screen_display_time; // Length of time the arm screen is displayed
#ifdef USE_ADSB
uint16_t adsb_distance_warning; // in metres
uint16_t adsb_distance_alert; // in metres
uint16_t adsb_ignore_plane_above_me_limit; // in metres
#endif
} osdConfig_t; } osdConfig_t;
PG_DECLARE(osdConfig_t, osdConfig); PG_DECLARE(osdConfig_t, osdConfig);

View file

@ -99,3 +99,5 @@
#define MSP2_INAV_EZ_TUNE_SET 0x2071 #define MSP2_INAV_EZ_TUNE_SET 0x2071
#define MSP2_INAV_SELECT_MIXER_PROFILE 0x2080 #define MSP2_INAV_SELECT_MIXER_PROFILE 0x2080
#define MSP2_ADSB_VEHICLE_LIST 0x2090

View file

@ -70,6 +70,9 @@ typedef enum {
#ifdef USE_BARO #ifdef USE_BARO
TASK_BARO, TASK_BARO,
#endif #endif
#ifdef USE_ADSB
TASK_ADSB,
#endif
#ifdef USE_PITOT #ifdef USE_PITOT
TASK_PITOT, TASK_PITOT,
#endif #endif

View file

@ -28,6 +28,7 @@
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "config/parameter_group_ids.h" #include "config/parameter_group_ids.h"
#include "fc/runtime_config.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
@ -45,6 +46,7 @@
static bool standardBoardAlignment = true; // board orientation correction static bool standardBoardAlignment = true; // board orientation correction
static fpMat3_t boardRotMatrix; static fpMat3_t boardRotMatrix;
static fpMat3_t tailRotMatrix;
// no template required since defaults are zero // no template required since defaults are zero
PG_REGISTER(boardAlignment_t, boardAlignment, PG_BOARD_ALIGNMENT, 0); PG_REGISTER(boardAlignment_t, boardAlignment, PG_BOARD_ALIGNMENT, 0);
@ -56,19 +58,19 @@ static bool isBoardAlignmentStandard(const boardAlignment_t *boardAlignment)
void initBoardAlignment(void) void initBoardAlignment(void)
{ {
if (isBoardAlignmentStandard(boardAlignment())) { standardBoardAlignment=isBoardAlignmentStandard(boardAlignment());
standardBoardAlignment = true; fp_angles_t rotationAngles;
} else {
fp_angles_t rotationAngles; rotationAngles.angles.roll = DECIDEGREES_TO_RADIANS(boardAlignment()->rollDeciDegrees );
rotationAngles.angles.pitch = DECIDEGREES_TO_RADIANS(boardAlignment()->pitchDeciDegrees);
rotationAngles.angles.yaw = DECIDEGREES_TO_RADIANS(boardAlignment()->yawDeciDegrees );
standardBoardAlignment = false; rotationMatrixFromAngles(&boardRotMatrix, &rotationAngles);
fp_angles_t tailSitter_rotationAngles;
rotationAngles.angles.roll = DECIDEGREES_TO_RADIANS(boardAlignment()->rollDeciDegrees ); tailSitter_rotationAngles.angles.roll = DECIDEGREES_TO_RADIANS(0);
rotationAngles.angles.pitch = DECIDEGREES_TO_RADIANS(boardAlignment()->pitchDeciDegrees); tailSitter_rotationAngles.angles.pitch = DECIDEGREES_TO_RADIANS(900);
rotationAngles.angles.yaw = DECIDEGREES_TO_RADIANS(boardAlignment()->yawDeciDegrees ); tailSitter_rotationAngles.angles.yaw = DECIDEGREES_TO_RADIANS(0);
rotationMatrixFromAngles(&tailRotMatrix, &tailSitter_rotationAngles);
rotationMatrixFromAngles(&boardRotMatrix, &rotationAngles);
}
} }
void updateBoardAlignment(int16_t roll, int16_t pitch) void updateBoardAlignment(int16_t roll, int16_t pitch)
@ -85,15 +87,23 @@ void updateBoardAlignment(int16_t roll, int16_t pitch)
initBoardAlignment(); initBoardAlignment();
} }
void applyTailSitterAlignment(fpVector3_t *fpVec)
{
if (!STATE(TAILSITTER)) {
return;
}
rotationMatrixRotateVector(fpVec, fpVec, &tailRotMatrix);
}
void applyBoardAlignment(float *vec) void applyBoardAlignment(float *vec)
{ {
if (standardBoardAlignment) { if (standardBoardAlignment && (!STATE(TAILSITTER))) {
return; return;
} }
fpVector3_t fpVec = { .v = { vec[X], vec[Y], vec[Z] } }; fpVector3_t fpVec = { .v = { vec[X], vec[Y], vec[Z] } };
rotationMatrixRotateVector(&fpVec, &fpVec, &boardRotMatrix); rotationMatrixRotateVector(&fpVec, &fpVec, &boardRotMatrix);
applyTailSitterAlignment(&fpVec);
vec[X] = lrintf(fpVec.x); vec[X] = lrintf(fpVec.x);
vec[Y] = lrintf(fpVec.y); vec[Y] = lrintf(fpVec.y);
vec[Z] = lrintf(fpVec.z); vec[Z] = lrintf(fpVec.z);

View file

@ -18,6 +18,7 @@
#pragma once #pragma once
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "common/vector.h"
typedef struct boardAlignment_s { typedef struct boardAlignment_s {
int16_t rollDeciDegrees; int16_t rollDeciDegrees;
@ -30,4 +31,5 @@ PG_DECLARE(boardAlignment_t, boardAlignment);
void initBoardAlignment(void); void initBoardAlignment(void);
void updateBoardAlignment(int16_t roll, int16_t pitch); void updateBoardAlignment(int16_t roll, int16_t pitch);
void applySensorAlignment(float * dest, float * src, uint8_t rotation); void applySensorAlignment(float * dest, float * src, uint8_t rotation);
void applyBoardAlignment(float *vec); void applyBoardAlignment(float *vec);
void applyTailSitterAlignment(fpVector3_t *vec);

View file

@ -472,7 +472,7 @@ void compassUpdate(timeUs_t currentTimeUs)
fpVector3_t rotated; fpVector3_t rotated;
rotationMatrixRotateVector(&rotated, &v, &mag.dev.magAlign.externalRotation); rotationMatrixRotateVector(&rotated, &v, &mag.dev.magAlign.externalRotation);
applyTailSitterAlignment(&rotated);
mag.magADC[X] = rotated.x; mag.magADC[X] = rotated.x;
mag.magADC[Y] = rotated.y; mag.magADC[Y] = rotated.y;
mag.magADC[Z] = rotated.z; mag.magADC[Z] = rotated.z;

View file

@ -183,6 +183,14 @@
#define USE_CMS_FONT_PREVIEW #define USE_CMS_FONT_PREVIEW
//ADSB RECEIVER
#ifdef USE_GPS
#define USE_ADSB
#define MAX_ADSB_VEHICLES 5
#define ADSB_LIMIT_CM 6400000
#endif
//Designed to free space of F722 and F411 MCUs //Designed to free space of F722 and F411 MCUs
#if (MCU_FLASH_SIZE > 512) #if (MCU_FLASH_SIZE > 512)
#define USE_VTX_FFPV #define USE_VTX_FFPV

View file

@ -58,6 +58,7 @@
#include "flight/pid.h" #include "flight/pid.h"
#include "flight/servos.h" #include "flight/servos.h"
#include "io/adsb.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/serial.h" #include "io/serial.h"
@ -1062,6 +1063,50 @@ static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) {
return true; return true;
} }
#ifdef USE_ADSB
static bool handleIncoming_ADSB_VEHICLE(void) {
mavlink_adsb_vehicle_t msg;
mavlink_msg_adsb_vehicle_decode(&mavRecvMsg, &msg);
adsbVehicleValues_t* vehicle = getVehicleForFill();
if(vehicle != NULL){
vehicle->icao = msg.ICAO_address;
vehicle->lat = msg.lat;
vehicle->lon = msg.lon;
vehicle->alt = (int32_t)(msg.altitude / 10);
vehicle->heading = msg.heading;
vehicle->flags = msg.flags;
vehicle->altitudeType = msg.altitude_type;
memcpy(&(vehicle->callsign), msg.callsign, sizeof(vehicle->callsign));
vehicle->emitterType = msg.emitter_type;
vehicle->tslc = msg.tslc;
adsbNewVehicle(vehicle);
}
//debug vehicle
/* if(vehicle != NULL){
char name[9] = "DUMMY ";
vehicle->icao = 666;
vehicle->lat = 492383514;
vehicle->lon = 165148681;
vehicle->alt = 100000;
vehicle->heading = 180;
vehicle->flags = ADSB_FLAGS_VALID_ALTITUDE | ADSB_FLAGS_VALID_COORDS;
vehicle->altitudeType = 0;
memcpy(&(vehicle->callsign), name, sizeof(vehicle->callsign));
vehicle->emitterType = 6;
vehicle->tslc = 0;
adsbNewVehicle(vehicle);
}*/
return true;
}
#endif
static bool processMAVLinkIncomingTelemetry(void) static bool processMAVLinkIncomingTelemetry(void)
{ {
while (serialRxBytesWaiting(mavlinkPort) > 0) { while (serialRxBytesWaiting(mavlinkPort) > 0) {
@ -1084,6 +1129,10 @@ static bool processMAVLinkIncomingTelemetry(void)
return handleIncoming_MISSION_REQUEST(); return handleIncoming_MISSION_REQUEST();
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
return handleIncoming_RC_CHANNELS_OVERRIDE(); return handleIncoming_RC_CHANNELS_OVERRIDE();
#ifdef USE_ADSB
case MAVLINK_MSG_ID_ADSB_VEHICLE:
return handleIncoming_ADSB_VEHICLE();
#endif
default: default:
return false; return false;
} }