3 #define MAVLINK_MSG_ID_SET_HOME_POSITION 243 20 #define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53 21 #define MAVLINK_MSG_ID_243_LEN 53 23 #define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85 24 #define MAVLINK_MSG_ID_243_CRC 85 26 #define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4 28 #define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ 29 "SET_HOME_POSITION", \ 31 { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ 32 { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ 33 { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ 34 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ 35 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ 36 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ 37 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ 38 { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ 39 { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ 40 { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ 41 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ 66 uint8_t
target_system, int32_t
latitude, int32_t
longitude, int32_t
altitude,
float x,
float y,
float z,
const float *
q,
float approach_x,
float approach_y,
float approach_z)
68 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 80 _mav_put_float_array(buf, 24, q, 4);
126 mavlink_message_t* msg,
127 uint8_t
target_system,int32_t
latitude,int32_t
longitude,int32_t
altitude,
float x,
float y,
float z,
const float *
q,
float approach_x,
float approach_y,
float approach_z)
129 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 141 _mav_put_float_array(buf, 24, q, 4);
160 #if MAVLINK_CRC_EXTRA 177 return mavlink_msg_set_home_position_pack(system_id, component_id, msg, set_home_position->
target_system, set_home_position->
latitude, set_home_position->
longitude, set_home_position->
altitude, set_home_position->
x, set_home_position->
y, set_home_position->
z, set_home_position->
q, set_home_position->
approach_x, set_home_position->
approach_y, set_home_position->
approach_z);
191 return mavlink_msg_set_home_position_pack_chan(system_id, component_id, chan, msg, set_home_position->
target_system, set_home_position->
latitude, set_home_position->
longitude, set_home_position->
altitude, set_home_position->
x, set_home_position->
y, set_home_position->
z, set_home_position->
q, set_home_position->
approach_x, set_home_position->
approach_y, set_home_position->
approach_z);
210 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 212 static inline void mavlink_msg_set_home_position_send(
mavlink_channel_t chan, uint8_t
target_system, int32_t
latitude, int32_t
longitude, int32_t
altitude,
float x,
float y,
float z,
const float *
q,
float approach_x,
float approach_y,
float approach_z)
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 226 _mav_put_float_array(buf, 24,
q, 4);
227 #if MAVLINK_CRC_EXTRA 245 #if MAVLINK_CRC_EXTRA 253 #if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN 261 static inline void mavlink_msg_set_home_position_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t
target_system, int32_t
latitude, int32_t
longitude, int32_t
altitude,
float x,
float y,
float z,
const float *
q,
float approach_x,
float approach_y,
float approach_z)
263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 264 char *buf = (
char *)msgbuf;
275 _mav_put_float_array(buf, 24,
q, 4);
276 #if MAVLINK_CRC_EXTRA 294 #if MAVLINK_CRC_EXTRA 325 return _MAV_RETURN_int32_t(msg, 0);
335 return _MAV_RETURN_int32_t(msg, 4);
345 return _MAV_RETURN_int32_t(msg, 8);
355 return _MAV_RETURN_float(msg, 12);
365 return _MAV_RETURN_float(msg, 16);
375 return _MAV_RETURN_float(msg, 20);
385 return _MAV_RETURN_float_array(msg, q, 4, 24);
395 return _MAV_RETURN_float(msg, 40);
405 return _MAV_RETURN_float(msg, 44);
415 return _MAV_RETURN_float(msg, 48);
426 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t *msg, float *q)
Get field q from set_home_position message.
#define _mav_put_float(buf, wire_offset, b)
static void mavlink_msg_set_home_position_decode(const mavlink_message_t *msg, mavlink_set_home_position_t *set_home_position)
Decode a set_home_position message into a struct.
static uint16_t mavlink_msg_set_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_home_position_t *set_home_position)
Encode a set_home_position struct.
struct __mavlink_set_home_position_t mavlink_set_home_position_t
static int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t *msg)
Get field latitude from set_home_position message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t *msg)
Get field altitude from set_home_position message.
static uint16_t mavlink_msg_set_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_home_position_t *set_home_position)
Encode a set_home_position struct on a channel.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t *msg)
Get field approach_x from set_home_position message.
static float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t *msg)
Get field approach_z from set_home_position message.
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
Pack a set_home_position message.
#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC
static float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t *msg)
Get field approach_y from set_home_position message.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static float mavlink_msg_set_home_position_get_x(const mavlink_message_t *msg)
Get field x from set_home_position message.
static uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t *msg)
Send a set_home_position message.
static float mavlink_msg_set_home_position_get_z(const mavlink_message_t *msg)
Get field z from set_home_position message.
static int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t *msg)
Get field longitude from set_home_position message.
static float mavlink_msg_set_home_position_get_y(const mavlink_message_t *msg)
Get field y from set_home_position message.
#define MAVLINK_MSG_ID_SET_HOME_POSITION
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
static uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
Pack a set_home_position message on a channel.
#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN