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) {
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) {
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:
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,
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,
617 MAV_PARAM_TYPE_REAL32,
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