30 #pragma GCC diagnostic push
31 #pragma GCC diagnostic ignored "-Waddress-of-packed-member"
32 #pragma GCC diagnostic ignored "-Wswitch-default"
33 #pragma GCC diagnostic ignored "-Wuninitialized"
34 #include "mavlink/ardupilotmega/mavlink.h"
35 #pragma GCC diagnostic pop
37 #if PERIODIC_TELEMETRY
38 #define PERIODIC_C_MAVLINK
40 #include "generated/periodic_telemetry.h"
41 #ifndef TELEMETRY_MAVLINK_NB_MSG
42 #warning Using hardcoded msg periods. To customize specify a <process name="Mavlink" type="mavlink"> in your telemetry file.
46 #include "generated/airframe.h"
47 #include "generated/modules.h"
48 #include "generated/settings.h"
49 #include "generated/flight_plan.h"
54 #include "pprz_version.h"
58 #if defined RADIO_CONTROL
63 #ifndef MAV_AUTOPILOT_ID
64 #define MAV_AUTOPILOT_ID MAV_AUTOPILOT_PPZ
107 #ifndef MAVLINK_SYSID
108 #define MAVLINK_SYSID AC_ID
111 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
112 struct telemetry_cb_slots mavlink_cbs[TELEMETRY_MAVLINK_NB_MSG] = TELEMETRY_MAVLINK_CBS;
113 struct periodic_telemetry mavlink_telemetry = { TELEMETRY_MAVLINK_NB_MSG, mavlink_cbs };
125 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
150 #if PERIODIC_TELEMETRY && defined TELEMETRY_MAVLINK_NB_MSG
153 periodic_telemetry_send_Mavlink(&mavlink_telemetry, NULL, NULL);
163 #if !defined (TELEMETRY_MAVLINK_NB_MSG)
193 for (i = 0; i < NB_SETTING; i++) {
194 for (j = 0; j < 16; j++) {
217 mavlink_message_t
msg;
225 if (mavlink_parse_char(MAVLINK_COMM_0, test, &
msg, &
status)) {
234 switch (
msg->msgid) {
235 case MAVLINK_MSG_ID_PLAY_TUNE:
236 case MAVLINK_MSG_ID_PLAY_TUNE_V2:
240 case MAVLINK_MSG_ID_HEARTBEAT:
244 case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: {
245 mavlink_request_data_stream_t cmd;
246 mavlink_msg_request_data_stream_decode(
msg, &cmd);
248 mavlink_msg_data_stream_send(MAVLINK_COMM_0, cmd.req_stream_id, 0, 0);
254 case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: {
255 mavlink_rc_channels_override_t cmd;
256 mavlink_msg_rc_channels_override_decode(
msg, &cmd);
257 #if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK
258 uint8_t thrust = (cmd.chan3_raw - 950) * 127 / 1100;
259 int8_t roll = -(cmd.chan1_raw - 1500) * 255 / 1100 / 2;
260 int8_t pitch = -(cmd.chan2_raw - 1500) * 255 / 1100 / 2;
261 int8_t yaw = -(cmd.chan4_raw - 1500) * 255 / 1100;
262 int8_t temp_rc[4] = {roll, pitch, yaw, thrust};
271 case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
277 case MAVLINK_MSG_ID_PARAM_REQUEST_READ: {
278 mavlink_param_request_read_t cmd;
279 mavlink_msg_param_request_read_decode(
msg, &cmd);
282 if (cmd.param_index == -1) {
287 if (cmd.param_index > -1) {
288 mavlink_msg_param_value_send(MAVLINK_COMM_0,
290 settings_get_value(cmd.param_index),
291 MAV_PARAM_TYPE_REAL32,
299 case MAVLINK_MSG_ID_PARAM_SET: {
300 mavlink_param_set_t set;
301 mavlink_msg_param_set_decode(
msg, &set);
304 if ((
uint8_t) set.target_system == AC_ID) {
311 if (set.param_type == MAV_PARAM_TYPE_REAL32 &&
312 !isnan(set.param_value) && !isinf(set.param_value)) {
313 DlSetting(
idx, set.param_value);
315 mavlink_msg_param_value_send(MAVLINK_COMM_0,
317 settings_get_value(
idx),
318 MAV_PARAM_TYPE_REAL32,
328 #ifdef ROTORCRAFT_FIRMWARE
330 case MAVLINK_MSG_ID_COMMAND_LONG: {
331 mavlink_command_long_t cmd;
332 mavlink_msg_command_long_decode(
msg, &cmd);
334 if ((
uint8_t) cmd.target_system == AC_ID) {
335 uint8_t result = MAV_RESULT_UNSUPPORTED;
336 switch (cmd.command) {
338 case MAV_CMD_SET_MESSAGE_INTERVAL:
339 case MAV_CMD_DO_SET_MODE: {
341 int rc = snprintf(error_msg, 200,
"Do set %d: %0.0f %0.0f (%d)", cmd.command, cmd.param1, cmd.param2, cmd.target_system);
345 result = MAV_RESULT_ACCEPTED;
349 case MAV_CMD_NAV_GUIDED_ENABLE:
350 MAVLINK_DEBUG(
"got cmd NAV_GUIDED_ENABLE: %f\n", cmd.param1);
351 result = MAV_RESULT_FAILED;
352 if (cmd.param1 > 0.5) {
355 result = MAV_RESULT_ACCEPTED;
363 case MAV_CMD_COMPONENT_ARM_DISARM:
365 MAVLINK_DEBUG(
"got cmd COMPONENT_ARM_DISARM: %f\n", cmd.param1);
366 result = MAV_RESULT_FAILED;
367 if (cmd.param1 > 0.5) {
370 result = MAV_RESULT_ACCEPTED;
375 result = MAV_RESULT_ACCEPTED;
383 mavlink_msg_command_ack_send(MAVLINK_COMM_0, cmd.command, result, 0, UINT8_MAX,
msg->sysid,
msg->compid);
389 #ifdef WP_ML_global_target
390 case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: {
391 mavlink_set_position_target_global_int_t
target;
392 mavlink_msg_set_position_target_global_int_decode(
msg, &
target);
398 if (
target.coordinate_frame == MAV_FRAME_GLOBAL ||
target.coordinate_frame == MAV_FRAME_GLOBAL_INT) {
413 uint8_t wp_id = WP_ML_global_target;
416 &lla.
lat, &lla.
lon, &hmsl);
423 case MAVLINK_MSG_ID_SET_MODE: {
424 mavlink_set_mode_t
mode;
425 mavlink_msg_set_mode_decode(
msg, &
mode);
426 if (
mode.target_system == AC_ID) {
428 if (
mode.base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
434 if (
mode.base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
437 else if (
mode.base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
444 case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: {
445 mavlink_set_position_target_local_ned_t
target;
446 mavlink_msg_set_position_target_local_ned_decode(
msg, &
target);
448 if (
target.target_system == AC_ID) {
451 if (!(
target.type_mask & 0b1110000000100000)) {
452 switch (
target.coordinate_frame) {
453 case MAV_FRAME_LOCAL_NED:
457 case MAV_FRAME_LOCAL_OFFSET_NED:
458 MAVLINK_DEBUG(
"set position target, frame LOCAL_OFFSET_NED\n");
461 case MAV_FRAME_BODY_OFFSET_NED:
462 MAVLINK_DEBUG(
"set position target, frame BODY_OFFSET_NED\n");
469 else if (!(
target.type_mask & 0b0001110000100000)) {
471 switch (
target.coordinate_frame) {
472 case MAV_FRAME_LOCAL_NED:
493 #pragma GCC diagnostic push
494 #pragma GCC diagnostic ignored "-Wunused-parameter"
501 uint8_t mav_state = MAV_STATE_CALIBRATING;
502 uint8_t mav_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
504 #if defined(FIXEDWING_FIRMWARE)
505 uint8_t mav_type = MAV_TYPE_FIXED_WING;
508 mav_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
511 mav_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
514 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
517 mav_mode |= MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED;
522 #elif defined(ROTORCRAFT_FIRMWARE)
523 uint8_t mav_type = MAV_TYPE_QUADROTOR;
526 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
532 mav_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
542 mav_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
545 mav_mode |= MAV_MODE_FLAG_AUTO_ENABLED;
546 custom_mode = PLANE_MODE_GUIDED;
549 mav_mode = MAV_MODE_FLAG_GUIDED_ENABLED;
550 custom_mode = PLANE_MODE_GUIDED;
555 #error "mavlink datalink: unsupported firmware"
559 mav_state = MAV_STATE_STANDBY;
561 mav_state = MAV_STATE_ACTIVE;
562 mav_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
565 mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
579 mavlink_msg_extended_sys_state_send(MAVLINK_COMM_0, MAV_VTOL_STATE_UNDEFINED, landed_state);
589 #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)
591 mavlink_msg_sys_status_send(MAVLINK_COMM_0,
627 mavlink_msg_attitude_send(MAVLINK_COMM_0,
640 mavlink_msg_local_position_ned_send(MAVLINK_COMM_0,
661 mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
677 mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0,
695 mavlink_msg_param_value_send(MAVLINK_COMM_0,
698 MAV_PARAM_TYPE_REAL32,
709 static uint32_t ver = PPRZ_VERSION_INT;
711 get_pprz_git_version((
uint8_t *)&sha);
712 mavlink_msg_autopilot_version_send(MAVLINK_COMM_0,
713 18446744073709551615U,
730 float repr_offset_q[4] = {0, 0, 0, 0};
731 mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_0,
755 mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
795 for (
uint8_t i = 0; i < nb_sats; i++) {
811 mavlink_msg_gps_status_send(MAVLINK_COMM_0,
812 gps.
num_sv, prn, used, elevation, azimuth, snr);
817 #if defined RADIO_CONTROL
820 #ifdef PPM_PULSE_TYPE_POSITIVE
821 #define RC_CHANNELS RADIO_CTL_NB
823 #define PPM_PULSES(_i) ((_i) < RADIO_CTL_NB ? ppm_pulses[(_i)] : UINT16_MAX)
826 #define RC_CHANNELS RADIO_CONTROL_NB_CHANNEL
827 #define PPM_OF_PPRZ(_v) ((_v) / 19.2 + 1500)
828 #define PPM_PULSES(_i) ((_i) < RADIO_CONTROL_NB_CHANNEL ? PPM_OF_PPRZ(radio_control.values[(_i)]) + MAX_PPRZ : UINT16_MAX)
834 #if defined RADIO_CONTROL
835 mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
846 mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
849 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
850 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
851 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
852 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
853 UINT16_MAX, UINT16_MAX, 255);
865 mavlink_msg_battery_status_send(MAVLINK_COMM_0,
876 MAV_BATTERY_CHARGE_STATE_UNDEFINED,
878 MAV_BATTERY_MODE_UNKNOWN,
894 #ifdef COMMAND_THRUST
896 #elif defined COMMAND_THROTTLE
900 mavlink_msg_vfr_hud_send(MAVLINK_COMM_0,
911 #pragma GCC diagnostic pop
bool autopilot_set_mode(uint8_t new_autopilot_mode)
set autopilot mode
uint8_t autopilot_get_mode(void)
get autopilot mode
bool autopilot_set_motors_on(bool motors_on)
turn motors on/off, eventually depending of the current mode set kill_throttle accordingly FIXME is i...
bool autopilot_get_motors_on(void)
get motors status
bool autopilot_in_flight(void)
get in_flight flag
bool autopilot_throttle_killed(void)
get kill status
Core autopilot interface common to all firmwares.
bool autopilot_guided_move_ned(float vx, float vy, float vz, float heading)
Set velocity and heading setpoints in GUIDED mode.
bool autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw)
Set position and heading setpoints wrt.
bool autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw)
Set position and heading setpoints wrt.
bool autopilot_guided_goto_ned(float x, float y, float z, float heading)
Set position and heading setpoints in GUIDED mode.
Autopilot guided mode interface.
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
uint32_t get_sys_time_msec(void)
Get the time in milliseconds since startup.
pprz_t commands[COMMANDS_NB]
Hardware independent code for commands handling.
struct Electrical electrical
Interface for electrical status: supply voltage, current, battery status, etc.
float energy
consumed energy in Wh
float current
current in A
float charge
consumed electric charge in Ah
float vsupply
supply voltage in V
#define AP_MODE_MANUAL
AP modes.
struct GpsState gps
global GPS state
Device independent GPS code (interface)
int16_t azim
azimuth in deg
int32_t hmsl
height above mean sea level (MSL) in mm
int8_t elev
elevation in deg
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
uint32_t sacc
speed accuracy in cm/s
int32_t course
GPS course over ground in rad*1e7, [0, 2*Pi]*1e7 (CW/north)
uint8_t cno
Carrier to Noise Ratio (Signal Strength) in dbHz.
uint32_t hacc
horizontal accuracy in cm
uint16_t pdop
position dilution of precision scaled by 100
uint8_t svid
Satellite ID.
uint16_t gspeed
norm of 2d ground speed in cm/s
uint32_t vacc
vertical accuracy in cm
struct SVinfo svinfos[GPS_NB_CHANNELS]
holds information from the Space Vehicles (Satellites)
uint8_t num_sv
number of sat in fix
int32_t lat
in degrees*1e7
int32_t alt
in millimeters above WGS84 reference ellipsoid
int32_t lon
in degrees*1e7
void ned_of_lla_point_i(struct NedCoor_i *ned, struct LtpDef_i *def, struct LlaCoor_i *lla)
Convert a point from LLA to local NED.
vector in Latitude, Longitude and Altitude
vector in North East Down coordinates
static bool stateIsAttitudeValid(void)
Test if attitudes are valid.
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
static struct LlaCoor_i * stateGetPositionLla_i(void)
Get position in LLA coordinates (int).
bool ned_initialized_i
true if local int coordinate frame is initialsed
static struct LtpDef_i * stateGetNedOrigin_i(void)
Get the coordinate NED frame origin (int)
int32_t stateGetHmslOrigin_i(void)
Get the HMSL of the frame origin (int)
float stateGetHmslOrigin_f(void)
Get the HMSL of the frame origin (float)
static struct LlaCoor_f * stateGetPositionLla_f(void)
Get position in LLA coordinates (float).
static struct NedCoor_f * stateGetPositionNed_f(void)
Get position in local NED coordinates (float).
struct LlaCoor_i stateGetLlaOrigin_i(void)
Get the LLA position of the frame origin (int)
struct LlaCoor_f stateGetLlaOrigin_f(void)
Get the LLA position of the frame origin (float)
static struct FloatRates * stateGetBodyRates_f(void)
Get vehicle body angular rate (float).
static float stateGetHorizontalSpeedNorm_f(void)
Get norm of horizontal ground speed (float).
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
static float stateGetAirspeed_f(void)
Get airspeed (float).
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)
static int16_t settings_idx_from_param_id(char *param_id)
static uint8_t custom_version[8]
first 8 bytes (16 chars) of GIT SHA1
static void mavlink_send_autopilot_version(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_system_time(struct transport_tx *trans, struct link_device *dev)
Send SYSTEM_TIME.
static char mavlink_param_names[NB_SETTING][16+1]
mavlink parameter names.
static uint8_t mavlink_params_idx
Transmitting parameters index.
static void mavlink_send_gps_global_origin(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_gps_raw_int(struct transport_tx *trans, struct link_device *dev)
void mavlink_periodic(void)
Periodic MAVLink calls.
mavlink_system_t mavlink_system
mavlink_mission_mgr mission_mgr
#define MAVLINK_SYSID
MAVLink initialization.
static void mavlink_send_global_position_int(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_battery_status(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_attitude_quaternion(struct transport_tx *trans, struct link_device *dev)
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 mavlink_common_message_handler(const mavlink_message_t *msg)
static void mavlink_send_extended_sys_state(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_rc_channels(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_params(struct transport_tx *trans, struct link_device *dev)
Send the parameters.
static void mavlink_send_gps_status(struct transport_tx *trans, struct link_device *dev)
Send gps status.
void mavlink_periodic_telemetry(void)
Send periodic mavlink messages as defined in Mavlink process of telemetry xml file.
void mavlink_event(void)
Event MAVLink calls.
void mavlink_init(void)
Module functions.
static void mavlink_send_local_position_ned(struct transport_tx *trans, struct link_device *dev)
static void mavlink_send_attitude(struct transport_tx *trans, struct link_device *dev)
Send the attitude.
static void mavlink_send_heartbeat(struct transport_tx *trans, struct link_device *dev)
Send a heartbeat.
static void mavlink_send_sys_status(struct transport_tx *trans, struct link_device *dev)
Send the system status.
Basic MAVLink datalink implementation.
#define MAVLINK_DEBUG(...)
#define MAVLinkSendMessage()
#define MAVLinkChAvailable()
void mavlink_mission_init(mavlink_mission_mgr *mgr)
void mavlink_mission_message_handler(const mavlink_message_t *msg)
void mavlink_mission_periodic(void)
update current block and send if changed
Common functions used within the mission library, blocks and waypoints cannot be send simultaneously ...
void waypoint_set_latlon(uint8_t wp_id, struct LlaCoor_i *lla)
set waypoint latitude/longitude without updating altitude
void waypoint_set_alt(uint8_t wp_id, float alt)
Set altitude of waypoint in meters (above reference)
float alt
in meters (normally above WGS84 reference ellipsoid)
Generic interface for radio control modules.
void parse_rc_up_datalink(int8_t n, int8_t *channels)
Decode datalink message to get rc values with RC_UP message.
#define AP_MODE_HOVER_DIRECT
#define AP_MODE_RATE_DIRECT
#define AP_MODE_RATE_RC_CLIMB
#define AP_MODE_HOVER_CLIMB
#define AP_MODE_HOVER_Z_HOLD
#define AP_MODE_RC_DIRECT
#define AP_MODE_ATTITUDE_DIRECT
#define AP_MODE_ATTITUDE_CLIMB
#define AP_MODE_ATTITUDE_Z_HOLD
#define AP_MODE_ATTITUDE_RC_CLIMB
#define AP_MODE_RATE_Z_HOLD
#define AP_MODE_CARE_FREE_DIRECT
static uint8_t mode
mode holds the current sonar mode mode = 0 used at high altitude, uses 16 wave patterns mode = 1 used...
API to get/set the generic vehicle states.
static const struct usb_device_descriptor dev
Architecture independent timing functions.
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Common tools for periodic telemetry interface Allows subsystem to register callback functions.
Periodic telemetry structure.
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
int int32_t
Typedef defining 32 bit int type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
short int16_t
Typedef defining 16 bit short type.
unsigned long long uint64_t
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
signed char int8_t
Typedef defining 8 bit char type.