3 #define MAVLINK_MSG_ID_HOME_POSITION 242 19 #define MAVLINK_MSG_ID_HOME_POSITION_LEN 52 20 #define MAVLINK_MSG_ID_242_LEN 52 22 #define MAVLINK_MSG_ID_HOME_POSITION_CRC 104 23 #define MAVLINK_MSG_ID_242_CRC 104 25 #define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4 27 #define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ 30 { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ 31 { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ 32 { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ 33 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ 34 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ 35 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ 36 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ 37 { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ 38 { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ 39 { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ 65 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 76 _mav_put_float_array(buf, 24, q, 4);
120 mavlink_message_t* msg,
123 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 134 _mav_put_float_array(buf, 24, q, 4);
152 #if MAVLINK_CRC_EXTRA 169 return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->
latitude, home_position->
longitude, home_position->
altitude, home_position->
x, home_position->
y, home_position->
z, home_position->
q, home_position->
approach_x, home_position->
approach_y, home_position->
approach_z);
183 return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->
latitude, home_position->
longitude, home_position->
altitude, home_position->
x, home_position->
y, home_position->
z, home_position->
q, home_position->
approach_x, home_position->
approach_y, home_position->
approach_z);
201 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 203 static inline void mavlink_msg_home_position_send(
mavlink_channel_t chan, 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)
205 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 216 _mav_put_float_array(buf, 24,
q, 4);
217 #if MAVLINK_CRC_EXTRA 234 #if MAVLINK_CRC_EXTRA 242 #if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN 250 static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, 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)
252 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 253 char *buf = (
char *)msgbuf;
263 _mav_put_float_array(buf, 24,
q, 4);
264 #if MAVLINK_CRC_EXTRA 281 #if MAVLINK_CRC_EXTRA 302 return _MAV_RETURN_int32_t(msg, 0);
312 return _MAV_RETURN_int32_t(msg, 4);
322 return _MAV_RETURN_int32_t(msg, 8);
332 return _MAV_RETURN_float(msg, 12);
342 return _MAV_RETURN_float(msg, 16);
352 return _MAV_RETURN_float(msg, 20);
362 return _MAV_RETURN_float_array(msg, q, 4, 24);
372 return _MAV_RETURN_float(msg, 40);
382 return _MAV_RETURN_float(msg, 44);
392 return _MAV_RETURN_float(msg, 48);
403 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_home_position_t *home_position)
Encode a home_position struct.
#define _mav_put_float(buf, wire_offset, b)
static int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t *msg)
Send a home_position message.
struct __mavlink_home_position_t mavlink_home_position_t
static void mavlink_msg_home_position_decode(const mavlink_message_t *msg, mavlink_home_position_t *home_position)
Decode a home_position message into a struct.
static float mavlink_msg_home_position_get_y(const mavlink_message_t *msg)
Get field y from home_position message.
#define MAVLINK_MSG_ID_HOME_POSITION_CRC
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.
static uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, 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 home_position message on a channel.
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_home_position_get_x(const mavlink_message_t *msg)
Get field x from home_position message.
static float mavlink_msg_home_position_get_approach_x(const mavlink_message_t *msg)
Get field approach_x from home_position message.
#define _MAV_PAYLOAD(msg)
static float mavlink_msg_home_position_get_z(const mavlink_message_t *msg)
Get field z from home_position message.
static float mavlink_msg_home_position_get_approach_y(const mavlink_message_t *msg)
Get field approach_y from home_position message.
static int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t *msg)
Get field altitude from home_position message.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, 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 home_position message.
static float mavlink_msg_home_position_get_approach_z(const mavlink_message_t *msg)
Get field approach_z from home_position message.
static uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_home_position_t *home_position)
Encode a home_position struct on a channel.
#define MAVLINK_MSG_ID_HOME_POSITION_LEN
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 int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t *msg)
Get field longitude from home_position message.
static uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t *msg, float *q)
Get field q from home_position message.
#define MAVLINK_MSG_ID_HOME_POSITION