Robot Control Library
Mavlink_Helpers

Description

helper functions for the most common mavlink packets.

<rc/mavlink_udp_helpers.h>

For use with the functions in mavlink_udp.h

Author
James Strawson & Henry Gaudet
Date
1/24/2018

Functions

int rc_mav_send_heartbeat_abbreviated (void)
 Constructs and sends a heartbeat packet of type MAVLINK_MSG_ID_HEARTBEAT. More...
 
int rc_mav_send_heartbeat (uint32_t custom_mode, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint8_t system_status)
 Constructs and sends a heartbeat packet of type MAVLINK_MSG_ID_HEARTBEAT. More...
 
int rc_mav_get_heartbeat (mavlink_heartbeat_t *data)
 fetches the most recently received heartbeat packet of type MAVLINK_MSG_ID_HEARTBEAT More...
 
int rc_mav_send_attitude (float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
 Send and attitude packet of type MAVLINK_MSG_ID_ATTITUDE. More...
 
int rc_mav_get_attitude (mavlink_attitude_t *data)
 Fetches the last attitude packet of type MAVLINK_MSG_ID_ATTITUDE. More...
 
int rc_mav_send_attitude_quaternion (float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
 Packs and sends an attitude quaternion packet of type MAVLINK_MSG_ID_ATTITUDE_QUATERNION. More...
 
int rc_mav_get_attitude_quaternion (mavlink_attitude_quaternion_t *data)
 Fetches and unpacks the last received MAVLINK_MSG_ID_ATTITUDE_QUATERNION. More...
 
int rc_mav_send_local_position_ned (float x, float y, float z, float vx, float vy, float vz)
 Packs and sends a local position NED packet of type MAVLINK_MSG_ID_LOCAL_POSITION_NED. More...
 
int rc_mav_get_local_position_ned (mavlink_local_position_ned_t *data)
 Fetches and unpacks the last received MAVLINK_MSG_ID_LOCAL_POSITION_NED. More...
 
int rc_mav_send_global_position_int (int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
 Packs and sends a packet of type MAVLINK_MSG_ID_GLOBAL_POSITION_INT. More...
 
int rc_mav_get_global_position_int (mavlink_global_position_int_t *data)
 Fetches and unpacks the last received MAVLINK_MSG_ID_GLOBAL_POSITION_INT. More...
 
int rc_mav_send_set_position_target_local_ned (float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate, uint16_t type_mask, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame)
 Packs and sends a packet of type MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED. More...
 
int rc_mav_get_set_position_target_local_ned (mavlink_set_position_target_local_ned_t *data)
 fetches and unpacks the most recently received packet of type MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED More...
 
int rc_mav_send_set_position_target_global_int (int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate, uint16_t type_mask, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame)
 Packs and sends a packet of type MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT. More...
 
int rc_mav_get_set_position_target_global_int (mavlink_set_position_target_global_int_t *data)
 Fetches and unpacks the last received packet of type MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT. More...
 
int rc_mav_send_gps_raw_int (int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t fix_type, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)
 Packs and sends a packet of type MAVLINK_MSG_ID_GPS_RAW_INT. More...
 
int rc_mav_get_gps_raw_int (mavlink_gps_raw_int_t *data)
 Fetches and unpacks a packet of type MAVLINK_MSG_ID_GPS_RAW_INT. More...
 
int rc_mav_send_scaled_pressure (float press_abs, float press_diff, int16_t temperature)
 Packs and sends a packet of type MAVLINK_MSG_ID_SCALED_PRESSURE. More...
 
int rc_mav_get_scaled_pressure (mavlink_scaled_pressure_t *data)
 Fetches and unpacks last received packet of type MAVLINK_MSG_ID_SCALED_PRESSURE. More...
 
int rc_mav_send_servo_output_raw (uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw, uint8_t port, uint16_t servo9_raw, uint16_t servo10_raw, uint16_t servo11_raw, uint16_t servo12_raw, uint16_t servo13_raw, uint16_t servo14_raw, uint16_t servo15_raw, uint16_t servo16_raw)
 Packs and sends packet of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW. More...
 
int rc_mav_get_servo_output_raw (mavlink_servo_output_raw_t *data)
 Fetch and unpack message of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW. More...
 
int rc_mav_send_sys_status (uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4, int8_t battery_remaining)
 { function_description } More...
 
int rc_mav_get_sys_status (mavlink_sys_status_t *data)
 Fetch and unpack packet of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW. More...
 
int rc_mav_send_manual_control (int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons, uint8_t target)
 Pack and send message of type MAVLINK_MSG_ID_MANUAL_CONTROL. More...
 
int rc_mav_get_manual_control (mavlink_manual_control_t *data)
 Fetch and unpack the last received message of type MAVLINK_MSG_ID_MANUAL_CONTROL. More...
 
int rc_mav_send_att_pos_mocap (float q[4], float x, float y, float z)
 Packs and send a message of type MAVLINK_MSG_ID_ATT_POS_MOCAP. More...
 
int rc_mav_get_att_pos_mocap (mavlink_att_pos_mocap_t *data)
 Fetche and unpacks last received packet of type MAVLINK_MSG_ID_ATT_POS_MOCAP. More...
 

Function Documentation

◆ rc_mav_send_heartbeat_abbreviated()

int rc_mav_send_heartbeat_abbreviated ( void  )

Constructs and sends a heartbeat packet of type MAVLINK_MSG_ID_HEARTBEAT.

This is a shortcut for rc_mav_send_heartbeat for those which don't wish to populate all of the availbale fields in the mavlink heartbeat packet. It still sends a complete heartbeat packet but with all 0's in the packet payload fields. The receiver can still see the system_id of the sender and this still serves the primary purpose to the heartbeat packet which is to indicate that a communication channel is open and functioning.

Returns
0 on success or -1 on failure.
Examples:
rc_test_mavlink.c.

◆ rc_mav_send_heartbeat()

int rc_mav_send_heartbeat ( uint32_t  custom_mode,
uint8_t  type,
uint8_t  autopilot,
uint8_t  base_mode,
uint8_t  system_status 
)

Constructs and sends a heartbeat packet of type MAVLINK_MSG_ID_HEARTBEAT.

Constructs and sends a heartbeat packet to the previously set destination ip address. The arguments encompass all available parameters in the heartbeat packet. However, many users will not be bothered to populate these parameters and may opt to use rc_mav_send_heartbeat_abbreviated() instead.

Parameters
[in]custom_modeA bitfield for use for autopilot-specific flags.
[in]typeType of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
[in]autopilotAutopilot type / class. defined in MAV_AUTOPILOT ENUM
[in]base_modeSystem mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
[in]system_statusSystem status flag, see MAV_STATE ENUM
Returns
0 on success, -1 on failure

◆ rc_mav_get_heartbeat()

int rc_mav_get_heartbeat ( mavlink_heartbeat_t *  data)

fetches the most recently received heartbeat packet of type MAVLINK_MSG_ID_HEARTBEAT

Parameters
[out]datapointer to put heartbeat packet data
Returns
0 on success, -1 on failure for example if no message has been received of type msg_id.

◆ rc_mav_send_attitude()

int rc_mav_send_attitude ( float  roll,
float  pitch,
float  yaw,
float  rollspeed,
float  pitchspeed,
float  yawspeed 
)

Send and attitude packet of type MAVLINK_MSG_ID_ATTITUDE.

Parameters
[in]rollRoll angle (rad, -pi..+pi)
[in]pitchPitch angle (rad, -pi..+pi)
[in]yawYaw angle (rad, -pi..+pi)
[in]rollspeedRoll angular speed (rad/s)
[in]pitchspeedPitch angular speed (rad/s)
[in]yawspeedYaw angular speed (rad/s)
Returns
0 on success, -1 on failure

◆ rc_mav_get_attitude()

int rc_mav_get_attitude ( mavlink_attitude_t *  data)

Fetches the last attitude packet of type MAVLINK_MSG_ID_ATTITUDE.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_attitude_quaternion()

int rc_mav_send_attitude_quaternion ( float  q1,
float  q2,
float  q3,
float  q4,
float  rollspeed,
float  pitchspeed,
float  yawspeed 
)

Packs and sends an attitude quaternion packet of type MAVLINK_MSG_ID_ATTITUDE_QUATERNION.

Parameters
[in]q1Quaternion component 1
[in]q2Quaternion component 2
[in]q3Quaternion component 3
[in]q4Quaternion component 4
[in]rollspeedRoll angular speed (rad/s)
[in]pitchspeedPitch angular speed (rad/s)
[in]yawspeedYaw angular speed (rad/s)
Returns
0 on success, -1 on failure

◆ rc_mav_get_attitude_quaternion()

int rc_mav_get_attitude_quaternion ( mavlink_attitude_quaternion_t *  data)

Fetches and unpacks the last received MAVLINK_MSG_ID_ATTITUDE_QUATERNION.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_local_position_ned()

int rc_mav_send_local_position_ned ( float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz 
)

Packs and sends a local position NED packet of type MAVLINK_MSG_ID_LOCAL_POSITION_NED.

Parameters
[in]xX Position (meters)
[in]yY Position (meters)
[in]zZ Position (meters)
[in]vxX Speed (m/s)
[in]vyY Speed (m/s)
[in]vzZ Speed (m/s)
Returns
0 on success, -1 on failure

◆ rc_mav_get_local_position_ned()

int rc_mav_get_local_position_ned ( mavlink_local_position_ned_t *  data)

Fetches and unpacks the last received MAVLINK_MSG_ID_LOCAL_POSITION_NED.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_global_position_int()

int rc_mav_send_global_position_int ( int32_t  lat,
int32_t  lon,
int32_t  alt,
int32_t  relative_alt,
int16_t  vx,
int16_t  vy,
int16_t  vz,
uint16_t  hdg 
)

Packs and sends a packet of type MAVLINK_MSG_ID_GLOBAL_POSITION_INT.

Parameters
[in]latLatitude, expressed as * 1E7
[in]lonLongitude, expressed as * 1E7
[in]altAltitude in meters, expressed as * 1000 (millimeters), above MSL
[in]relative_altAltitude above ground in meters, expressed as * 1000 (millimeters)
[in]vxGround X Speed (Latitude), expressed as m/s * 100
[in]vyGround Y Speed (Longitude), expressed as m/s * 100
[in]vzGround Z Speed (Altitude), expressed as m/s * 100
[in]hdgCompass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
Returns
0 on success, -1 on failure

◆ rc_mav_get_global_position_int()

int rc_mav_get_global_position_int ( mavlink_global_position_int_t *  data)

Fetches and unpacks the last received MAVLINK_MSG_ID_GLOBAL_POSITION_INT.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_set_position_target_local_ned()

int rc_mav_send_set_position_target_local_ned ( float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz,
float  afx,
float  afy,
float  afz,
float  yaw,
float  yaw_rate,
uint16_t  type_mask,
uint8_t  target_system,
uint8_t  target_component,
uint8_t  coordinate_frame 
)

Packs and sends a packet of type MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED.

Parameters
[in]xX Position in NED frame in m
[in]yY Position in NED frame in m
[in]zZ Position in NED frame in meters (note, altitude is negative in NED)
[in]vxX velocity in NED frame in m/s
[in]vyY velocity in NED frame in m/s
[in]vzZ velocity in NED frame in m/s
[in]afxX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
[in]afyY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
[in]afzZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
[in]yawyaw setpoint in rad
[in]yaw_rateyaw rate setpoint in rad/s
[in]type_maskBitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
[in]target_systemSystem ID of the target system
[in]target_componentComponent ID
[in]coordinate_frameValid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
Returns
0 on success, -1 on failure

◆ rc_mav_get_set_position_target_local_ned()

int rc_mav_get_set_position_target_local_ned ( mavlink_set_position_target_local_ned_t *  data)

fetches and unpacks the most recently received packet of type MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_set_position_target_global_int()

int rc_mav_send_set_position_target_global_int ( int32_t  lat_int,
int32_t  lon_int,
float  alt,
float  vx,
float  vy,
float  vz,
float  afx,
float  afy,
float  afz,
float  yaw,
float  yaw_rate,
uint16_t  type_mask,
uint8_t  target_system,
uint8_t  target_component,
uint8_t  coordinate_frame 
)

Packs and sends a packet of type MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT.

Parameters
[in]lat_intX Position in WGS84 frame in 1e7 * degrees
[in]lon_intY Position in WGS84 frame in 1e7 * degrees
[in]altAltitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
[in]vxX velocity in NED frame in m/s
[in]vyY velocity in NED frame in m/s
[in]vzZ velocity in NED frame in m/s
[in]afxX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
[in]afyY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
[in]afzZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter/s^2 or N
[in]yawyaw setpoint in rad
[in]yaw_rateyaw rate setpoint in rad/s
[in]type_maskBitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
[in]target_systemSystem ID
[in]target_componentComponent ID
[in]coordinate_frameValid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
Returns
0 on success, -1 on failure

◆ rc_mav_get_set_position_target_global_int()

int rc_mav_get_set_position_target_global_int ( mavlink_set_position_target_global_int_t *  data)

Fetches and unpacks the last received packet of type MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_gps_raw_int()

int rc_mav_send_gps_raw_int ( int32_t  lat,
int32_t  lon,
int32_t  alt,
uint16_t  eph,
uint16_t  epv,
uint16_t  vel,
uint16_t  cog,
uint8_t  fix_type,
uint8_t  satellites_visible,
int32_t  alt_ellipsoid,
uint32_t  h_acc,
uint32_t  v_acc,
uint32_t  vel_acc,
uint32_t  hdg_acc 
)

Packs and sends a packet of type MAVLINK_MSG_ID_GPS_RAW_INT.

Parameters
[in]latLatitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
[in]lonLongitude (WGS84, EGM96 ellipsoid), in degrees * 1E7
[in]altAltitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
[in]ephGPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
[in]epvGPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
[in]velGPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
[in]cogCourse over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
[in]fix_typeSee the GPS_FIX_TYPE enum.
[in]satellites_visibleNumber of satellites visible. If unknown, set to 255
[in]alt_ellipsoidAltitude (above WGS84, EGM96 ellipsoid), in meters * 1000 (positive for up).
[in]h_accPosition uncertainty in meters * 1000 (positive for up).
[in]v_accAltitude uncertainty in meters * 1000 (positive for up).
[in]vel_accSpeed uncertainty in meters * 1000 (positive for up).
[in]hdg_accHeading / track uncertainty in degrees * 1e5.
Returns
0 on success, -1 on failure

◆ rc_mav_get_gps_raw_int()

int rc_mav_get_gps_raw_int ( mavlink_gps_raw_int_t *  data)

Fetches and unpacks a packet of type MAVLINK_MSG_ID_GPS_RAW_INT.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_scaled_pressure()

int rc_mav_send_scaled_pressure ( float  press_abs,
float  press_diff,
int16_t  temperature 
)

Packs and sends a packet of type MAVLINK_MSG_ID_SCALED_PRESSURE.

Parameters
[in]press_absAbsolute pressure (hectopascal)
[in]press_diffDifferential pressure 1 (hectopascal)
[in]temperatureTemperature measurement (0.01 degrees celsius)
Returns
0 on success, -1 on failure

◆ rc_mav_get_scaled_pressure()

int rc_mav_get_scaled_pressure ( mavlink_scaled_pressure_t *  data)

Fetches and unpacks last received packet of type MAVLINK_MSG_ID_SCALED_PRESSURE.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_servo_output_raw()

int rc_mav_send_servo_output_raw ( uint16_t  servo1_raw,
uint16_t  servo2_raw,
uint16_t  servo3_raw,
uint16_t  servo4_raw,
uint16_t  servo5_raw,
uint16_t  servo6_raw,
uint16_t  servo7_raw,
uint16_t  servo8_raw,
uint8_t  port,
uint16_t  servo9_raw,
uint16_t  servo10_raw,
uint16_t  servo11_raw,
uint16_t  servo12_raw,
uint16_t  servo13_raw,
uint16_t  servo14_raw,
uint16_t  servo15_raw,
uint16_t  servo16_raw 
)

Packs and sends packet of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW.

Parameters
[in]servo1_rawServo output 1 value, in microseconds
[in]servo2_rawServo output 2 value, in microseconds
[in]servo3_rawServo output 3 value, in microseconds
[in]servo4_rawServo output 4 value, in microseconds
[in]servo5_rawServo output 5 value, in microseconds
[in]servo6_rawServo output 6 value, in microseconds
[in]servo7_rawServo output 7 value, in microseconds
[in]servo8_rawServo output 8 value, in microseconds
[in]portServo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
[in]servo9_rawServo output 9 value, in microseconds
[in]servo10_rawServo output 10 value, in microseconds
[in]servo11_rawServo output 11 value, in microseconds
[in]servo12_rawServo output 12 value, in microseconds
[in]servo13_rawServo output 13 value, in microseconds
[in]servo14_rawServo output 14 value, in microseconds
[in]servo15_rawServo output 15 value, in microseconds
[in]servo16_rawServo output 16 value, in microseconds
Returns
0 on success, -1 on failure

◆ rc_mav_get_servo_output_raw()

int rc_mav_get_servo_output_raw ( mavlink_servo_output_raw_t *  data)

Fetch and unpack message of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_sys_status()

int rc_mav_send_sys_status ( uint32_t  onboard_control_sensors_present,
uint32_t  onboard_control_sensors_enabled,
uint32_t  onboard_control_sensors_health,
uint16_t  load,
uint16_t  voltage_battery,
int16_t  current_battery,
uint16_t  drop_rate_comm,
uint16_t  errors_comm,
uint16_t  errors_count1,
uint16_t  errors_count2,
uint16_t  errors_count3,
uint16_t  errors_count4,
int8_t  battery_remaining 
)

{ function_description }

Parameters
[in]onboard_control_sensors_presentBitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
[in]onboard_control_sensors_enabledBitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
[in]onboard_control_sensors_healthBitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
[in]loadMaximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
[in]voltage_batteryBattery voltage, in millivolts (1 = 1 millivolt)
[in]current_batteryBattery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
[in]drop_rate_commCommunication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
[in]errors_commCommunication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
[in]errors_count1Autopilot-specific errors
[in]errors_count2Autopilot-specific errors
[in]errors_count3Autopilot-specific errors
[in]errors_count4Autopilot-specific errors
[in]battery_remainingRemaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
Returns
0 on success, -1 on failure

◆ rc_mav_get_sys_status()

int rc_mav_get_sys_status ( mavlink_sys_status_t *  data)

Fetch and unpack packet of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_manual_control()

int rc_mav_send_manual_control ( int16_t  x,
int16_t  y,
int16_t  z,
int16_t  r,
uint16_t  buttons,
uint8_t  target 
)

Pack and send message of type MAVLINK_MSG_ID_MANUAL_CONTROL.

Parameters
[in]xX-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
[in]yY-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
[in]zZ-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
[in]rR-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
[in]buttonsA bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
[in]targetThe system to be controlled.
Returns
0 on success, -1 on failure

◆ rc_mav_get_manual_control()

int rc_mav_get_manual_control ( mavlink_manual_control_t *  data)

Fetch and unpack the last received message of type MAVLINK_MSG_ID_MANUAL_CONTROL.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure

◆ rc_mav_send_att_pos_mocap()

int rc_mav_send_att_pos_mocap ( float  q[4],
float  x,
float  y,
float  z 
)

Packs and send a message of type MAVLINK_MSG_ID_ATT_POS_MOCAP.

Parameters
qAttitude quaternion, w, x, y, z order, zero-rotation is (1,0,0,0)
[in]xX position in meters (NED)
[in]yY position in meters (NED)
[in]zZ position in meters (NED)
Returns
0 on success, -1 on failure

◆ rc_mav_get_att_pos_mocap()

int rc_mav_get_att_pos_mocap ( mavlink_att_pos_mocap_t *  data)

Fetche and unpacks last received packet of type MAVLINK_MSG_ID_ATT_POS_MOCAP.

Parameters
[out]dataPointer to user's packet struct to be populated with new data
Returns
0 on success, -1 on failure