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,
312 #ifdef ROTORCRAFT_FIRMWARE
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;
441 #if defined(FIXEDWING_FIRMWARE)
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;
459 #elif defined(ROTORCRAFT_FIRMWARE)
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;
490 #error "mavlink datalink: unsupported firmware"
494 mav_state = MAV_STATE_STANDBY;
496 mav_state = MAV_STATE_ACTIVE;
497 mav_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
500 mavlink_msg_heartbeat_send(MAVLINK_COMM_0,
515 #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)
517 mavlink_msg_sys_status_send(MAVLINK_COMM_0,
550 mavlink_msg_attitude_send(MAVLINK_COMM_0,
563 mavlink_msg_local_position_ned_send(MAVLINK_COMM_0,
583 mavlink_msg_global_position_int_send(MAVLINK_COMM_0,
599 mavlink_msg_gps_global_origin_send(MAVLINK_COMM_0,
616 mavlink_msg_param_value_send(MAVLINK_COMM_0,
619 MAV_PARAM_TYPE_REAL32,
630 static uint32_t ver = PPRZ_VERSION_INT;
632 get_pprz_git_version((
uint8_t *)&sha);
633 mavlink_msg_autopilot_version_send(MAVLINK_COMM_0,
651 mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_0,
674 mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
708 for (
uint8_t i = 0; i < nb_sats; i++) {
724 mavlink_msg_gps_status_send(MAVLINK_COMM_0,
725 gps.
num_sv, prn, used, elevation, azimuth, snr);
730 #if defined RADIO_CONTROL
733 #ifdef PPM_PULSE_TYPE_POSITIVE
734 #define RC_CHANNELS RADIO_CTL_NB
736 #define PPM_PULSES(_i) ((_i) < RADIO_CTL_NB ? ppm_pulses[(_i)] : UINT16_MAX)
739 #define RC_CHANNELS RADIO_CONTROL_NB_CHANNEL
740 #define PPM_OF_PPRZ(_v) ((_v) / 19.2 + 1500)
741 #define PPM_PULSES(_i) ((_i) < RADIO_CONTROL_NB_CHANNEL ? PPM_OF_PPRZ(radio_control.values[(_i)]) + MAX_PPRZ : UINT16_MAX)
747 #if defined RADIO_CONTROL
748 mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
759 mavlink_msg_rc_channels_send(MAVLINK_COMM_0,
762 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
763 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
764 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
765 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
766 UINT16_MAX, UINT16_MAX, 255);
778 mavlink_msg_battery_status_send(MAVLINK_COMM_0,
802 #ifdef COMMAND_THRUST
804 #elif defined COMMAND_THROTTLE
807 mavlink_msg_vfr_hud_send(MAVLINK_COMM_0,
818 #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_get_motors_on(void)
get motors status
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...
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
int8_t elev
elevation in deg
struct LlaCoor_i lla_pos
position in LLA (lat,lon: deg*1e7; alt: mm over ellipsoid)
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.
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
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 hmsl
Height above mean sea level in mm.
int32_t alt
in millimeters above WGS84 reference ellipsoid
struct LlaCoor_i lla
Reference point in lla.
int32_t lon
in degrees*1e7
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).
struct LtpDef_f ned_origin_f
Definition of the local (flat earth) coordinate system.
struct LtpDef_i ned_origin_i
Definition of the local (flat earth) coordinate system.
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 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).
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_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 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.
float hmsl
Height above mean sea level in meters.
Generic interface for radio control modules.
#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.