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"
53 #if defined RADIO_CONTROL
97 #define MAVLINK_SYSID AC_ID
100 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
101 struct telemetry_cb_slots mavlink_cbs[TELEMETRY_MAVLINK_NB_MSG] = TELEMETRY_MAVLINK_CBS;
102 struct periodic_telemetry mavlink_telemetry = { TELEMETRY_MAVLINK_NB_MSG, mavlink_cbs };
114 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
138 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
141 periodic_telemetry_send_Mavlink(&mavlink_telemetry, NULL, NULL);
151 #if !defined (TELEMETRY_MAVLINK_NB_MSG)
181 for (i = 0; i < NB_SETTING; i++) {
182 for (j = 0; j < 16; j++) {
205 mavlink_message_t
msg;
213 if (mavlink_parse_char(MAVLINK_COMM_0, test, &msg, &status)) {
222 switch (msg->msgid) {
223 case MAVLINK_MSG_ID_HEARTBEAT:
227 case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: {
228 mavlink_request_data_stream_t cmd;
229 mavlink_msg_request_data_stream_decode(msg, &cmd);
231 mavlink_msg_data_stream_send(MAVLINK_COMM_0, cmd.req_stream_id, 0, 0);
237 case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: {
238 mavlink_rc_channels_override_t cmd;
239 mavlink_msg_rc_channels_override_decode(msg, &cmd);
240 #if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK
241 uint8_t thrust = (cmd.chan3_raw - 950) * 127 / 1100;
242 int8_t roll = -(cmd.chan1_raw - 1500) * 255 / 1100 / 2;
243 int8_t pitch = -(cmd.chan2_raw - 1500) * 255 / 1100 / 2;
244 int8_t yaw = -(cmd.chan4_raw - 1500) * 255 / 1100;
253 case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
259 case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
260 mavlink_param_request_read_t cmd;
261 mavlink_msg_param_request_read_decode(msg, &cmd);
264 if (cmd.param_index == -1) {
268 mavlink_msg_param_value_send(MAVLINK_COMM_0,
270 settings_get_value(cmd.param_index),
271 MAV_PARAM_TYPE_REAL32,
279 case MAVLINK_MSG_ID_PARAM_SET: {
280 mavlink_param_set_t set;
281 mavlink_msg_param_set_decode(msg, &set);
284 if ((
uint8_t) set.target_system == AC_ID) {
291 if (set.param_type == MAV_PARAM_TYPE_REAL32 &&
292 !isnan(set.param_value) && !isinf(set.param_value)) {
293 DlSetting(idx, set.param_value);
295 mavlink_msg_param_value_send(MAVLINK_COMM_0,
297 settings_get_value(idx),
298 MAV_PARAM_TYPE_REAL32,
310 case MAVLINK_MSG_ID_COMMAND_LONG: {
311 mavlink_command_long_t cmd;
312 mavlink_msg_command_long_decode(msg, &cmd);
314 if ((
uint8_t) cmd.target_system == AC_ID) {
315 uint8_t result = MAV_RESULT_UNSUPPORTED;
316 switch (cmd.command) {
317 case MAV_CMD_NAV_GUIDED_ENABLE:
318 MAVLINK_DEBUG(
"got cmd NAV_GUIDED_ENABLE: %f\n", cmd.param1);
319 result = MAV_RESULT_FAILED;
320 if (cmd.param1 > 0.5) {
323 result = MAV_RESULT_ACCEPTED;
331 case MAV_CMD_COMPONENT_ARM_DISARM:
333 MAVLINK_DEBUG(
"got cmd COMPONENT_ARM_DISARM: %f\n", cmd.param1);
334 result = MAV_RESULT_FAILED;
335 if (cmd.param1 > 0.5) {
338 result = MAV_RESULT_ACCEPTED;
343 result = MAV_RESULT_ACCEPTED;
351 mavlink_msg_command_ack_send(MAVLINK_COMM_0, cmd.command, result);
357 case MAVLINK_MSG_ID_SET_MODE: {
358 mavlink_set_mode_t mode;
359 mavlink_msg_set_mode_decode(msg, &mode);
360 if (mode.target_system == AC_ID) {
361 MAVLINK_DEBUG(
"got SET_MODE: base_mode:%d\n", mode.base_mode);
362 if (mode.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
368 if (mode.base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
371 else if (mode.base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
378 case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: {
379 mavlink_set_position_target_local_ned_t
target;
380 mavlink_msg_set_position_target_local_ned_decode(msg, &target);
382 if (target.target_system == AC_ID) {
383 MAVLINK_DEBUG(
"SET_POSITION_TARGET_LOCAL_NED, byte_mask: %d\n", target.type_mask);
385 if (!(target.type_mask & 0b1110000000100000)) {
386 switch (target.coordinate_frame) {
387 case MAV_FRAME_LOCAL_NED:
391 case MAV_FRAME_LOCAL_OFFSET_NED:
392 MAVLINK_DEBUG(
"set position target, frame LOCAL_OFFSET_NED\n");
395 case MAV_FRAME_BODY_OFFSET_NED:
396 MAVLINK_DEBUG(
"set position target, frame BODY_OFFSET_NED\n");
410 MAVLINK_DEBUG(
"Received message with id: %d\r\n", msg->msgid);
416 #pragma GCC diagnostic push
417 #pragma GCC diagnostic ignored "-Wunused-parameter"
424 uint8_t mav_state = MAV_STATE_CALIBRATING;
427 uint8_t mav_type = MAV_TYPE_FIXED_WING;
430 mav_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
433 mav_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
436 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
439 mav_mode |= MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED;
445 uint8_t mav_type = MAV_TYPE_QUADROTOR;
448 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
454 mav_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
464 mav_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
467 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
470 mav_mode = MAV_MODE_FLAG_GUIDED_ENABLED;
477 mav_state = MAV_STATE_STANDBY;
479 mav_state = MAV_STATE_ACTIVE;
480 mav_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
483 mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
498 #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)
500 mavlink_msg_sys_status_send(MAVLINK_COMM_0,
533 mavlink_msg_attitude_send(MAVLINK_COMM_0,
546 mavlink_msg_local_position_ned_send(MAVLINK_COMM_0,
563 uint16_t compass_heading = heading * 100;
566 mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
582 mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0,
599 mavlink_msg_param_value_send(MAVLINK_COMM_0,
601 settings_get_value(mavlink_params_idx),
602 MAV_PARAM_TYPE_REAL32,
607 mavlink_params_idx++;
613 static uint32_t ver = PPRZ_VERSION_INT;
615 get_pprz_git_version((
uint8_t *)&sha);
616 mavlink_msg_autopilot_version_send(MAVLINK_COMM_0,
634 mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_0,
657 mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
691 for (
uint8_t i = 0; i < nb_sats; i++) {
707 mavlink_msg_gps_status_send(MAVLINK_COMM_0,
708 gps.
num_sv, prn, used, elevation, azimuth, snr);
713 #if defined RADIO_CONTROL
716 #ifdef PPM_PULSE_TYPE_POSITIVE
717 #define RC_CHANNELS RADIO_CTL_NB
718 #define PPM_PULSES(_i) ((_i) < RADIO_CTL_NB ? ppm_pulses[(_i)] : UINT16_MAX)
722 #define RC_CHANNELS RADIO_CONTROL_NB_CHANNEL
723 #define PPM_OF_PPRZ(_v) ((_v) / 19.2 + 1500)
724 #define PPM_PULSES(_i) ((_i) < RADIO_CONTROL_NB_CHANNEL ? PPM_OF_PPRZ(radio_control.values[(_i)]) + MAX_PPRZ : UINT16_MAX)
730 #if defined RADIO_CONTROL
731 mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
742 mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
745 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
746 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
747 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
748 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
749 UINT16_MAX, UINT16_MAX, 255);
761 mavlink_msg_battery_status_send(MAVLINK_COMM_0,
785 #ifdef COMMAND_THRUST
787 #elif defined COMMAND_THROTTLE
790 mavlink_msg_vfr_hud_send(MAVLINK_COMM_0,
801 #pragma GCC diagnostic pop
static uint32_t get_sys_time_msec(void)
Get the time in milliseconds since startup.
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.
#define AP_MODE_ATTITUDE_DIRECT
static float stateGetHorizontalSpeedNorm_f(void)
Get norm of horizontal ground speed (float).
Generic transmission transport header.
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)
bool_t autopilot_motors_on
#define AP_MODE_HOVER_DIRECT
static bool_t stateIsAttitudeValid(void)
Test if attitudes are valid.
struct LtpDef_f ned_origin_f
Definition of the local (flat earth) coordinate system.
Periodic telemetry structure.
#define AP_MODE_RATE_RC_CLIMB
#define AP_MODE_RATE_Z_HOLD
void mavlink_mission_periodic(void)
update current block and send if changed
static float stateGetAirspeed_f(void)
Get airspeed (float).
#define AP_MODE_ATTITUDE_Z_HOLD
static struct LlaCoor_f * stateGetPositionLla_f(void)
Get position in LLA coordinates (float).
void mavlink_mission_init(mavlink_mission_mgr *mgr)
void mavlink_init(void)
Module functions.
#define AP_MODE_HOVER_CLIMB
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_RATE_DIRECT
static uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
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.
bool_t autopilot_guided_goto_ned(float x, float y, float z, float heading)
Set position and heading setpoints in GUIDED mode.
mavlink_system_t mavlink_system
#define MAVLINK_DEBUG(...)
#define AP_MODE_RC_DIRECT
void mavlink_event(void)
Event MAVLink calls.
unsigned long long uint64_t
void autopilot_set_motors_on(bool_t motors_on)
bool_t autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw)
Set position and heading setpoints wrt.
#define AP_MODE_CARE_FREE_DIRECT
uint8_t cno
Carrier to Noise Ratio (Signal Strength) in dbHz.
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)
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
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).
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)
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)
void mavlink_periodic_telemetry(void)
Send periodic mavlink messages as defined in Mavlink process of telemetry xml file.
uint16_t vsupply
supply voltage in decivolts
static void mavlink_send_autopilot_version(struct transport_tx *trans, struct link_device *dev)
#define AP_MODE_HOVER_Z_HOLD
int32_t consumed
consumption in mAh
uint8_t num_sv
number of sat in fix
#define AP_MODE_ATTITUDE_RC_CLIMB
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_t autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw)
Set position and heading setpoints wrt.
struct Electrical electrical
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.
bool_t ned_initialized_i
true if local int coordinate frame is initialsed
#define PPRZ_MODE_MANUAL
AP modes.
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)
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.
void autopilot_set_mode(uint8_t new_autopilot_mode)
static struct NedCoor_f * stateGetPositionNed_f(void)
Get position in local NED coordinates (float).
#define AP_MODE_ATTITUDE_CLIMB
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.
static struct LlaCoor_i * stateGetPositionLla_i(void)
Get position in LLA coordinates (int).
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
#define MAVLinkChAvailable()
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.