2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
24 * Author: Konstantin Sharlaimov
32 #if defined(USE_TELEMETRY_MAVLINK)
34 #include "common/maths.h"
35 #include "common/axis.h"
36 #include "common/color.h"
38 #include "config/feature.h"
40 #include "pg/pg_ids.h"
43 #include "drivers/accgyro/accgyro.h"
44 #include "drivers/sensor.h"
45 #include "drivers/time.h"
47 #include "config/config.h"
48 #include "fc/rc_controls.h"
49 #include "fc/runtime_config.h"
51 #include "flight/mixer.h"
52 #include "flight/pid.h"
53 #include "flight/imu.h"
54 #include "flight/failsafe.h"
55 #include "flight/position.h"
57 #include "io/serial.h"
58 #include "io/gimbal.h"
60 #include "io/ledstrip.h"
64 #include "sensors/sensors.h"
65 #include "sensors/acceleration.h"
66 #include "sensors/gyro.h"
67 #include "sensors/barometer.h"
68 #include "sensors/boardalignment.h"
69 #include "sensors/battery.h"
71 #include "telemetry/telemetry.h"
72 #include "telemetry/mavlink.h"
74 // mavlink library uses unnames unions that's causes GCC to complain if -Wpedantic is used
75 // until this is resolved in mavlink library - ignore -Wpedantic for mavlink code
76 #pragma GCC diagnostic push
77 #pragma GCC diagnostic ignored "-Wpedantic"
78 #include "common/mavlink.h"
79 #pragma GCC diagnostic pop
81 #define TELEMETRY_MAVLINK_INITIAL_PORT_MODE MODE_TX
82 #define TELEMETRY_MAVLINK_MAXRATE 50
83 #define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
85 extern uint16_t rssi
; // FIXME dependency on mw.c
87 static serialPort_t
*mavlinkPort
= NULL
;
88 static const serialPortConfig_t
*portConfig
;
90 static bool mavlinkTelemetryEnabled
= false;
91 static portSharing_e mavlinkPortSharing
;
93 /* MAVLink datastream rates in Hz */
94 static const uint8_t mavRates
[] = {
95 [MAV_DATA_STREAM_EXTENDED_STATUS
] = 2, //2Hz
96 [MAV_DATA_STREAM_RC_CHANNELS
] = 5, //5Hz
97 [MAV_DATA_STREAM_POSITION
] = 2, //2Hz
98 [MAV_DATA_STREAM_EXTRA1
] = 10, //10Hz
99 [MAV_DATA_STREAM_EXTRA2
] = 10 //2Hz
102 #define MAXSTREAMS (sizeof(mavRates) / sizeof(mavRates[0]))
104 static uint8_t mavTicks
[MAXSTREAMS
];
105 static mavlink_message_t mavMsg
;
106 static uint8_t mavBuffer
[MAVLINK_MAX_PACKET_LEN
];
107 static uint32_t lastMavlinkMessage
= 0;
109 static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum
)
111 uint8_t rate
= (uint8_t) mavRates
[streamNum
];
116 if (mavTicks
[streamNum
] == 0) {
117 // we're triggering now, setup the next trigger point
118 if (rate
> TELEMETRY_MAVLINK_MAXRATE
) {
119 rate
= TELEMETRY_MAVLINK_MAXRATE
;
122 mavTicks
[streamNum
] = (TELEMETRY_MAVLINK_MAXRATE
/ rate
);
126 // count down at TASK_RATE_HZ
127 mavTicks
[streamNum
]--;
132 static void mavlinkSerialWrite(uint8_t * buf
, uint16_t length
)
134 for (int i
= 0; i
< length
; i
++)
135 serialWrite(mavlinkPort
, buf
[i
]);
138 static int16_t headingOrScaledMilliAmpereHoursDrawn(void)
140 if (isAmperageConfigured() && telemetryConfig()->mavlink_mah_as_heading_divisor
> 0) {
141 // In the Connex Prosight OSD, this goes between 0 and 999, so it will need to be scaled in that range.
142 return getMAhDrawn() / telemetryConfig()->mavlink_mah_as_heading_divisor
;
144 // heading Current heading in degrees, in compass units (0..360, 0=north)
145 return DECIDEGREES_TO_DEGREES(attitude
.values
.yaw
);
149 void freeMAVLinkTelemetryPort(void)
151 closeSerialPort(mavlinkPort
);
153 mavlinkTelemetryEnabled
= false;
156 void initMAVLinkTelemetry(void)
158 portConfig
= findSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK
);
159 mavlinkPortSharing
= determinePortSharing(portConfig
, FUNCTION_TELEMETRY_MAVLINK
);
162 void configureMAVLinkTelemetryPort(void)
168 baudRate_e baudRateIndex
= portConfig
->telemetry_baudrateIndex
;
169 if (baudRateIndex
== BAUD_AUTO
) {
170 // default rate for minimOSD
171 baudRateIndex
= BAUD_57600
;
174 mavlinkPort
= openSerialPort(portConfig
->identifier
, FUNCTION_TELEMETRY_MAVLINK
, NULL
, NULL
, baudRates
[baudRateIndex
], TELEMETRY_MAVLINK_INITIAL_PORT_MODE
, telemetryConfig()->telemetry_inverted
? SERIAL_INVERTED
: SERIAL_NOT_INVERTED
);
180 mavlinkTelemetryEnabled
= true;
183 void checkMAVLinkTelemetryState(void)
185 if (portConfig
&& telemetryCheckRxPortShared(portConfig
, rxRuntimeState
.serialrxProvider
)) {
186 if (!mavlinkTelemetryEnabled
&& telemetrySharedPort
!= NULL
) {
187 mavlinkPort
= telemetrySharedPort
;
188 mavlinkTelemetryEnabled
= true;
191 bool newTelemetryEnabledValue
= telemetryDetermineEnabledState(mavlinkPortSharing
);
193 if (newTelemetryEnabledValue
== mavlinkTelemetryEnabled
) {
197 if (newTelemetryEnabledValue
)
198 configureMAVLinkTelemetryPort();
200 freeMAVLinkTelemetryPort();
204 void mavlinkSendSystemStatus(void)
208 uint32_t onboardControlAndSensors
= 35843;
211 onboard_control_sensors_present Bitmask
213 1000110000000011 For all = 35843
214 0001000000000100 With Mag = 4100
215 0010000000001000 With Baro = 8200
216 0100000000100000 With GPS = 16416
220 if (sensors(SENSOR_MAG
)) onboardControlAndSensors
|= 4100;
221 if (sensors(SENSOR_BARO
)) onboardControlAndSensors
|= 8200;
222 if (sensors(SENSOR_GPS
)) onboardControlAndSensors
|= 16416;
224 uint16_t batteryVoltage
= 0;
225 int16_t batteryAmperage
= -1;
226 int8_t batteryRemaining
= 100;
228 if (getBatteryState() < BATTERY_NOT_PRESENT
) {
229 batteryVoltage
= isBatteryVoltageConfigured() ? getBatteryVoltage() * 10 : batteryVoltage
;
230 batteryAmperage
= isAmperageConfigured() ? getAmperage() : batteryAmperage
;
231 batteryRemaining
= isBatteryVoltageConfigured() ? calculateBatteryPercentageRemaining() : batteryRemaining
;
234 mavlink_msg_sys_status_pack(0, 200, &mavMsg
,
235 // onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present.
236 //Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure,
237 // 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position,
238 // 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization,
239 // 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
240 onboardControlAndSensors
,
241 // onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled
242 onboardControlAndSensors
,
243 // onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error.
244 onboardControlAndSensors
& 1023,
245 // load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
247 // voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
249 // current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
251 // battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
253 // drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
255 // errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
257 // errors_count1 Autopilot-specific errors
259 // errors_count2 Autopilot-specific errors
261 // errors_count3 Autopilot-specific errors
263 // errors_count4 Autopilot-specific errors
265 msgLength
= mavlink_msg_to_send_buffer(mavBuffer
, &mavMsg
);
266 mavlinkSerialWrite(mavBuffer
, msgLength
);
269 void mavlinkSendRCChannelsAndRSSI(void)
272 mavlink_msg_rc_channels_raw_pack(0, 200, &mavMsg
,
273 // time_boot_ms Timestamp (milliseconds since system boot)
275 // port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
277 // chan1_raw RC channel 1 value, in microseconds
278 (rxRuntimeState
.channelCount
>= 1) ? rcData
[0] : 0,
279 // chan2_raw RC channel 2 value, in microseconds
280 (rxRuntimeState
.channelCount
>= 2) ? rcData
[1] : 0,
281 // chan3_raw RC channel 3 value, in microseconds
282 (rxRuntimeState
.channelCount
>= 3) ? rcData
[2] : 0,
283 // chan4_raw RC channel 4 value, in microseconds
284 (rxRuntimeState
.channelCount
>= 4) ? rcData
[3] : 0,
285 // chan5_raw RC channel 5 value, in microseconds
286 (rxRuntimeState
.channelCount
>= 5) ? rcData
[4] : 0,
287 // chan6_raw RC channel 6 value, in microseconds
288 (rxRuntimeState
.channelCount
>= 6) ? rcData
[5] : 0,
289 // chan7_raw RC channel 7 value, in microseconds
290 (rxRuntimeState
.channelCount
>= 7) ? rcData
[6] : 0,
291 // chan8_raw RC channel 8 value, in microseconds
292 (rxRuntimeState
.channelCount
>= 8) ? rcData
[7] : 0,
293 // rssi Receive signal strength indicator, 0: 0%, 255: 100%
294 constrain(scaleRange(getRssi(), 0, RSSI_MAX_VALUE
, 0, 255), 0, 255));
295 msgLength
= mavlink_msg_to_send_buffer(mavBuffer
, &mavMsg
);
296 mavlinkSerialWrite(mavBuffer
, msgLength
);
300 void mavlinkSendPosition(void)
303 uint8_t gpsFixType
= 0;
305 if (!sensors(SENSOR_GPS
))
308 if (!STATE(GPS_FIX
)) {
312 if (gpsSol
.numSat
< 5) {
320 mavlink_msg_gps_raw_int_pack(0, 200, &mavMsg
,
321 // time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
323 // fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
325 // lat Latitude in 1E7 degrees
327 // lon Longitude in 1E7 degrees
329 // alt Altitude in 1E3 meters (millimeters) above MSL
330 gpsSol
.llh
.altCm
* 10,
331 // eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
333 // epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
335 // vel GPS ground speed (m/s * 100). If unknown, set to: 65535
337 // cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
338 gpsSol
.groundCourse
* 10,
339 // satellites_visible Number of satellites visible. If unknown, set to 255
341 msgLength
= mavlink_msg_to_send_buffer(mavBuffer
, &mavMsg
);
342 mavlinkSerialWrite(mavBuffer
, msgLength
);
345 mavlink_msg_global_position_int_pack(0, 200, &mavMsg
,
346 // time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
348 // lat Latitude in 1E7 degrees
350 // lon Longitude in 1E7 degrees
352 // alt Altitude in 1E3 meters (millimeters) above MSL
353 gpsSol
.llh
.altCm
* 10,
354 // relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
355 getEstimatedAltitudeCm() * 10,
356 // Ground X Speed (Latitude), expressed as m/s * 100
358 // Ground Y Speed (Longitude), expressed as m/s * 100
360 // Ground Z Speed (Altitude), expressed as m/s * 100
362 // heading Current heading in degrees, in compass units (0..360, 0=north)
363 headingOrScaledMilliAmpereHoursDrawn()
365 msgLength
= mavlink_msg_to_send_buffer(mavBuffer
, &mavMsg
);
366 mavlinkSerialWrite(mavBuffer
, msgLength
);
368 mavlink_msg_gps_global_origin_pack(0, 200, &mavMsg
,
369 // latitude Latitude (WGS84), expressed as * 1E7
370 GPS_home
[GPS_LATITUDE
],
371 // longitude Longitude (WGS84), expressed as * 1E7
372 GPS_home
[GPS_LONGITUDE
],
373 // altitude Altitude(WGS84), expressed as * 1000
375 msgLength
= mavlink_msg_to_send_buffer(mavBuffer
, &mavMsg
);
376 mavlinkSerialWrite(mavBuffer
, msgLength
);
380 void mavlinkSendAttitude(void)
383 mavlink_msg_attitude_pack(0, 200, &mavMsg
,
384 // time_boot_ms Timestamp (milliseconds since system boot)
386 // roll Roll angle (rad)
387 DECIDEGREES_TO_RADIANS(attitude
.values
.roll
),
388 // pitch Pitch angle (rad)
389 DECIDEGREES_TO_RADIANS(-attitude
.values
.pitch
),
390 // yaw Yaw angle (rad)
391 DECIDEGREES_TO_RADIANS(attitude
.values
.yaw
),
392 // rollspeed Roll angular speed (rad/s)
394 // pitchspeed Pitch angular speed (rad/s)
396 // yawspeed Yaw angular speed (rad/s)
398 msgLength
= mavlink_msg_to_send_buffer(mavBuffer
, &mavMsg
);
399 mavlinkSerialWrite(mavBuffer
, msgLength
);
402 void mavlinkSendHUDAndHeartbeat(void)
405 float mavAltitude
= 0;
406 float mavGroundSpeed
= 0;
407 float mavAirSpeed
= 0;
408 float mavClimbRate
= 0;
411 // use ground speed if source available
412 if (sensors(SENSOR_GPS
)) {
413 mavGroundSpeed
= gpsSol
.groundSpeed
/ 100.0f
;
417 mavAltitude
= getEstimatedAltitudeCm() / 100.0;
419 mavlink_msg_vfr_hud_pack(0, 200, &mavMsg
,
420 // airspeed Current airspeed in m/s
422 // groundspeed Current ground speed in m/s
424 // heading Current heading in degrees, in compass units (0..360, 0=north)
425 headingOrScaledMilliAmpereHoursDrawn(),
426 // throttle Current throttle setting in integer percent, 0 to 100
427 scaleRange(constrain(rcData
[THROTTLE
], PWM_RANGE_MIN
, PWM_RANGE_MAX
), PWM_RANGE_MIN
, PWM_RANGE_MAX
, 0, 100),
428 // alt Current altitude (MSL), in meters, if we have sonar or baro use them, otherwise use GPS (less accurate)
430 // climb Current climb rate in meters/second
432 msgLength
= mavlink_msg_to_send_buffer(mavBuffer
, &mavMsg
);
433 mavlinkSerialWrite(mavBuffer
, msgLength
);
436 uint8_t mavModes
= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
;
437 if (ARMING_FLAG(ARMED
))
438 mavModes
|= MAV_MODE_FLAG_SAFETY_ARMED
;
440 uint8_t mavSystemType
;
441 switch (mixerConfig()->mixerMode
)
444 mavSystemType
= MAV_TYPE_TRICOPTER
;
450 mavSystemType
= MAV_TYPE_QUADROTOR
;
455 mavSystemType
= MAV_TYPE_HEXAROTOR
;
458 case MIXER_OCTOFLATP
:
459 case MIXER_OCTOFLATX
:
460 mavSystemType
= MAV_TYPE_OCTOROTOR
;
462 case MIXER_FLYING_WING
:
464 case MIXER_CUSTOM_AIRPLANE
:
465 mavSystemType
= MAV_TYPE_FIXED_WING
;
467 case MIXER_HELI_120_CCPM
:
468 case MIXER_HELI_90_DEG
:
469 mavSystemType
= MAV_TYPE_HELICOPTER
;
472 mavSystemType
= MAV_TYPE_GENERIC
;
476 // Custom mode for compatibility with APM OSDs
477 uint8_t mavCustomMode
= 1; // Acro by default
479 if (FLIGHT_MODE(ANGLE_MODE
) || FLIGHT_MODE(HORIZON_MODE
)) {
480 mavCustomMode
= 0; //Stabilize
481 mavModes
|= MAV_MODE_FLAG_STABILIZE_ENABLED
;
484 uint8_t mavSystemState
= 0;
485 if (ARMING_FLAG(ARMED
)) {
486 if (failsafeIsActive()) {
487 mavSystemState
= MAV_STATE_CRITICAL
;
490 mavSystemState
= MAV_STATE_ACTIVE
;
494 mavSystemState
= MAV_STATE_STANDBY
;
497 mavlink_msg_heartbeat_pack(0, 200, &mavMsg
,
498 // type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
500 // autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
501 MAV_AUTOPILOT_GENERIC
,
502 // base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
504 // custom_mode A bitfield for use for autopilot-specific flags.
506 // system_status System status flag, see MAV_STATE ENUM
508 msgLength
= mavlink_msg_to_send_buffer(mavBuffer
, &mavMsg
);
509 mavlinkSerialWrite(mavBuffer
, msgLength
);
512 void processMAVLinkTelemetry(void)
514 // is executed @ TELEMETRY_MAVLINK_MAXRATE rate
515 if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_STATUS
)) {
516 mavlinkSendSystemStatus();
519 if (mavlinkStreamTrigger(MAV_DATA_STREAM_RC_CHANNELS
)) {
520 mavlinkSendRCChannelsAndRSSI();
524 if (mavlinkStreamTrigger(MAV_DATA_STREAM_POSITION
)) {
525 mavlinkSendPosition();
529 if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA1
)) {
530 mavlinkSendAttitude();
533 if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2
)) {
534 mavlinkSendHUDAndHeartbeat();
538 void handleMAVLinkTelemetry(void)
540 if (!mavlinkTelemetryEnabled
) {
548 uint32_t now
= micros();
549 if ((now
- lastMavlinkMessage
) >= TELEMETRY_MAVLINK_DELAY
) {
550 processMAVLinkTelemetry();
551 lastMavlinkMessage
= now
;