|
Paparazzi UAS
v5.12_stable-4-g9b43e9b
Paparazzi is a free software Unmanned Aircraft System.
|
Basic MAVLink datalink implementation. More...
#include "modules/datalink/mavlink.h"#include "mavlink/paparazzi/mavlink.h"#include "subsystems/datalink/telemetry_common.h"#include "generated/periodic_telemetry.h"#include "generated/airframe.h"#include "generated/modules.h"#include "generated/settings.h"#include "mcu_periph/sys_time.h"#include "subsystems/electrical.h"#include "state.h"#include "pprz_version.h"#include "autopilot.h"#include "autopilot_guided.h"#include "subsystems/radio_control.h"#include "modules/datalink/missionlib/mission_manager.h"#include <stdint.h>#include "subsystems/gps.h"#include "subsystems/commands.h"
Include dependency graph for mavlink.c:Go to the source code of this file.
Macros | |
| #define | PERIODIC_C_MAVLINK |
| #define | MAVLINK_SYSID AC_ID |
| MAVLink initialization. More... | |
| #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) |
| #define | RC_CHANNELS RADIO_CONTROL_NB_CHANNEL |
| #define | PPM_OF_PPRZ(_v) ((_v) / 19.2 + 1500) |
| #define | PPM_PULSES(_i) ((_i) < RADIO_CONTROL_NB_CHANNEL ? PPM_OF_PPRZ(radio_control.values[(_i)]) + MAX_PPRZ : UINT16_MAX) |
Functions | |
| void | mavlink_common_message_handler (const mavlink_message_t *msg) |
| static void | mavlink_send_heartbeat (struct transport_tx *trans, struct link_device *dev) |
| Send a heartbeat. More... | |
| static void | mavlink_send_sys_status (struct transport_tx *trans, struct link_device *dev) |
| Send the system status. More... | |
| static void | mavlink_send_system_time (struct transport_tx *trans, struct link_device *dev) |
| Send SYSTEM_TIME. More... | |
| static void | mavlink_send_attitude (struct transport_tx *trans, struct link_device *dev) |
| Send the attitude. More... | |
| static void | mavlink_send_local_position_ned (struct transport_tx *trans, struct link_device *dev) |
| static void | mavlink_send_global_position_int (struct transport_tx *trans, struct link_device *dev) |
| static void | mavlink_send_params (struct transport_tx *trans, struct link_device *dev) |
| Send the parameters. More... | |
| static void | mavlink_send_autopilot_version (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_gps_raw_int (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_battery_status (struct transport_tx *trans, struct link_device *dev) |
| static void | mavlink_send_gps_global_origin (struct transport_tx *trans, struct link_device *dev) |
| static void | mavlink_send_gps_status (struct transport_tx *trans, struct link_device *dev) |
| Send gps status. More... | |
| 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. More... | |
| void | mavlink_init (void) |
| Module functions. More... | |
| void | mavlink_periodic_telemetry (void) |
| Send periodic mavlink messages as defined in Mavlink process of telemetry xml file. More... | |
| void | mavlink_periodic (void) |
| Periodic MAVLink calls. More... | |
| static int16_t | settings_idx_from_param_id (char *param_id) |
| void | mavlink_event (void) |
| Event MAVLink calls. More... | |
Variables | |
| mavlink_system_t | mavlink_system |
| static uint8_t | mavlink_params_idx = NB_SETTING |
| Transmitting parameters index. More... | |
| static char | mavlink_param_names [NB_SETTING][16+1] = SETTINGS_NAMES_SHORT |
| mavlink parameter names. More... | |
| static uint8_t | custom_version [8] |
| first 8 bytes (16 chars) of GIT SHA1 More... | |
| mavlink_mission_mgr | mission_mgr |
Basic MAVLink datalink implementation.
Definition in file mavlink.c.
| #define MAVLINK_SYSID AC_ID |
| #define PPM_PULSES | ( | _i | ) | ((_i) < RADIO_CONTROL_NB_CHANNEL ? PPM_OF_PPRZ(radio_control.values[(_i)]) + MAX_PPRZ : UINT16_MAX) |
Definition at line 739 of file mavlink.c.
Referenced by mavlink_send_rc_channels().
| #define RC_CHANNELS RADIO_CONTROL_NB_CHANNEL |
Definition at line 737 of file mavlink.c.
Referenced by mavlink_send_rc_channels().
| #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) |
Referenced by mavlink_send_sys_status().
| void mavlink_common_message_handler | ( | const mavlink_message_t * | msg | ) |
Definition at line 222 of file mavlink.c.
References AP_MODE_GUIDED, AP_MODE_NAV, autopilot_get_mode(), autopilot_get_motors_on(), autopilot_guided_goto_body_relative(), autopilot_guided_goto_ned(), autopilot_guided_goto_ned_relative(), autopilot_guided_move_ned(), autopilot_set_mode(), autopilot_set_motors_on(), FALSE, idx, MAVLINK_DEBUG, mavlink_param_names, mavlink_params_idx, MAVLinkSendMessage, mode, parse_rc_4ch_datalink(), settings_idx_from_param_id(), target, and TRUE.
Referenced by mavlink_event().
Here is the call graph for this function:
Here is the caller graph for this function:| void mavlink_event | ( | void | ) |
Event MAVLink calls.
Definition at line 205 of file mavlink.c.
References mavlink_common_message_handler(), mavlink_mission_message_handler(), MAVLinkChAvailable, MAVLinkGetch, and msg.
Here is the call graph for this function:| void mavlink_init | ( | void | ) |
Module functions.
Definition at line 107 of file mavlink.c.
References custom_version, mavlink_mission_init(), mavlink_send_attitude(), mavlink_send_attitude_quaternion(), mavlink_send_autopilot_version(), mavlink_send_battery_status(), mavlink_send_global_position_int(), mavlink_send_gps_global_origin(), mavlink_send_gps_raw_int(), mavlink_send_gps_status(), mavlink_send_heartbeat(), mavlink_send_local_position_ned(), mavlink_send_rc_channels(), mavlink_send_sys_status(), mavlink_send_system_time(), mavlink_send_vfr_hud(), MAVLINK_SYSID, mavlink_system, and register_periodic_telemetry().
Here is the call graph for this function:| void mavlink_periodic | ( | void | ) |
Periodic MAVLink calls.
Called at MAVLINK_PERIODIC_FREQ (set in module xml to 10Hz)
Definition at line 151 of file mavlink.c.
References mavlink_mission_periodic(), mavlink_send_attitude(), mavlink_send_attitude_quaternion(), mavlink_send_autopilot_version(), mavlink_send_battery_status(), mavlink_send_global_position_int(), mavlink_send_gps_global_origin(), mavlink_send_gps_raw_int(), mavlink_send_gps_status(), mavlink_send_heartbeat(), mavlink_send_local_position_ned(), mavlink_send_params(), mavlink_send_rc_channels(), mavlink_send_sys_status(), mavlink_send_system_time(), and mavlink_send_vfr_hud().
Here is the call graph for this function:| void mavlink_periodic_telemetry | ( | void | ) |
|
static |
Send the attitude.
Definition at line 546 of file mavlink.c.
References get_sys_time_msec(), MAVLinkSendMessage, p, stateGetBodyRates_f(), and stateGetNedToBodyEulers_f().
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Definition at line 647 of file mavlink.c.
References get_sys_time_msec(), MAVLinkSendMessage, p, stateGetBodyRates_f(), and stateGetNedToBodyQuat_f().
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
TODO: fill in versions correctly, how should they be encoded?
Definition at line 625 of file mavlink.c.
References MAVLinkSendMessage.
Referenced by mavlink_init(), and mavlink_periodic().
Here is the caller graph for this function:
|
static |
TODO: check what all these fields are supposed to represent
Definition at line 770 of file mavlink.c.
References Electrical::consumed, Electrical::current, electrical, Electrical::energy, MAVLinkSendMessage, and Electrical::vsupply.
Referenced by mavlink_init(), and mavlink_periodic().
Here is the caller graph for this function:
|
static |
TODO: check/ask what coordinate system vel is supposed to be in, not clear from docs
Definition at line 572 of file mavlink.c.
References LlaCoor_i::alt, get_sys_time_msec(), heading, LtpDef_f::hmsl, MAVLinkSendMessage, State::ned_origin_f, state, stateGetNedToBodyEulers_f(), stateGetPositionLla_i(), and stateGetSpeedNed_f().
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Definition at line 594 of file mavlink.c.
References LtpDef_i::hmsl, LlaCoor_i::lat, LtpDef_i::lla, LlaCoor_i::lon, MAVLinkSendMessage, State::ned_initialized_i, State::ned_origin_i, and state.
Referenced by mavlink_init(), and mavlink_periodic().
Here is the caller graph for this function:
|
static |
Definition at line 665 of file mavlink.c.
References LlaCoor_i::alt, course, GpsState::course, GpsState::fix, get_sys_time_usec(), gps, GpsState::gspeed, LlaCoor_i::lat, GpsState::lla_pos, LlaCoor_i::lon, MAVLinkSendMessage, GpsState::num_sv, and GpsState::pdop.
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Send gps status.
The GPS status message consists of:
Definition at line 697 of file mavlink.c.
References SVinfo::azim, SVinfo::cno, SVinfo::elev, gps, GPS_NB_CHANNELS, MAVLinkSendMessage, Min, GpsState::num_sv, SVinfo::svid, and GpsState::svinfos.
Referenced by mavlink_init(), and mavlink_periodic().
Here is the caller graph for this function:
|
static |
Send a heartbeat.
Definition at line 437 of file mavlink.c.
References AP_MODE_ATTITUDE_CLIMB, AP_MODE_ATTITUDE_DIRECT, AP_MODE_ATTITUDE_RC_CLIMB, AP_MODE_ATTITUDE_Z_HOLD, AP_MODE_AUTO1, AP_MODE_AUTO2, AP_MODE_CARE_FREE_DIRECT, AP_MODE_GUIDED, AP_MODE_HOME, AP_MODE_HOVER_CLIMB, AP_MODE_HOVER_DIRECT, AP_MODE_HOVER_Z_HOLD, AP_MODE_MANUAL, AP_MODE_NAV, AP_MODE_RATE_DIRECT, AP_MODE_RATE_RC_CLIMB, AP_MODE_RATE_Z_HOLD, AP_MODE_RC_DIRECT, autopilot_get_mode(), autopilot_throttle_killed(), MAVLinkSendMessage, and stateIsAttitudeValid().
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Definition at line 559 of file mavlink.c.
References get_sys_time_msec(), MAVLinkSendMessage, stateGetPositionNed_f(), and stateGetSpeedNed_f().
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Send the parameters.
Definition at line 608 of file mavlink.c.
References mavlink_param_names, mavlink_params_idx, and MAVLinkSendMessage.
Referenced by mavlink_periodic().
Here is the caller graph for this function:
|
static |
Definition at line 743 of file mavlink.c.
References get_sys_time_msec(), MAVLinkSendMessage, PPM_PULSES, and RC_CHANNELS.
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Send the system status.
TODO: FIXME
Definition at line 510 of file mavlink.c.
References Electrical::current, electrical, MAVLinkSendMessage, UAV_SENSORS, and Electrical::vsupply.
Referenced by mavlink_init(), and mavlink_periodic().
Here is the caller graph for this function:
|
static |
Send SYSTEM_TIME.
Definition at line 537 of file mavlink.c.
References get_sys_time_msec(), and MAVLinkSendMessage.
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Send Metrics typically displayed on a HUD for fixed wing aircraft.
Definition at line 793 of file mavlink.c.
References commands, heading, MAVLinkSendMessage, MAX_PPRZ, stateGetAirspeed_f(), stateGetHorizontalSpeedNorm_f(), stateGetNedToBodyEulers_f(), stateGetPositionLla_f(), and stateGetSpeedNed_f().
Referenced by mavlink_init(), and mavlink_periodic().
Here is the call graph for this function:
Here is the caller graph for this function:
|
static |
Definition at line 177 of file mavlink.c.
References mavlink_param_names.
Referenced by mavlink_common_message_handler().
Here is the caller graph for this function:
|
static |
first 8 bytes (16 chars) of GIT SHA1
Definition at line 71 of file mavlink.c.
Referenced by mavlink_init().
|
static |
mavlink parameter names.
16 chars + 1 NULL termination.
Definition at line 70 of file mavlink.c.
Referenced by mavlink_common_message_handler(), mavlink_send_params(), and settings_idx_from_param_id().
|
static |
Transmitting parameters index.
Definition at line 66 of file mavlink.c.
Referenced by mavlink_common_message_handler(), and mavlink_send_params().
| mavlink_system_t mavlink_system |
Definition at line 64 of file mavlink.c.
Referenced by mavlink_block_message_handler(), mavlink_init(), and mavlink_wp_message_handler().
| mavlink_mission_mgr mission_mgr |
Definition at line 73 of file mavlink.c.
Referenced by mavlink_block_message_handler(), mavlink_mission_cancel_timer(), mavlink_mission_message_handler(), mavlink_mission_periodic(), mavlink_mission_set_timer(), mavlink_send_block(), mavlink_send_block_count(), mavlink_send_mission_ack(), and mavlink_wp_message_handler().