mavlink_msg_home_position.h
Go to the documentation of this file.
1 // MESSAGE HOME_POSITION PACKING
2 
3 #define MAVLINK_MSG_ID_HOME_POSITION 242
4 
6 {
7  int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/
8  int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/
9  int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/
10  float x; /*< Local X position of this position in the local coordinate frame*/
11  float y; /*< Local Y position of this position in the local coordinate frame*/
12  float z; /*< Local Z position of this position in the local coordinate frame*/
13  float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/
14  float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
15  float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
16  float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
18 
19 #define MAVLINK_MSG_ID_HOME_POSITION_LEN 52
20 #define MAVLINK_MSG_ID_242_LEN 52
21 
22 #define MAVLINK_MSG_ID_HOME_POSITION_CRC 104
23 #define MAVLINK_MSG_ID_242_CRC 104
24 
25 #define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4
26 
27 #define MAVLINK_MESSAGE_INFO_HOME_POSITION { \
28  "HOME_POSITION", \
29  10, \
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) }, \
40  } \
41 }
42 
43 
62 static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
63  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)
64 {
65 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67  _mav_put_int32_t(buf, 0, latitude);
68  _mav_put_int32_t(buf, 4, longitude);
69  _mav_put_int32_t(buf, 8, altitude);
70  _mav_put_float(buf, 12, x);
71  _mav_put_float(buf, 16, y);
72  _mav_put_float(buf, 20, z);
73  _mav_put_float(buf, 40, approach_x);
74  _mav_put_float(buf, 44, approach_y);
75  _mav_put_float(buf, 48, approach_z);
76  _mav_put_float_array(buf, 24, q, 4);
78 #else
80  packet.latitude = latitude;
81  packet.longitude = longitude;
82  packet.altitude = altitude;
83  packet.x = x;
84  packet.y = y;
85  packet.z = z;
86  packet.approach_x = approach_x;
87  packet.approach_y = approach_y;
88  packet.approach_z = approach_z;
89  mav_array_memcpy(packet.q, q, sizeof(float)*4);
91 #endif
92 
93  msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
94 #if MAVLINK_CRC_EXTRA
96 #else
97  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_LEN);
98 #endif
99 }
100 
119 static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
120  mavlink_message_t* msg,
121  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)
122 {
123 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
125  _mav_put_int32_t(buf, 0, latitude);
126  _mav_put_int32_t(buf, 4, longitude);
127  _mav_put_int32_t(buf, 8, altitude);
128  _mav_put_float(buf, 12, x);
129  _mav_put_float(buf, 16, y);
130  _mav_put_float(buf, 20, z);
131  _mav_put_float(buf, 40, approach_x);
132  _mav_put_float(buf, 44, approach_y);
133  _mav_put_float(buf, 48, approach_z);
134  _mav_put_float_array(buf, 24, q, 4);
136 #else
138  packet.latitude = latitude;
139  packet.longitude = longitude;
140  packet.altitude = altitude;
141  packet.x = x;
142  packet.y = y;
143  packet.z = z;
144  packet.approach_x = approach_x;
145  packet.approach_y = approach_y;
146  packet.approach_z = approach_z;
147  mav_array_memcpy(packet.q, q, sizeof(float)*4);
149 #endif
150 
151  msg->msgid = MAVLINK_MSG_ID_HOME_POSITION;
152 #if MAVLINK_CRC_EXTRA
154 #else
155  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_LEN);
156 #endif
157 }
158 
167 static inline 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)
168 {
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);
170 }
171 
181 static inline 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)
182 {
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);
184 }
185 
201 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
202 
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)
204 {
205 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
207  _mav_put_int32_t(buf, 0, latitude);
208  _mav_put_int32_t(buf, 4, longitude);
209  _mav_put_int32_t(buf, 8, altitude);
210  _mav_put_float(buf, 12, x);
211  _mav_put_float(buf, 16, y);
212  _mav_put_float(buf, 20, z);
213  _mav_put_float(buf, 40, approach_x);
214  _mav_put_float(buf, 44, approach_y);
215  _mav_put_float(buf, 48, approach_z);
216  _mav_put_float_array(buf, 24, q, 4);
217 #if MAVLINK_CRC_EXTRA
219 #else
220  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
221 #endif
222 #else
224  packet.latitude = latitude;
225  packet.longitude = longitude;
226  packet.altitude = altitude;
227  packet.x = x;
228  packet.y = y;
229  packet.z = z;
230  packet.approach_x = approach_x;
231  packet.approach_y = approach_y;
232  packet.approach_z = approach_z;
233  mav_array_memcpy(packet.q, q, sizeof(float)*4);
234 #if MAVLINK_CRC_EXTRA
235  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
236 #else
237  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
238 #endif
239 #endif
240 }
241 
242 #if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
243 /*
244  This varient of _send() can be used to save stack space by re-using
245  memory from the receive buffer. The caller provides a
246  mavlink_message_t which is the size of a full mavlink message. This
247  is usually the receive buffer for the channel, and allows a reply to an
248  incoming message with minimum stack space usage.
249  */
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)
251 {
252 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
253  char *buf = (char *)msgbuf;
254  _mav_put_int32_t(buf, 0, latitude);
255  _mav_put_int32_t(buf, 4, longitude);
256  _mav_put_int32_t(buf, 8, altitude);
257  _mav_put_float(buf, 12, x);
258  _mav_put_float(buf, 16, y);
259  _mav_put_float(buf, 20, z);
260  _mav_put_float(buf, 40, approach_x);
261  _mav_put_float(buf, 44, approach_y);
262  _mav_put_float(buf, 48, approach_z);
263  _mav_put_float_array(buf, 24, q, 4);
264 #if MAVLINK_CRC_EXTRA
266 #else
267  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
268 #endif
269 #else
271  packet->latitude = latitude;
272  packet->longitude = longitude;
273  packet->altitude = altitude;
274  packet->x = x;
275  packet->y = y;
276  packet->z = z;
277  packet->approach_x = approach_x;
278  packet->approach_y = approach_y;
279  packet->approach_z = approach_z;
280  mav_array_memcpy(packet->q, q, sizeof(float)*4);
281 #if MAVLINK_CRC_EXTRA
282  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
283 #else
284  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
285 #endif
286 #endif
287 }
288 #endif
289 
290 #endif
291 
292 // MESSAGE HOME_POSITION UNPACKING
293 
294 
300 static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg)
301 {
302  return _MAV_RETURN_int32_t(msg, 0);
303 }
304 
310 static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg)
311 {
312  return _MAV_RETURN_int32_t(msg, 4);
313 }
314 
320 static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg)
321 {
322  return _MAV_RETURN_int32_t(msg, 8);
323 }
324 
330 static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg)
331 {
332  return _MAV_RETURN_float(msg, 12);
333 }
334 
340 static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg)
341 {
342  return _MAV_RETURN_float(msg, 16);
343 }
344 
350 static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg)
351 {
352  return _MAV_RETURN_float(msg, 20);
353 }
354 
360 static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q)
361 {
362  return _MAV_RETURN_float_array(msg, q, 4, 24);
363 }
364 
370 static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg)
371 {
372  return _MAV_RETURN_float(msg, 40);
373 }
374 
380 static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg)
381 {
382  return _MAV_RETURN_float(msg, 44);
383 }
384 
390 static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg)
391 {
392  return _MAV_RETURN_float(msg, 48);
393 }
394 
401 static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position)
402 {
403 #if MAVLINK_NEED_BYTE_SWAP
404  home_position->latitude = mavlink_msg_home_position_get_latitude(msg);
406  home_position->altitude = mavlink_msg_home_position_get_altitude(msg);
407  home_position->x = mavlink_msg_home_position_get_x(msg);
408  home_position->y = mavlink_msg_home_position_get_y(msg);
409  home_position->z = mavlink_msg_home_position_get_z(msg);
410  mavlink_msg_home_position_get_q(msg, home_position->q);
414 #else
415  memcpy(home_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HOME_POSITION_LEN);
416 #endif
417 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:148
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:25