mavlink_msg_position_target_local_ned.h
Go to the documentation of this file.
00001 // MESSAGE POSITION_TARGET_LOCAL_NED PACKING
00002 
00003 #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85
00004 
00005 typedef struct __mavlink_position_target_local_ned_t
00006 {
00007  uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/
00008  float x; /*< X Position in NED frame in meters*/
00009  float y; /*< Y Position in NED frame in meters*/
00010  float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/
00011  float vx; /*< X velocity in NED frame in meter / s*/
00012  float vy; /*< Y velocity in NED frame in meter / s*/
00013  float vz; /*< Z velocity in NED frame in meter / s*/
00014  float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
00015  float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
00016  float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/
00017  float yaw; /*< yaw setpoint in rad*/
00018  float yaw_rate; /*< yaw rate setpoint in rad/s*/
00019  uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/
00020  uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/
00021 } mavlink_position_target_local_ned_t;
00022 
00023 #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51
00024 #define MAVLINK_MSG_ID_85_LEN 51
00025 
00026 #define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140
00027 #define MAVLINK_MSG_ID_85_CRC 140
00028 
00029 
00030 
00031 #define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \
00032         "POSITION_TARGET_LOCAL_NED", \
00033         14, \
00034         {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \
00035          { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \
00036          { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \
00037          { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \
00038          { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \
00039          { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \
00040          { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \
00041          { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \
00042          { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \
00043          { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \
00044          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \
00045          { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \
00046          { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \
00047          { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \
00048          } \
00049 }
00050 
00051 
00074 static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00075                                                        uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
00076 {
00077 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00078         char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
00079         _mav_put_uint32_t(buf, 0, time_boot_ms);
00080         _mav_put_float(buf, 4, x);
00081         _mav_put_float(buf, 8, y);
00082         _mav_put_float(buf, 12, z);
00083         _mav_put_float(buf, 16, vx);
00084         _mav_put_float(buf, 20, vy);
00085         _mav_put_float(buf, 24, vz);
00086         _mav_put_float(buf, 28, afx);
00087         _mav_put_float(buf, 32, afy);
00088         _mav_put_float(buf, 36, afz);
00089         _mav_put_float(buf, 40, yaw);
00090         _mav_put_float(buf, 44, yaw_rate);
00091         _mav_put_uint16_t(buf, 48, type_mask);
00092         _mav_put_uint8_t(buf, 50, coordinate_frame);
00093 
00094         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00095 #else
00096         mavlink_position_target_local_ned_t packet;
00097         packet.time_boot_ms = time_boot_ms;
00098         packet.x = x;
00099         packet.y = y;
00100         packet.z = z;
00101         packet.vx = vx;
00102         packet.vy = vy;
00103         packet.vz = vz;
00104         packet.afx = afx;
00105         packet.afy = afy;
00106         packet.afz = afz;
00107         packet.yaw = yaw;
00108         packet.yaw_rate = yaw_rate;
00109         packet.type_mask = type_mask;
00110         packet.coordinate_frame = coordinate_frame;
00111 
00112         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00113 #endif
00114 
00115         msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
00116 #if MAVLINK_CRC_EXTRA
00117     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
00118 #else
00119     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00120 #endif
00121 }
00122 
00145 static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00146                                                            mavlink_message_t* msg,
00147                                                            uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
00148 {
00149 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00150         char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
00151         _mav_put_uint32_t(buf, 0, time_boot_ms);
00152         _mav_put_float(buf, 4, x);
00153         _mav_put_float(buf, 8, y);
00154         _mav_put_float(buf, 12, z);
00155         _mav_put_float(buf, 16, vx);
00156         _mav_put_float(buf, 20, vy);
00157         _mav_put_float(buf, 24, vz);
00158         _mav_put_float(buf, 28, afx);
00159         _mav_put_float(buf, 32, afy);
00160         _mav_put_float(buf, 36, afz);
00161         _mav_put_float(buf, 40, yaw);
00162         _mav_put_float(buf, 44, yaw_rate);
00163         _mav_put_uint16_t(buf, 48, type_mask);
00164         _mav_put_uint8_t(buf, 50, coordinate_frame);
00165 
00166         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00167 #else
00168         mavlink_position_target_local_ned_t packet;
00169         packet.time_boot_ms = time_boot_ms;
00170         packet.x = x;
00171         packet.y = y;
00172         packet.z = z;
00173         packet.vx = vx;
00174         packet.vy = vy;
00175         packet.vz = vz;
00176         packet.afx = afx;
00177         packet.afy = afy;
00178         packet.afz = afz;
00179         packet.yaw = yaw;
00180         packet.yaw_rate = yaw_rate;
00181         packet.type_mask = type_mask;
00182         packet.coordinate_frame = coordinate_frame;
00183 
00184         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00185 #endif
00186 
00187         msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
00188 #if MAVLINK_CRC_EXTRA
00189     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
00190 #else
00191     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00192 #endif
00193 }
00194 
00203 static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
00204 {
00205         return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
00206 }
00207 
00217 static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
00218 {
00219         return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
00220 }
00221 
00241 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00242 
00243 static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
00244 {
00245 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00246         char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
00247         _mav_put_uint32_t(buf, 0, time_boot_ms);
00248         _mav_put_float(buf, 4, x);
00249         _mav_put_float(buf, 8, y);
00250         _mav_put_float(buf, 12, z);
00251         _mav_put_float(buf, 16, vx);
00252         _mav_put_float(buf, 20, vy);
00253         _mav_put_float(buf, 24, vz);
00254         _mav_put_float(buf, 28, afx);
00255         _mav_put_float(buf, 32, afy);
00256         _mav_put_float(buf, 36, afz);
00257         _mav_put_float(buf, 40, yaw);
00258         _mav_put_float(buf, 44, yaw_rate);
00259         _mav_put_uint16_t(buf, 48, type_mask);
00260         _mav_put_uint8_t(buf, 50, coordinate_frame);
00261 
00262 #if MAVLINK_CRC_EXTRA
00263     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
00264 #else
00265     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00266 #endif
00267 #else
00268         mavlink_position_target_local_ned_t packet;
00269         packet.time_boot_ms = time_boot_ms;
00270         packet.x = x;
00271         packet.y = y;
00272         packet.z = z;
00273         packet.vx = vx;
00274         packet.vy = vy;
00275         packet.vz = vz;
00276         packet.afx = afx;
00277         packet.afy = afy;
00278         packet.afz = afz;
00279         packet.yaw = yaw;
00280         packet.yaw_rate = yaw_rate;
00281         packet.type_mask = type_mask;
00282         packet.coordinate_frame = coordinate_frame;
00283 
00284 #if MAVLINK_CRC_EXTRA
00285     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
00286 #else
00287     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00288 #endif
00289 #endif
00290 }
00291 
00292 #if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00293 /*
00294   This varient of _send() can be used to save stack space by re-using
00295   memory from the receive buffer.  The caller provides a
00296   mavlink_message_t which is the size of a full mavlink message. This
00297   is usually the receive buffer for the channel, and allows a reply to an
00298   incoming message with minimum stack space usage.
00299  */
00300 static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
00301 {
00302 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00303         char *buf = (char *)msgbuf;
00304         _mav_put_uint32_t(buf, 0, time_boot_ms);
00305         _mav_put_float(buf, 4, x);
00306         _mav_put_float(buf, 8, y);
00307         _mav_put_float(buf, 12, z);
00308         _mav_put_float(buf, 16, vx);
00309         _mav_put_float(buf, 20, vy);
00310         _mav_put_float(buf, 24, vz);
00311         _mav_put_float(buf, 28, afx);
00312         _mav_put_float(buf, 32, afy);
00313         _mav_put_float(buf, 36, afz);
00314         _mav_put_float(buf, 40, yaw);
00315         _mav_put_float(buf, 44, yaw_rate);
00316         _mav_put_uint16_t(buf, 48, type_mask);
00317         _mav_put_uint8_t(buf, 50, coordinate_frame);
00318 
00319 #if MAVLINK_CRC_EXTRA
00320     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
00321 #else
00322     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00323 #endif
00324 #else
00325         mavlink_position_target_local_ned_t *packet = (mavlink_position_target_local_ned_t *)msgbuf;
00326         packet->time_boot_ms = time_boot_ms;
00327         packet->x = x;
00328         packet->y = y;
00329         packet->z = z;
00330         packet->vx = vx;
00331         packet->vy = vy;
00332         packet->vz = vz;
00333         packet->afx = afx;
00334         packet->afy = afy;
00335         packet->afz = afz;
00336         packet->yaw = yaw;
00337         packet->yaw_rate = yaw_rate;
00338         packet->type_mask = type_mask;
00339         packet->coordinate_frame = coordinate_frame;
00340 
00341 #if MAVLINK_CRC_EXTRA
00342     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
00343 #else
00344     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00345 #endif
00346 #endif
00347 }
00348 #endif
00349 
00350 #endif
00351 
00352 // MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING
00353 
00354 
00360 static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg)
00361 {
00362         return _MAV_RETURN_uint32_t(msg,  0);
00363 }
00364 
00370 static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg)
00371 {
00372         return _MAV_RETURN_uint8_t(msg,  50);
00373 }
00374 
00380 static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg)
00381 {
00382         return _MAV_RETURN_uint16_t(msg,  48);
00383 }
00384 
00390 static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg)
00391 {
00392         return _MAV_RETURN_float(msg,  4);
00393 }
00394 
00400 static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg)
00401 {
00402         return _MAV_RETURN_float(msg,  8);
00403 }
00404 
00410 static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg)
00411 {
00412         return _MAV_RETURN_float(msg,  12);
00413 }
00414 
00420 static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg)
00421 {
00422         return _MAV_RETURN_float(msg,  16);
00423 }
00424 
00430 static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg)
00431 {
00432         return _MAV_RETURN_float(msg,  20);
00433 }
00434 
00440 static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg)
00441 {
00442         return _MAV_RETURN_float(msg,  24);
00443 }
00444 
00450 static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg)
00451 {
00452         return _MAV_RETURN_float(msg,  28);
00453 }
00454 
00460 static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg)
00461 {
00462         return _MAV_RETURN_float(msg,  32);
00463 }
00464 
00470 static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg)
00471 {
00472         return _MAV_RETURN_float(msg,  36);
00473 }
00474 
00480 static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg)
00481 {
00482         return _MAV_RETURN_float(msg,  40);
00483 }
00484 
00490 static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg)
00491 {
00492         return _MAV_RETURN_float(msg,  44);
00493 }
00494 
00501 static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned)
00502 {
00503 #if MAVLINK_NEED_BYTE_SWAP
00504         position_target_local_ned->time_boot_ms = mavlink_msg_position_target_local_ned_get_time_boot_ms(msg);
00505         position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg);
00506         position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg);
00507         position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg);
00508         position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg);
00509         position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg);
00510         position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg);
00511         position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg);
00512         position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg);
00513         position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg);
00514         position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg);
00515         position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg);
00516         position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg);
00517         position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg);
00518 #else
00519         memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
00520 #endif
00521 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35