14 changed files with 1115 additions and 20 deletions
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
@ -0,0 +1,320 @@
@@ -0,0 +1,320 @@
|
||||
// MESSAGE BATTERY_STATUS PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_BATTERY_STATUS 147 |
||||
|
||||
typedef struct __mavlink_battery_status_t |
||||
{ |
||||
uint16_t voltage_cell_1; ///< Battery voltage of cell 1, in millivolts (1 = 1 millivolt)
|
||||
uint16_t voltage_cell_2; ///< Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell
|
||||
uint16_t voltage_cell_3; ///< Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell
|
||||
uint16_t voltage_cell_4; ///< Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell
|
||||
uint16_t voltage_cell_5; ///< Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell
|
||||
uint16_t voltage_cell_6; ///< Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell
|
||||
int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
|
||||
uint8_t accu_id; ///< Accupack ID
|
||||
int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
|
||||
} mavlink_battery_status_t; |
||||
|
||||
#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 16 |
||||
#define MAVLINK_MSG_ID_147_LEN 16 |
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ |
||||
"BATTERY_STATUS", \
|
||||
9, \
|
||||
{ { "voltage_cell_1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_battery_status_t, voltage_cell_1) }, \
|
||||
{ "voltage_cell_2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_battery_status_t, voltage_cell_2) }, \
|
||||
{ "voltage_cell_3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_battery_status_t, voltage_cell_3) }, \
|
||||
{ "voltage_cell_4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_battery_status_t, voltage_cell_4) }, \
|
||||
{ "voltage_cell_5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_battery_status_t, voltage_cell_5) }, \
|
||||
{ "voltage_cell_6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_battery_status_t, voltage_cell_6) }, \
|
||||
{ "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_battery_status_t, current_battery) }, \
|
||||
{ "accu_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_battery_status_t, accu_id) }, \
|
||||
{ "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 15, offsetof(mavlink_battery_status_t, battery_remaining) }, \
|
||||
} \
|
||||
} |
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a battery_status message |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param msg The MAVLink message to compress the data into |
||||
* |
||||
* @param accu_id Accupack ID |
||||
* @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt) |
||||
* @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
||||
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery |
||||
* @return length of the message in bytes (excluding serial stream start sign) |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||||
uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int8_t battery_remaining) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[16]; |
||||
_mav_put_uint16_t(buf, 0, voltage_cell_1); |
||||
_mav_put_uint16_t(buf, 2, voltage_cell_2); |
||||
_mav_put_uint16_t(buf, 4, voltage_cell_3); |
||||
_mav_put_uint16_t(buf, 6, voltage_cell_4); |
||||
_mav_put_uint16_t(buf, 8, voltage_cell_5); |
||||
_mav_put_uint16_t(buf, 10, voltage_cell_6); |
||||
_mav_put_int16_t(buf, 12, current_battery); |
||||
_mav_put_uint8_t(buf, 14, accu_id); |
||||
_mav_put_int8_t(buf, 15, battery_remaining); |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); |
||||
#else |
||||
mavlink_battery_status_t packet; |
||||
packet.voltage_cell_1 = voltage_cell_1; |
||||
packet.voltage_cell_2 = voltage_cell_2; |
||||
packet.voltage_cell_3 = voltage_cell_3; |
||||
packet.voltage_cell_4 = voltage_cell_4; |
||||
packet.voltage_cell_5 = voltage_cell_5; |
||||
packet.voltage_cell_6 = voltage_cell_6; |
||||
packet.current_battery = current_battery; |
||||
packet.accu_id = accu_id; |
||||
packet.battery_remaining = battery_remaining; |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); |
||||
#endif |
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; |
||||
return mavlink_finalize_message(msg, system_id, component_id, 16, 42); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Pack a battery_status message on a channel |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param chan The MAVLink channel this message was sent over |
||||
* @param msg The MAVLink message to compress the data into |
||||
* @param accu_id Accupack ID |
||||
* @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt) |
||||
* @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
||||
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery |
||||
* @return length of the message in bytes (excluding serial stream start sign) |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||||
mavlink_message_t* msg, |
||||
uint8_t accu_id,uint16_t voltage_cell_1,uint16_t voltage_cell_2,uint16_t voltage_cell_3,uint16_t voltage_cell_4,uint16_t voltage_cell_5,uint16_t voltage_cell_6,int16_t current_battery,int8_t battery_remaining) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[16]; |
||||
_mav_put_uint16_t(buf, 0, voltage_cell_1); |
||||
_mav_put_uint16_t(buf, 2, voltage_cell_2); |
||||
_mav_put_uint16_t(buf, 4, voltage_cell_3); |
||||
_mav_put_uint16_t(buf, 6, voltage_cell_4); |
||||
_mav_put_uint16_t(buf, 8, voltage_cell_5); |
||||
_mav_put_uint16_t(buf, 10, voltage_cell_6); |
||||
_mav_put_int16_t(buf, 12, current_battery); |
||||
_mav_put_uint8_t(buf, 14, accu_id); |
||||
_mav_put_int8_t(buf, 15, battery_remaining); |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16); |
||||
#else |
||||
mavlink_battery_status_t packet; |
||||
packet.voltage_cell_1 = voltage_cell_1; |
||||
packet.voltage_cell_2 = voltage_cell_2; |
||||
packet.voltage_cell_3 = voltage_cell_3; |
||||
packet.voltage_cell_4 = voltage_cell_4; |
||||
packet.voltage_cell_5 = voltage_cell_5; |
||||
packet.voltage_cell_6 = voltage_cell_6; |
||||
packet.current_battery = current_battery; |
||||
packet.accu_id = accu_id; |
||||
packet.battery_remaining = battery_remaining; |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16); |
||||
#endif |
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; |
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 42); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Encode a battery_status struct into a message |
||||
* |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param msg The MAVLink message to compress the data into |
||||
* @param battery_status C-struct to read the message contents from |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) |
||||
{ |
||||
return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->battery_remaining); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Send a battery_status message |
||||
* @param chan MAVLink channel to send the message |
||||
* |
||||
* @param accu_id Accupack ID |
||||
* @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt) |
||||
* @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell |
||||
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
||||
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery |
||||
*/ |
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
|
||||
static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int8_t battery_remaining) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[16]; |
||||
_mav_put_uint16_t(buf, 0, voltage_cell_1); |
||||
_mav_put_uint16_t(buf, 2, voltage_cell_2); |
||||
_mav_put_uint16_t(buf, 4, voltage_cell_3); |
||||
_mav_put_uint16_t(buf, 6, voltage_cell_4); |
||||
_mav_put_uint16_t(buf, 8, voltage_cell_5); |
||||
_mav_put_uint16_t(buf, 10, voltage_cell_6); |
||||
_mav_put_int16_t(buf, 12, current_battery); |
||||
_mav_put_uint8_t(buf, 14, accu_id); |
||||
_mav_put_int8_t(buf, 15, battery_remaining); |
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, 16, 42); |
||||
#else |
||||
mavlink_battery_status_t packet; |
||||
packet.voltage_cell_1 = voltage_cell_1; |
||||
packet.voltage_cell_2 = voltage_cell_2; |
||||
packet.voltage_cell_3 = voltage_cell_3; |
||||
packet.voltage_cell_4 = voltage_cell_4; |
||||
packet.voltage_cell_5 = voltage_cell_5; |
||||
packet.voltage_cell_6 = voltage_cell_6; |
||||
packet.current_battery = current_battery; |
||||
packet.accu_id = accu_id; |
||||
packet.battery_remaining = battery_remaining; |
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, 16, 42); |
||||
#endif |
||||
} |
||||
|
||||
#endif |
||||
|
||||
// MESSAGE BATTERY_STATUS UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field accu_id from battery_status message |
||||
* |
||||
* @return Accupack ID |
||||
*/ |
||||
static inline uint8_t mavlink_msg_battery_status_get_accu_id(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint8_t(msg, 14); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field voltage_cell_1 from battery_status message |
||||
* |
||||
* @return Battery voltage of cell 1, in millivolts (1 = 1 millivolt) |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_1(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint16_t(msg, 0); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field voltage_cell_2 from battery_status message |
||||
* |
||||
* @return Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_2(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint16_t(msg, 2); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field voltage_cell_3 from battery_status message |
||||
* |
||||
* @return Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_3(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint16_t(msg, 4); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field voltage_cell_4 from battery_status message |
||||
* |
||||
* @return Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_4(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint16_t(msg, 6); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field voltage_cell_5 from battery_status message |
||||
* |
||||
* @return Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_5(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint16_t(msg, 8); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field voltage_cell_6 from battery_status message |
||||
* |
||||
* @return Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell |
||||
*/ |
||||
static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_6(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint16_t(msg, 10); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field current_battery from battery_status message |
||||
* |
||||
* @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
||||
*/ |
||||
static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_int16_t(msg, 12); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field battery_remaining from battery_status message |
||||
* |
||||
* @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery |
||||
*/ |
||||
static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_int8_t(msg, 15); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Decode a battery_status message into a struct |
||||
* |
||||
* @param msg The message to decode |
||||
* @param battery_status C-struct to decode the message contents into |
||||
*/ |
||||
static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
battery_status->voltage_cell_1 = mavlink_msg_battery_status_get_voltage_cell_1(msg); |
||||
battery_status->voltage_cell_2 = mavlink_msg_battery_status_get_voltage_cell_2(msg); |
||||
battery_status->voltage_cell_3 = mavlink_msg_battery_status_get_voltage_cell_3(msg); |
||||
battery_status->voltage_cell_4 = mavlink_msg_battery_status_get_voltage_cell_4(msg); |
||||
battery_status->voltage_cell_5 = mavlink_msg_battery_status_get_voltage_cell_5(msg); |
||||
battery_status->voltage_cell_6 = mavlink_msg_battery_status_get_voltage_cell_6(msg); |
||||
battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg); |
||||
battery_status->accu_id = mavlink_msg_battery_status_get_accu_id(msg); |
||||
battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg); |
||||
#else |
||||
memcpy(battery_status, _MAV_PAYLOAD(msg), 16); |
||||
#endif |
||||
} |
@ -0,0 +1,276 @@
@@ -0,0 +1,276 @@
|
||||
// MESSAGE SETPOINT_6DOF PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_SETPOINT_6DOF 149 |
||||
|
||||
typedef struct __mavlink_setpoint_6dof_t |
||||
{ |
||||
float trans_x; ///< Translational Component in x
|
||||
float trans_y; ///< Translational Component in y
|
||||
float trans_z; ///< Translational Component in z
|
||||
float rot_x; ///< Rotational Component in x
|
||||
float rot_y; ///< Rotational Component in y
|
||||
float rot_z; ///< Rotational Component in z
|
||||
uint8_t target_system; ///< System ID
|
||||
} mavlink_setpoint_6dof_t; |
||||
|
||||
#define MAVLINK_MSG_ID_SETPOINT_6DOF_LEN 25 |
||||
#define MAVLINK_MSG_ID_149_LEN 25 |
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_SETPOINT_6DOF { \ |
||||
"SETPOINT_6DOF", \
|
||||
7, \
|
||||
{ { "trans_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_setpoint_6dof_t, trans_x) }, \
|
||||
{ "trans_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_setpoint_6dof_t, trans_y) }, \
|
||||
{ "trans_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_setpoint_6dof_t, trans_z) }, \
|
||||
{ "rot_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_setpoint_6dof_t, rot_x) }, \
|
||||
{ "rot_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_setpoint_6dof_t, rot_y) }, \
|
||||
{ "rot_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_setpoint_6dof_t, rot_z) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_setpoint_6dof_t, target_system) }, \
|
||||
} \
|
||||
} |
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a setpoint_6dof message |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param msg The MAVLink message to compress the data into |
||||
* |
||||
* @param target_system System ID |
||||
* @param trans_x Translational Component in x |
||||
* @param trans_y Translational Component in y |
||||
* @param trans_z Translational Component in z |
||||
* @param rot_x Rotational Component in x |
||||
* @param rot_y Rotational Component in y |
||||
* @param rot_z Rotational Component in z |
||||
* @return length of the message in bytes (excluding serial stream start sign) |
||||
*/ |
||||
static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||||
uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[25]; |
||||
_mav_put_float(buf, 0, trans_x); |
||||
_mav_put_float(buf, 4, trans_y); |
||||
_mav_put_float(buf, 8, trans_z); |
||||
_mav_put_float(buf, 12, rot_x); |
||||
_mav_put_float(buf, 16, rot_y); |
||||
_mav_put_float(buf, 20, rot_z); |
||||
_mav_put_uint8_t(buf, 24, target_system); |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); |
||||
#else |
||||
mavlink_setpoint_6dof_t packet; |
||||
packet.trans_x = trans_x; |
||||
packet.trans_y = trans_y; |
||||
packet.trans_z = trans_z; |
||||
packet.rot_x = rot_x; |
||||
packet.rot_y = rot_y; |
||||
packet.rot_z = rot_z; |
||||
packet.target_system = target_system; |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); |
||||
#endif |
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_SETPOINT_6DOF; |
||||
return mavlink_finalize_message(msg, system_id, component_id, 25, 15); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Pack a setpoint_6dof message on a channel |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param chan The MAVLink channel this message was sent over |
||||
* @param msg The MAVLink message to compress the data into |
||||
* @param target_system System ID |
||||
* @param trans_x Translational Component in x |
||||
* @param trans_y Translational Component in y |
||||
* @param trans_z Translational Component in z |
||||
* @param rot_x Rotational Component in x |
||||
* @param rot_y Rotational Component in y |
||||
* @param rot_z Rotational Component in z |
||||
* @return length of the message in bytes (excluding serial stream start sign) |
||||
*/ |
||||
static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||||
mavlink_message_t* msg, |
||||
uint8_t target_system,float trans_x,float trans_y,float trans_z,float rot_x,float rot_y,float rot_z) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[25]; |
||||
_mav_put_float(buf, 0, trans_x); |
||||
_mav_put_float(buf, 4, trans_y); |
||||
_mav_put_float(buf, 8, trans_z); |
||||
_mav_put_float(buf, 12, rot_x); |
||||
_mav_put_float(buf, 16, rot_y); |
||||
_mav_put_float(buf, 20, rot_z); |
||||
_mav_put_uint8_t(buf, 24, target_system); |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25); |
||||
#else |
||||
mavlink_setpoint_6dof_t packet; |
||||
packet.trans_x = trans_x; |
||||
packet.trans_y = trans_y; |
||||
packet.trans_z = trans_z; |
||||
packet.rot_x = rot_x; |
||||
packet.rot_y = rot_y; |
||||
packet.rot_z = rot_z; |
||||
packet.target_system = target_system; |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25); |
||||
#endif |
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_SETPOINT_6DOF; |
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 15); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Encode a setpoint_6dof struct into a message |
||||
* |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param msg The MAVLink message to compress the data into |
||||
* @param setpoint_6dof C-struct to read the message contents from |
||||
*/ |
||||
static inline uint16_t mavlink_msg_setpoint_6dof_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_setpoint_6dof_t* setpoint_6dof) |
||||
{ |
||||
return mavlink_msg_setpoint_6dof_pack(system_id, component_id, msg, setpoint_6dof->target_system, setpoint_6dof->trans_x, setpoint_6dof->trans_y, setpoint_6dof->trans_z, setpoint_6dof->rot_x, setpoint_6dof->rot_y, setpoint_6dof->rot_z); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Send a setpoint_6dof message |
||||
* @param chan MAVLink channel to send the message |
||||
* |
||||
* @param target_system System ID |
||||
* @param trans_x Translational Component in x |
||||
* @param trans_y Translational Component in y |
||||
* @param trans_z Translational Component in z |
||||
* @param rot_x Rotational Component in x |
||||
* @param rot_y Rotational Component in y |
||||
* @param rot_z Rotational Component in z |
||||
*/ |
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
|
||||
static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[25]; |
||||
_mav_put_float(buf, 0, trans_x); |
||||
_mav_put_float(buf, 4, trans_y); |
||||
_mav_put_float(buf, 8, trans_z); |
||||
_mav_put_float(buf, 12, rot_x); |
||||
_mav_put_float(buf, 16, rot_y); |
||||
_mav_put_float(buf, 20, rot_z); |
||||
_mav_put_uint8_t(buf, 24, target_system); |
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, 25, 15); |
||||
#else |
||||
mavlink_setpoint_6dof_t packet; |
||||
packet.trans_x = trans_x; |
||||
packet.trans_y = trans_y; |
||||
packet.trans_z = trans_z; |
||||
packet.rot_x = rot_x; |
||||
packet.rot_y = rot_y; |
||||
packet.rot_z = rot_z; |
||||
packet.target_system = target_system; |
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, 25, 15); |
||||
#endif |
||||
} |
||||
|
||||
#endif |
||||
|
||||
// MESSAGE SETPOINT_6DOF UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from setpoint_6dof message |
||||
* |
||||
* @return System ID |
||||
*/ |
||||
static inline uint8_t mavlink_msg_setpoint_6dof_get_target_system(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint8_t(msg, 24); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field trans_x from setpoint_6dof message |
||||
* |
||||
* @return Translational Component in x |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_6dof_get_trans_x(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 0); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field trans_y from setpoint_6dof message |
||||
* |
||||
* @return Translational Component in y |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_6dof_get_trans_y(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 4); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field trans_z from setpoint_6dof message |
||||
* |
||||
* @return Translational Component in z |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_6dof_get_trans_z(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 8); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field rot_x from setpoint_6dof message |
||||
* |
||||
* @return Rotational Component in x |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_6dof_get_rot_x(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 12); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field rot_y from setpoint_6dof message |
||||
* |
||||
* @return Rotational Component in y |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_6dof_get_rot_y(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 16); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field rot_z from setpoint_6dof message |
||||
* |
||||
* @return Rotational Component in z |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_6dof_get_rot_z(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 20); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Decode a setpoint_6dof message into a struct |
||||
* |
||||
* @param msg The message to decode |
||||
* @param setpoint_6dof C-struct to decode the message contents into |
||||
*/ |
||||
static inline void mavlink_msg_setpoint_6dof_decode(const mavlink_message_t* msg, mavlink_setpoint_6dof_t* setpoint_6dof) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
setpoint_6dof->trans_x = mavlink_msg_setpoint_6dof_get_trans_x(msg); |
||||
setpoint_6dof->trans_y = mavlink_msg_setpoint_6dof_get_trans_y(msg); |
||||
setpoint_6dof->trans_z = mavlink_msg_setpoint_6dof_get_trans_z(msg); |
||||
setpoint_6dof->rot_x = mavlink_msg_setpoint_6dof_get_rot_x(msg); |
||||
setpoint_6dof->rot_y = mavlink_msg_setpoint_6dof_get_rot_y(msg); |
||||
setpoint_6dof->rot_z = mavlink_msg_setpoint_6dof_get_rot_z(msg); |
||||
setpoint_6dof->target_system = mavlink_msg_setpoint_6dof_get_target_system(msg); |
||||
#else |
||||
memcpy(setpoint_6dof, _MAV_PAYLOAD(msg), 25); |
||||
#endif |
||||
} |
@ -0,0 +1,320 @@
@@ -0,0 +1,320 @@
|
||||
// MESSAGE SETPOINT_8DOF PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_SETPOINT_8DOF 148 |
||||
|
||||
typedef struct __mavlink_setpoint_8dof_t |
||||
{ |
||||
float val1; ///< Value 1
|
||||
float val2; ///< Value 2
|
||||
float val3; ///< Value 3
|
||||
float val4; ///< Value 4
|
||||
float val5; ///< Value 5
|
||||
float val6; ///< Value 6
|
||||
float val7; ///< Value 7
|
||||
float val8; ///< Value 8
|
||||
uint8_t target_system; ///< System ID
|
||||
} mavlink_setpoint_8dof_t; |
||||
|
||||
#define MAVLINK_MSG_ID_SETPOINT_8DOF_LEN 33 |
||||
#define MAVLINK_MSG_ID_148_LEN 33 |
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_SETPOINT_8DOF { \ |
||||
"SETPOINT_8DOF", \
|
||||
9, \
|
||||
{ { "val1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_setpoint_8dof_t, val1) }, \
|
||||
{ "val2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_setpoint_8dof_t, val2) }, \
|
||||
{ "val3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_setpoint_8dof_t, val3) }, \
|
||||
{ "val4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_setpoint_8dof_t, val4) }, \
|
||||
{ "val5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_setpoint_8dof_t, val5) }, \
|
||||
{ "val6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_setpoint_8dof_t, val6) }, \
|
||||
{ "val7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_setpoint_8dof_t, val7) }, \
|
||||
{ "val8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_setpoint_8dof_t, val8) }, \
|
||||
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_setpoint_8dof_t, target_system) }, \
|
||||
} \
|
||||
} |
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a setpoint_8dof message |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param msg The MAVLink message to compress the data into |
||||
* |
||||
* @param target_system System ID |
||||
* @param val1 Value 1 |
||||
* @param val2 Value 2 |
||||
* @param val3 Value 3 |
||||
* @param val4 Value 4 |
||||
* @param val5 Value 5 |
||||
* @param val6 Value 6 |
||||
* @param val7 Value 7 |
||||
* @param val8 Value 8 |
||||
* @return length of the message in bytes (excluding serial stream start sign) |
||||
*/ |
||||
static inline uint16_t mavlink_msg_setpoint_8dof_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||||
uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[33]; |
||||
_mav_put_float(buf, 0, val1); |
||||
_mav_put_float(buf, 4, val2); |
||||
_mav_put_float(buf, 8, val3); |
||||
_mav_put_float(buf, 12, val4); |
||||
_mav_put_float(buf, 16, val5); |
||||
_mav_put_float(buf, 20, val6); |
||||
_mav_put_float(buf, 24, val7); |
||||
_mav_put_float(buf, 28, val8); |
||||
_mav_put_uint8_t(buf, 32, target_system); |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); |
||||
#else |
||||
mavlink_setpoint_8dof_t packet; |
||||
packet.val1 = val1; |
||||
packet.val2 = val2; |
||||
packet.val3 = val3; |
||||
packet.val4 = val4; |
||||
packet.val5 = val5; |
||||
packet.val6 = val6; |
||||
packet.val7 = val7; |
||||
packet.val8 = val8; |
||||
packet.target_system = target_system; |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); |
||||
#endif |
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_SETPOINT_8DOF; |
||||
return mavlink_finalize_message(msg, system_id, component_id, 33, 241); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Pack a setpoint_8dof message on a channel |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param chan The MAVLink channel this message was sent over |
||||
* @param msg The MAVLink message to compress the data into |
||||
* @param target_system System ID |
||||
* @param val1 Value 1 |
||||
* @param val2 Value 2 |
||||
* @param val3 Value 3 |
||||
* @param val4 Value 4 |
||||
* @param val5 Value 5 |
||||
* @param val6 Value 6 |
||||
* @param val7 Value 7 |
||||
* @param val8 Value 8 |
||||
* @return length of the message in bytes (excluding serial stream start sign) |
||||
*/ |
||||
static inline uint16_t mavlink_msg_setpoint_8dof_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||||
mavlink_message_t* msg, |
||||
uint8_t target_system,float val1,float val2,float val3,float val4,float val5,float val6,float val7,float val8) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[33]; |
||||
_mav_put_float(buf, 0, val1); |
||||
_mav_put_float(buf, 4, val2); |
||||
_mav_put_float(buf, 8, val3); |
||||
_mav_put_float(buf, 12, val4); |
||||
_mav_put_float(buf, 16, val5); |
||||
_mav_put_float(buf, 20, val6); |
||||
_mav_put_float(buf, 24, val7); |
||||
_mav_put_float(buf, 28, val8); |
||||
_mav_put_uint8_t(buf, 32, target_system); |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33); |
||||
#else |
||||
mavlink_setpoint_8dof_t packet; |
||||
packet.val1 = val1; |
||||
packet.val2 = val2; |
||||
packet.val3 = val3; |
||||
packet.val4 = val4; |
||||
packet.val5 = val5; |
||||
packet.val6 = val6; |
||||
packet.val7 = val7; |
||||
packet.val8 = val8; |
||||
packet.target_system = target_system; |
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33); |
||||
#endif |
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_SETPOINT_8DOF; |
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 241); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Encode a setpoint_8dof struct into a message |
||||
* |
||||
* @param system_id ID of this system |
||||
* @param component_id ID of this component (e.g. 200 for IMU) |
||||
* @param msg The MAVLink message to compress the data into |
||||
* @param setpoint_8dof C-struct to read the message contents from |
||||
*/ |
||||
static inline uint16_t mavlink_msg_setpoint_8dof_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_setpoint_8dof_t* setpoint_8dof) |
||||
{ |
||||
return mavlink_msg_setpoint_8dof_pack(system_id, component_id, msg, setpoint_8dof->target_system, setpoint_8dof->val1, setpoint_8dof->val2, setpoint_8dof->val3, setpoint_8dof->val4, setpoint_8dof->val5, setpoint_8dof->val6, setpoint_8dof->val7, setpoint_8dof->val8); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Send a setpoint_8dof message |
||||
* @param chan MAVLink channel to send the message |
||||
* |
||||
* @param target_system System ID |
||||
* @param val1 Value 1 |
||||
* @param val2 Value 2 |
||||
* @param val3 Value 3 |
||||
* @param val4 Value 4 |
||||
* @param val5 Value 5 |
||||
* @param val6 Value 6 |
||||
* @param val7 Value 7 |
||||
* @param val8 Value 8 |
||||
*/ |
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||||
|
||||
static inline void mavlink_msg_setpoint_8dof_send(mavlink_channel_t chan, uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||||
char buf[33]; |
||||
_mav_put_float(buf, 0, val1); |
||||
_mav_put_float(buf, 4, val2); |
||||
_mav_put_float(buf, 8, val3); |
||||
_mav_put_float(buf, 12, val4); |
||||
_mav_put_float(buf, 16, val5); |
||||
_mav_put_float(buf, 20, val6); |
||||
_mav_put_float(buf, 24, val7); |
||||
_mav_put_float(buf, 28, val8); |
||||
_mav_put_uint8_t(buf, 32, target_system); |
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, 33, 241); |
||||
#else |
||||
mavlink_setpoint_8dof_t packet; |
||||
packet.val1 = val1; |
||||
packet.val2 = val2; |
||||
packet.val3 = val3; |
||||
packet.val4 = val4; |
||||
packet.val5 = val5; |
||||
packet.val6 = val6; |
||||
packet.val7 = val7; |
||||
packet.val8 = val8; |
||||
packet.target_system = target_system; |
||||
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)&packet, 33, 241); |
||||
#endif |
||||
} |
||||
|
||||
#endif |
||||
|
||||
// MESSAGE SETPOINT_8DOF UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field target_system from setpoint_8dof message |
||||
* |
||||
* @return System ID |
||||
*/ |
||||
static inline uint8_t mavlink_msg_setpoint_8dof_get_target_system(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_uint8_t(msg, 32); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field val1 from setpoint_8dof message |
||||
* |
||||
* @return Value 1 |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_8dof_get_val1(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 0); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field val2 from setpoint_8dof message |
||||
* |
||||
* @return Value 2 |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_8dof_get_val2(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 4); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field val3 from setpoint_8dof message |
||||
* |
||||
* @return Value 3 |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_8dof_get_val3(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 8); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field val4 from setpoint_8dof message |
||||
* |
||||
* @return Value 4 |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_8dof_get_val4(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 12); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field val5 from setpoint_8dof message |
||||
* |
||||
* @return Value 5 |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_8dof_get_val5(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 16); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field val6 from setpoint_8dof message |
||||
* |
||||
* @return Value 6 |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_8dof_get_val6(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 20); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field val7 from setpoint_8dof message |
||||
* |
||||
* @return Value 7 |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_8dof_get_val7(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 24); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Get field val8 from setpoint_8dof message |
||||
* |
||||
* @return Value 8 |
||||
*/ |
||||
static inline float mavlink_msg_setpoint_8dof_get_val8(const mavlink_message_t* msg) |
||||
{ |
||||
return _MAV_RETURN_float(msg, 28); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Decode a setpoint_8dof message into a struct |
||||
* |
||||
* @param msg The message to decode |
||||
* @param setpoint_8dof C-struct to decode the message contents into |
||||
*/ |
||||
static inline void mavlink_msg_setpoint_8dof_decode(const mavlink_message_t* msg, mavlink_setpoint_8dof_t* setpoint_8dof) |
||||
{ |
||||
#if MAVLINK_NEED_BYTE_SWAP |
||||
setpoint_8dof->val1 = mavlink_msg_setpoint_8dof_get_val1(msg); |
||||
setpoint_8dof->val2 = mavlink_msg_setpoint_8dof_get_val2(msg); |
||||
setpoint_8dof->val3 = mavlink_msg_setpoint_8dof_get_val3(msg); |
||||
setpoint_8dof->val4 = mavlink_msg_setpoint_8dof_get_val4(msg); |
||||
setpoint_8dof->val5 = mavlink_msg_setpoint_8dof_get_val5(msg); |
||||
setpoint_8dof->val6 = mavlink_msg_setpoint_8dof_get_val6(msg); |
||||
setpoint_8dof->val7 = mavlink_msg_setpoint_8dof_get_val7(msg); |
||||
setpoint_8dof->val8 = mavlink_msg_setpoint_8dof_get_val8(msg); |
||||
setpoint_8dof->target_system = mavlink_msg_setpoint_8dof_get_target_system(msg); |
||||
#else |
||||
memcpy(setpoint_8dof, _MAV_PAYLOAD(msg), 33); |
||||
#endif |
||||
} |
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
File diff suppressed because one or more lines are too long
Loading…
Reference in new issue