Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions docs/ADSB.md
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ 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)
* [ADSBee1090](https://pantsforbirds.com/adsbee-1090/) (tested)
* [SoftRf](https://github.com/lyusupov/SoftRF/wiki/Nano-Edition) (not 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
Expand Down Expand Up @@ -63,3 +64,13 @@ AT+SETTINGS=SAVE
* in INAV configurator ports TAB set telemetry MAVLINK, and baudrate 115200
* https://pantsforbirds.com/adsbee-1090/quick-start/

## SoftRF settings
SoftRF needs more mavlink messages than other receivers, in INAV cli set correct mavlink output.
```
set mavlink_version = 1
set mavlink_pos_rate = 2
save
```
Baud rate for softRF is 57600. INAV supports only mandatory messages for softRF.
Messages MAVLINK_MSG_ID_SYS_STATUS, MAVLINK_MSG_ID_VFR_HUD, MAVLINK_MSG_ID_ATTITUDE are not supported.

2 changes: 2 additions & 0 deletions lib/main/MAVLink/common/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -987,6 +987,8 @@ typedef enum MAV_DATA_STREAM
MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */
MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */
MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages. | */
MAV_DATA_STREAM_SYSTEM_TIME=7, /* Enable SYSTEM_TIME messages. | */
MAV_DATA_STREAM_HEARTBEAT=8, /* Enable HEARTBEAT messages. | */
MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */
MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
Expand Down
130 changes: 78 additions & 52 deletions src/main/telemetry/mavlink.c
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,9 @@ static uint8_t mavRates[] = {
[MAV_DATA_STREAM_POSITION] = 2, // 2Hz
[MAV_DATA_STREAM_EXTRA1] = 3, // 3Hz
[MAV_DATA_STREAM_EXTRA2] = 2, // 2Hz, HEARTBEATs are important
[MAV_DATA_STREAM_EXTRA3] = 1 // 1Hz
[MAV_DATA_STREAM_EXTRA3] = 1, // 1Hz
[MAV_DATA_STREAM_SYSTEM_TIME] = 1, // 1Hz
[MAV_DATA_STREAM_HEARTBEAT] = 1, // 1Hz
};

#define MAXSTREAMS (sizeof(mavRates) / sizeof(mavRates[0]))
Expand Down Expand Up @@ -704,52 +706,22 @@ void mavlinkSendAttitude(void)
mavlinkSendMessage();
}

void mavlinkSendHUDAndHeartbeat(void)
void mavlinkSendSystemTime(void)
{
float mavAltitude = 0;
float mavGroundSpeed = 0;
float mavAirSpeed = 0;
float mavClimbRate = 0;
uint64_t timeUnixUsec = 0;
rtcTime_t rtcTime;

#if defined(USE_GPS)
// use ground speed if source available
if (sensors(SENSOR_GPS)
#ifdef USE_GPS_FIX_ESTIMATION
|| STATE(GPS_ESTIMATED_FIX)
#endif
) {
mavGroundSpeed = gpsSol.groundSpeed / 100.0f;
if (rtcGet(&rtcTime)) {
timeUnixUsec = (uint64_t)rtcTime * 1000ULL + (uint64_t)(micros() % 1000); // extrapolation to uS
//timeUnixUsec = (uint64_t)rtcTime * 1000ULL; // mS resolution
}
#endif

#if defined(USE_PITOT)
if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
mavAirSpeed = getAirspeedEstimate() / 100.0f;
}
#endif

// select best source for altitude
mavAltitude = getEstimatedActualPosition(Z) / 100.0f;
mavClimbRate = getEstimatedActualVelocity(Z) / 100.0f;

int16_t thr = getThrottlePercent(osdUsingScaledThrottle());
mavlink_msg_vfr_hud_pack(mavSystemId, mavComponentId, &mavSendMsg,
// airspeed Current airspeed in m/s
mavAirSpeed,
// groundspeed Current ground speed in m/s
mavGroundSpeed,
// heading Current heading in degrees, in compass units (0..360, 0=north)
DECIDEGREES_TO_DEGREES(attitude.values.yaw),
// throttle Current throttle setting in integer percent, 0 to 100
thr,
// alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
mavAltitude,
// climb Current climb rate in meters/second
mavClimbRate);

mavlink_msg_system_time_pack(mavSystemId, mavComponentId, &mavSendMsg, timeUnixUsec, millis());
mavlinkSendMessage();
}


void mavlinkSendHeartbeat(void)
{
uint8_t mavModes = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
if (ARMING_FLAG(ARMED))
mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
Expand Down Expand Up @@ -821,16 +793,62 @@ void mavlinkSendHUDAndHeartbeat(void)
}

mavlink_msg_heartbeat_pack(mavSystemId, mavComponentId, &mavSendMsg,
// type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
mavSystemType,
// autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
mavType,
// base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
mavModes,
// custom_mode A bitfield for use for autopilot-specific flags.
mavCustomMode,
// system_status System status flag, see MAV_STATE ENUM
mavSystemState);
// type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
mavSystemType,
// autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
mavType,
// base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
mavModes,
// custom_mode A bitfield for use for autopilot-specific flags.
mavCustomMode,
// system_status System status flag, see MAV_STATE ENUM
mavSystemState);

mavlinkSendMessage();
}

void mavlinkSendHUD(void)
{
float mavAltitude = 0;
float mavGroundSpeed = 0;
float mavAirSpeed = 0;
float mavClimbRate = 0;

#if defined(USE_GPS)
// use ground speed if source available
if (sensors(SENSOR_GPS)
#ifdef USE_GPS_FIX_ESTIMATION
|| STATE(GPS_ESTIMATED_FIX)
#endif
) {
mavGroundSpeed = gpsSol.groundSpeed / 100.0f;
}
#endif

#if defined(USE_PITOT)
if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
mavAirSpeed = getAirspeedEstimate() / 100.0f;
}
#endif

// select best source for altitude
mavAltitude = getEstimatedActualPosition(Z) / 100.0f;
mavClimbRate = getEstimatedActualVelocity(Z) / 100.0f;

int16_t thr = getThrottlePercent(osdUsingScaledThrottle());
mavlink_msg_vfr_hud_pack(mavSystemId, mavComponentId, &mavSendMsg,
// airspeed Current airspeed in m/s
mavAirSpeed,
// groundspeed Current ground speed in m/s
mavGroundSpeed,
// heading Current heading in degrees, in compass units (0..360, 0=north)
DECIDEGREES_TO_DEGREES(attitude.values.yaw),
// throttle Current throttle setting in integer percent, 0 to 100
thr,
// alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
mavAltitude,
// climb Current climb rate in meters/second
mavClimbRate);

mavlinkSendMessage();
}
Expand Down Expand Up @@ -952,13 +970,21 @@ void processMAVLinkTelemetry(timeUs_t currentTimeUs)
}

if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2)) {
mavlinkSendHUDAndHeartbeat();
mavlinkSendHUD();
}

if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA3)) {
mavlinkSendBatteryTemperatureStatusText();
}

if (mavlinkStreamTrigger(MAV_DATA_STREAM_HEARTBEAT)) {
mavlinkSendHeartbeat();
}

if (mavlinkStreamTrigger(MAV_DATA_STREAM_SYSTEM_TIME)) {
mavlinkSendSystemTime();
}

}

static bool handleIncoming_MISSION_CLEAR_ALL(void)
Expand Down
Loading