30 #pragma GCC diagnostic push
31 #pragma GCC diagnostic ignored "-Wswitch-default"
32 #include "mavlink/paparazzi/mavlink.h"
33 #pragma GCC diagnostic pop
35 #if PERIODIC_TELEMETRY
36 #define PERIODIC_C_MAVLINK
38 #include "generated/periodic_telemetry.h"
39 #ifndef TELEMETRY_MAVLINK_NB_MSG
40 #warning Using hardcoded msg periods. To customize specify a <process name="Mavlink" type="mavlink"> in your telemetry file.
44 #include "generated/airframe.h"
45 #include "generated/modules.h"
46 #include "generated/settings.h"
51 #include "pprz_version.h"
55 #if defined RADIO_CONTROL
99 #define MAVLINK_SYSID AC_ID
102 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
103 struct telemetry_cb_slots mavlink_cbs[TELEMETRY_MAVLINK_NB_MSG] = TELEMETRY_MAVLINK_CBS;
104 struct periodic_telemetry mavlink_telemetry = { TELEMETRY_MAVLINK_NB_MSG, mavlink_cbs };
116 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
140 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
143 periodic_telemetry_send_Mavlink(&mavlink_telemetry, NULL, NULL);
153 #if !defined (TELEMETRY_MAVLINK_NB_MSG)
183 for (i = 0; i < NB_SETTING; i++) {
184 for (j = 0; j < 16; j++) {
207 mavlink_message_t
msg;
215 if (mavlink_parse_char(MAVLINK_COMM_0, test, &msg, &status)) {
224 switch (msg->msgid) {
225 case MAVLINK_MSG_ID_HEARTBEAT:
229 case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: {
230 mavlink_request_data_stream_t cmd;
231 mavlink_msg_request_data_stream_decode(msg, &cmd);
233 mavlink_msg_data_stream_send(MAVLINK_COMM_0, cmd.req_stream_id, 0, 0);
239 case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: {
240 mavlink_rc_channels_override_t cmd;
241 mavlink_msg_rc_channels_override_decode(msg, &cmd);
242 #if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK
243 uint8_t thrust = (cmd.chan3_raw - 950) * 127 / 1100;
244 int8_t roll = -(cmd.chan1_raw - 1500) * 255 / 1100 / 2;
245 int8_t pitch = -(cmd.chan2_raw - 1500) * 255 / 1100 / 2;
246 int8_t yaw = -(cmd.chan4_raw - 1500) * 255 / 1100;
255 case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
261 case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
262 mavlink_param_request_read_t cmd;
263 mavlink_msg_param_request_read_decode(msg, &cmd);
266 if (cmd.param_index == -1) {
271 if (cmd.param_index > -1) {
272 mavlink_msg_param_value_send(MAVLINK_COMM_0,
274 settings_get_value(cmd.param_index),
275 MAV_PARAM_TYPE_REAL32,
283 case MAVLINK_MSG_ID_PARAM_SET: {
284 mavlink_param_set_t set;
285 mavlink_msg_param_set_decode(msg, &set);
288 if ((
uint8_t) set.target_system == AC_ID) {
295 if (set.param_type == MAV_PARAM_TYPE_REAL32 &&
296 !isnan(set.param_value) && !isinf(set.param_value)) {
297 DlSetting(idx, set.param_value);
299 mavlink_msg_param_value_send(MAVLINK_COMM_0,
301 settings_get_value(idx),
302 MAV_PARAM_TYPE_REAL32,
314 case MAVLINK_MSG_ID_COMMAND_LONG: {
315 mavlink_command_long_t cmd;
316 mavlink_msg_command_long_decode(msg, &cmd);
318 if ((
uint8_t) cmd.target_system == AC_ID) {
319 uint8_t result = MAV_RESULT_UNSUPPORTED;
320 switch (cmd.command) {
321 case MAV_CMD_NAV_GUIDED_ENABLE:
322 MAVLINK_DEBUG(
"got cmd NAV_GUIDED_ENABLE: %f\n", cmd.param1);
323 result = MAV_RESULT_FAILED;
324 if (cmd.param1 > 0.5) {
327 result = MAV_RESULT_ACCEPTED;
335 case MAV_CMD_COMPONENT_ARM_DISARM:
337 MAVLINK_DEBUG(
"got cmd COMPONENT_ARM_DISARM: %f\n", cmd.param1);
338 result = MAV_RESULT_FAILED;
339 if (cmd.param1 > 0.5) {
342 result = MAV_RESULT_ACCEPTED;
347 result = MAV_RESULT_ACCEPTED;
355 mavlink_msg_command_ack_send(MAVLINK_COMM_0, cmd.command, result);
361 case MAVLINK_MSG_ID_SET_MODE: {
362 mavlink_set_mode_t
mode;
363 mavlink_msg_set_mode_decode(msg, &mode);
364 if (mode.target_system == AC_ID) {
365 MAVLINK_DEBUG(
"got SET_MODE: base_mode:%d\n", mode.base_mode);
366 if (mode.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
372 if (mode.base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
375 else if (mode.base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
382 case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: {
383 mavlink_set_position_target_local_ned_t
target;
384 mavlink_msg_set_position_target_local_ned_decode(msg, &target);
386 if (target.target_system == AC_ID) {
387 MAVLINK_DEBUG(
"SET_POSITION_TARGET_LOCAL_NED, byte_mask: %d\n", target.type_mask);
389 if (!(target.type_mask & 0b1110000000100000)) {
390 switch (target.coordinate_frame) {
391 case MAV_FRAME_LOCAL_NED:
395 case MAV_FRAME_LOCAL_OFFSET_NED:
396 MAVLINK_DEBUG(
"set position target, frame LOCAL_OFFSET_NED\n");
399 case MAV_FRAME_BODY_OFFSET_NED:
400 MAVLINK_DEBUG(
"set position target, frame BODY_OFFSET_NED\n");
407 else if (!(target.type_mask & 0b0001110000100000)) {
409 switch (target.coordinate_frame) {
410 case MAV_FRAME_LOCAL_NED:
425 MAVLINK_DEBUG(
"Received message with id: %d\r\n", msg->msgid);
431 #pragma GCC diagnostic push
432 #pragma GCC diagnostic ignored "-Wunused-parameter"
439 uint8_t mav_state = MAV_STATE_CALIBRATING;
442 uint8_t mav_type = MAV_TYPE_FIXED_WING;
445 mav_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
448 mav_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
451 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
454 mav_mode |= MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED;
460 uint8_t mav_type = MAV_TYPE_QUADROTOR;
463 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
469 mav_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
479 mav_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
482 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
485 mav_mode = MAV_MODE_FLAG_GUIDED_ENABLED;
492 mav_state = MAV_STATE_STANDBY;
494 mav_state = MAV_STATE_ACTIVE;
495 mav_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
498 mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
513 #define UAV_SENSORS (MAV_SYS_STATUS_SENSOR_3D_GYRO|MAV_SYS_STATUS_SENSOR_3D_ACCEL|MAV_SYS_STATUS_SENSOR_3D_MAG|MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE)
515 mavlink_msg_sys_status_send(MAVLINK_COMM_0,
548 mavlink_msg_attitude_send(MAVLINK_COMM_0,
561 mavlink_msg_local_position_ned_send(MAVLINK_COMM_0,
578 uint16_t compass_heading = heading * 100;
581 mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
597 mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0,
614 mavlink_msg_param_value_send(MAVLINK_COMM_0,
616 settings_get_value(mavlink_params_idx),
617 MAV_PARAM_TYPE_REAL32,
622 mavlink_params_idx++;
628 static uint32_t ver = PPRZ_VERSION_INT;
630 get_pprz_git_version((
uint8_t *)&sha);
631 mavlink_msg_autopilot_version_send(MAVLINK_COMM_0,
649 mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_0,
672 mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
706 for (
uint8_t i = 0; i < nb_sats; i++) {
722 mavlink_msg_gps_status_send(MAVLINK_COMM_0,
723 gps.
num_sv, prn, used, elevation, azimuth, snr);
728 #if defined RADIO_CONTROL
731 #ifdef PPM_PULSE_TYPE_POSITIVE
732 #define RC_CHANNELS RADIO_CTL_NB
733 #define PPM_PULSES(_i) ((_i) < RADIO_CTL_NB ? ppm_pulses[(_i)] : UINT16_MAX)
737 #define RC_CHANNELS RADIO_CONTROL_NB_CHANNEL
738 #define PPM_OF_PPRZ(_v) ((_v) / 19.2 + 1500)
739 #define PPM_PULSES(_i) ((_i) < RADIO_CONTROL_NB_CHANNEL ? PPM_OF_PPRZ(radio_control.values[(_i)]) + MAX_PPRZ : UINT16_MAX)
745 #if defined RADIO_CONTROL
746 mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
757 mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
760 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
761 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
762 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
763 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
764 UINT16_MAX, UINT16_MAX, 255);
776 mavlink_msg_battery_status_send(MAVLINK_COMM_0,
800 #ifdef COMMAND_THRUST
802 #elif defined COMMAND_THROTTLE
805 mavlink_msg_vfr_hud_send(MAVLINK_COMM_0,
816 #pragma GCC diagnostic pop
bool autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw)
Set position and heading setpoints wrt.
int32_t current
current in milliamps
static void mavlink_send_local_position_ned(struct transport_tx *trans, struct link_device *dev)
void mavlink_common_message_handler(const mavlink_message_t *msg)
struct SVinfo svinfos[GPS_NB_CHANNELS]
holds information from the Space Vehicles (Satellites)
int16_t azim
azimuth in deg
Basic MAVLink datalink implementation.
static float stateGetHorizontalSpeedNorm_f(void)
Get norm of horizontal ground speed (float).
#define AP_MODE_RATE_DIRECT
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
static void mavlink_send_gps_raw_int(struct transport_tx *trans, struct link_device *dev)
void mavlink_mission_message_handler(const mavlink_message_t *msg)
#define AP_MODE_HOVER_DIRECT
uint32_t get_sys_time_msec(void)
Get the time in milliseconds since startup.
#define AP_MODE_RATE_Z_HOLD
bool autopilot_throttle_killed(void)
get kill status
bool autopilot_get_motors_on(void)
get motors status
struct LtpDef_f ned_origin_f
Definition of the local (flat earth) coordinate system.
Periodic telemetry structure.
void mavlink_mission_periodic(void)
update current block and send if changed
static float stateGetAirspeed_f(void)
Get airspeed (float).
static struct LlaCoor_f * stateGetPositionLla_f(void)
Get position in LLA coordinates (float).
#define AP_MODE_RATE_RC_CLIMB
void mavlink_mission_init(mavlink_mission_mgr *mgr)
Autopilot guided mode interface.
void mavlink_init(void)
Module functions.
bool autopilot_set_mode(uint8_t new_autopilot_mode)
set autopilot mode
uint8_t svid
Satellite ID.
static void mavlink_send_gps_status(struct transport_tx *trans, struct link_device *dev)
Send gps status.
Common tools for periodic telemetry interface Allows subsystem to register callback functions...
int32_t hmsl
Height above mean sea level in mm.
int8_t elev
elevation in deg
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
int32_t alt
in millimeters above WGS84 reference ellipsoid
#define AP_MODE_ATTITUDE_RC_CLIMB
Common functions used within the mission library, blocks and waypoints cannot be send simultaneously ...
static void mavlink_send_attitude(struct transport_tx *trans, struct link_device *dev)
Send the attitude.
#define AP_MODE_MANUAL
AP modes.
mavlink_system_t mavlink_system
#define MAVLINK_DEBUG(...)
#define AP_MODE_ATTITUDE_CLIMB
void mavlink_event(void)
Event MAVLink calls.
unsigned long long uint64_t
uint8_t cno
Carrier to Noise Ratio (Signal Strength) in dbHz.
static bool stateIsAttitudeValid(void)
Test if attitudes are valid.
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
Interface for electrical status: supply voltage, current, battery status, etc.
float hmsl
Height above mean sea level in meters.
Architecture independent timing functions.
void mavlink_periodic(void)
Periodic MAVLink calls.
Device independent GPS code (interface)
#define AP_MODE_HOVER_Z_HOLD
uint16_t pdop
position dilution of precision scaled by 100
static uint8_t custom_version[8]
first 8 bytes (16 chars) of GIT SHA1
static int16_t settings_idx_from_param_id(char *param_id)
static void mavlink_send_rc_channels(struct transport_tx *trans, struct link_device *dev)
struct LlaCoor_i lla
Reference point in lla.
int32_t lon
in degrees*1e7
#define AP_MODE_RC_DIRECT
static void mavlink_send_system_time(struct transport_tx *trans, struct link_device *dev)
Send SYSTEM_TIME.
Hardware independent code for commands handling.
#define MAVLinkSendMessage()
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
bool ned_initialized_i
true if local int coordinate frame is initialsed
static const struct usb_device_descriptor dev
struct LtpDef_i ned_origin_i
Definition of the local (flat earth) coordinate system.
static void mavlink_send_gps_global_origin(struct transport_tx *trans, struct link_device *dev)
Core autopilot interface common to all firmwares.
static void mavlink_send_attitude_quaternion(struct transport_tx *trans, struct link_device *dev)
#define MAVLINK_SYSID
MAVLink initialization.
pprz_t commands[COMMANDS_NB]
Storage of intermediate command values.
API to get/set the generic vehicle states.
int32_t course
GPS course over ground in rad*1e7, [0, 2*Pi]*1e7 (CW/north)
static uint8_t mode
mode holds the current sonar mode mode = 0 used at high altitude, uses 16 wave patterns mode = 1 used...
void mavlink_periodic_telemetry(void)
Send periodic mavlink messages as defined in Mavlink process of telemetry xml file.
#define AP_MODE_HOVER_CLIMB
uint16_t vsupply
supply voltage in decivolts
static void mavlink_send_autopilot_version(struct transport_tx *trans, struct link_device *dev)
void autopilot_set_motors_on(bool motors_on)
turn motors on/off, eventually depending of the current mode set kill_throttle accordingly FIXME is i...
int32_t consumed
consumption in mAh
uint8_t num_sv
number of sat in fix
static char mavlink_param_names[NB_SETTING][16+1]
mavlink parameter names.
uint16_t gspeed
norm of 2d ground speed in cm/s
float energy
consumed energy in mAh
bool autopilot_guided_move_ned(float vx, float vy, float vz, float heading)
Set velocity and heading setpoints in GUIDED mode.
struct Electrical electrical
#define AP_MODE_ATTITUDE_DIRECT
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
void parse_rc_4ch_datalink(uint8_t mode, uint8_t throttle, int8_t roll, int8_t pitch, int8_t yaw)
Decode datalink message to get rc values with RC_4CH message.
static void mavlink_send_battery_status(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_global_position_int(struct transport_tx *trans, struct link_device *dev)
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
#define AP_MODE_CARE_FREE_DIRECT
mavlink_mission_mgr mission_mgr
int32_t lat
in degrees*1e7
static void mavlink_send_vfr_hud(struct transport_tx *trans, struct link_device *dev)
Send Metrics typically displayed on a HUD for fixed wing aircraft.
static struct NedCoor_f * stateGetPositionNed_f(void)
Get position in local NED coordinates (float).
#define AP_MODE_ATTITUDE_Z_HOLD
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
static uint8_t mavlink_params_idx
Transmitting parameters index.
struct GpsState gps
global GPS state
static void mavlink_send_heartbeat(struct transport_tx *trans, struct link_device *dev)
Send a heartbeat.
bool autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw)
Set position and heading setpoints wrt.
static struct LlaCoor_i * stateGetPositionLla_i(void)
Get position in LLA coordinates (int).
bool autopilot_guided_goto_ned(float x, float y, float z, float heading)
Set position and heading setpoints in GUIDED mode.
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
#define MAVLinkChAvailable()
uint8_t autopilot_get_mode(void)
get autopilot mode
static void mavlink_send_params(struct transport_tx *trans, struct link_device *dev)
Send the parameters.
static void mavlink_send_sys_status(struct transport_tx *trans, struct link_device *dev)
Send the system status.