diff --git a/docs/ADSB.md b/docs/ADSB.md index 345af30a97..933cb264cd 100644 --- a/docs/ADSB.md +++ b/docs/ADSB.md @@ -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 +![TT-SC1 settings](Screenshots/ADSB_TTSC01_settings.png) diff --git a/docs/Screenshots/ADSB_TTSC01_settings.png b/docs/Screenshots/ADSB_TTSC01_settings.png new file mode 100644 index 0000000000..b98b73c445 Binary files /dev/null and b/docs/Screenshots/ADSB_TTSC01_settings.png differ diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index c8ae27f270..9f6508c194 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -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: diff --git a/src/main/io/adsb.c b/src/main/io/adsb.c index 573112c2df..260f89fa6a 100644 --- a/src/main/io/adsb.c +++ b/src/main/io/adsb.c @@ -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); diff --git a/src/main/io/adsb.h b/src/main/io/adsb.h index 86eefd8aac..77f2e31fa4 100644 --- a/src/main/io/adsb.h +++ b/src/main/io/adsb.h @@ -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); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d682c0299f..fff22479f0 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -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] = '-'; diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index c8f5600d6e..4e8d54535a 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -1134,6 +1134,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; @@ -1188,7 +1204,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: