16 #ifndef RC_MAVLINK_UDP_HELPERS_H 17 #define RC_MAVLINK_UDP_HELPERS_H 27 #include <rc/mavlink/common/mavlink.h> 28 #include <rc/mavlink/mavlink_types.h> 72 uint8_t system_status);
210 int32_t relative_alt,
276 uint8_t target_system,
277 uint8_t target_component,
278 uint8_t coordinate_frame);
339 uint8_t target_system,
340 uint8_t target_component,
341 uint8_t coordinate_frame);
399 uint8_t satellites_visible,
400 int32_t alt_ellipsoid,
430 int16_t temperature);
479 uint16_t servo10_raw,
480 uint16_t servo11_raw,
481 uint16_t servo12_raw,
482 uint16_t servo13_raw,
483 uint16_t servo14_raw,
484 uint16_t servo15_raw,
485 uint16_t servo16_raw);
534 uint32_t onboard_control_sensors_present,
535 uint32_t onboard_control_sensors_enabled,
536 uint32_t onboard_control_sensors_health,
538 uint16_t voltage_battery,
539 int16_t current_battery,
540 uint16_t drop_rate_comm,
541 uint16_t errors_comm,
542 uint16_t errors_count1,
543 uint16_t errors_count2,
544 uint16_t errors_count3,
545 uint16_t errors_count4,
546 int8_t battery_remaining);
640 #endif // RC_MAVLINK_UDP_HELPERS_H 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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
int rc_mav_get_scaled_pressure(mavlink_scaled_pressure_t *data)
Fetches and unpacks last received packet of type MAVLINK_MSG_ID_SCALED_PRESSURE.
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.
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.
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_NE...
int rc_mav_get_heartbeat(mavlink_heartbeat_t *data)
fetches the most recently received heartbeat packet of type MAVLINK_MSG_ID_HEARTBEAT ...
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.
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 }
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.
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. ...
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.
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.
int rc_mav_get_attitude(mavlink_attitude_t *data)
Fetches the last attitude packet of type MAVLINK_MSG_ID_ATTITUDE.
int rc_mav_send_heartbeat_abbreviated(void)
Constructs and sends a heartbeat packet of type MAVLINK_MSG_ID_HEARTBEAT.
int rc_mav_get_sys_status(mavlink_sys_status_t *data)
Fetch and unpack packet of type MAVLINK_MSG_ID_SERVO_OUTPUT_RAW.
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.
int rc_mav_get_attitude_quaternion(mavlink_attitude_quaternion_t *data)
Fetches and unpacks the last received MAVLINK_MSG_ID_ATTITUDE_QUATERNION.