00001
00002
00003 #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62
00004
00005 typedef struct __mavlink_nav_controller_output_t
00006 {
00007 float nav_roll;
00008 float nav_pitch;
00009 float alt_error;
00010 float aspd_error;
00011 float xtrack_error;
00012 int16_t nav_bearing;
00013 int16_t target_bearing;
00014 uint16_t wp_dist;
00015 } mavlink_nav_controller_output_t;
00016
00017 #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26
00018 #define MAVLINK_MSG_ID_62_LEN 26
00019
00020 #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183
00021 #define MAVLINK_MSG_ID_62_CRC 183
00022
00023
00024
00025 #define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \
00026 "NAV_CONTROLLER_OUTPUT", \
00027 8, \
00028 { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \
00029 { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \
00030 { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
00031 { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
00032 { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
00033 { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \
00034 { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \
00035 { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \
00036 } \
00037 }
00038
00039
00056 static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00057 float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
00058 {
00059 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00060 char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
00061 _mav_put_float(buf, 0, nav_roll);
00062 _mav_put_float(buf, 4, nav_pitch);
00063 _mav_put_float(buf, 8, alt_error);
00064 _mav_put_float(buf, 12, aspd_error);
00065 _mav_put_float(buf, 16, xtrack_error);
00066 _mav_put_int16_t(buf, 20, nav_bearing);
00067 _mav_put_int16_t(buf, 22, target_bearing);
00068 _mav_put_uint16_t(buf, 24, wp_dist);
00069
00070 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00071 #else
00072 mavlink_nav_controller_output_t packet;
00073 packet.nav_roll = nav_roll;
00074 packet.nav_pitch = nav_pitch;
00075 packet.alt_error = alt_error;
00076 packet.aspd_error = aspd_error;
00077 packet.xtrack_error = xtrack_error;
00078 packet.nav_bearing = nav_bearing;
00079 packet.target_bearing = target_bearing;
00080 packet.wp_dist = wp_dist;
00081
00082 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00083 #endif
00084
00085 msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
00086 #if MAVLINK_CRC_EXTRA
00087 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
00088 #else
00089 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00090 #endif
00091 }
00092
00109 static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00110 mavlink_message_t* msg,
00111 float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error)
00112 {
00113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00114 char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
00115 _mav_put_float(buf, 0, nav_roll);
00116 _mav_put_float(buf, 4, nav_pitch);
00117 _mav_put_float(buf, 8, alt_error);
00118 _mav_put_float(buf, 12, aspd_error);
00119 _mav_put_float(buf, 16, xtrack_error);
00120 _mav_put_int16_t(buf, 20, nav_bearing);
00121 _mav_put_int16_t(buf, 22, target_bearing);
00122 _mav_put_uint16_t(buf, 24, wp_dist);
00123
00124 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00125 #else
00126 mavlink_nav_controller_output_t packet;
00127 packet.nav_roll = nav_roll;
00128 packet.nav_pitch = nav_pitch;
00129 packet.alt_error = alt_error;
00130 packet.aspd_error = aspd_error;
00131 packet.xtrack_error = xtrack_error;
00132 packet.nav_bearing = nav_bearing;
00133 packet.target_bearing = target_bearing;
00134 packet.wp_dist = wp_dist;
00135
00136 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00137 #endif
00138
00139 msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
00140 #if MAVLINK_CRC_EXTRA
00141 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
00142 #else
00143 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00144 #endif
00145 }
00146
00155 static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output)
00156 {
00157 return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error);
00158 }
00159
00169 static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output)
00170 {
00171 return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error);
00172 }
00173
00187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00188
00189 static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
00190 {
00191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00192 char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
00193 _mav_put_float(buf, 0, nav_roll);
00194 _mav_put_float(buf, 4, nav_pitch);
00195 _mav_put_float(buf, 8, alt_error);
00196 _mav_put_float(buf, 12, aspd_error);
00197 _mav_put_float(buf, 16, xtrack_error);
00198 _mav_put_int16_t(buf, 20, nav_bearing);
00199 _mav_put_int16_t(buf, 22, target_bearing);
00200 _mav_put_uint16_t(buf, 24, wp_dist);
00201
00202 #if MAVLINK_CRC_EXTRA
00203 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
00204 #else
00205 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00206 #endif
00207 #else
00208 mavlink_nav_controller_output_t packet;
00209 packet.nav_roll = nav_roll;
00210 packet.nav_pitch = nav_pitch;
00211 packet.alt_error = alt_error;
00212 packet.aspd_error = aspd_error;
00213 packet.xtrack_error = xtrack_error;
00214 packet.nav_bearing = nav_bearing;
00215 packet.target_bearing = target_bearing;
00216 packet.wp_dist = wp_dist;
00217
00218 #if MAVLINK_CRC_EXTRA
00219 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
00220 #else
00221 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00222 #endif
00223 #endif
00224 }
00225
00226 #if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00227
00228
00229
00230
00231
00232
00233
00234 static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
00235 {
00236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00237 char *buf = (char *)msgbuf;
00238 _mav_put_float(buf, 0, nav_roll);
00239 _mav_put_float(buf, 4, nav_pitch);
00240 _mav_put_float(buf, 8, alt_error);
00241 _mav_put_float(buf, 12, aspd_error);
00242 _mav_put_float(buf, 16, xtrack_error);
00243 _mav_put_int16_t(buf, 20, nav_bearing);
00244 _mav_put_int16_t(buf, 22, target_bearing);
00245 _mav_put_uint16_t(buf, 24, wp_dist);
00246
00247 #if MAVLINK_CRC_EXTRA
00248 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
00249 #else
00250 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00251 #endif
00252 #else
00253 mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf;
00254 packet->nav_roll = nav_roll;
00255 packet->nav_pitch = nav_pitch;
00256 packet->alt_error = alt_error;
00257 packet->aspd_error = aspd_error;
00258 packet->xtrack_error = xtrack_error;
00259 packet->nav_bearing = nav_bearing;
00260 packet->target_bearing = target_bearing;
00261 packet->wp_dist = wp_dist;
00262
00263 #if MAVLINK_CRC_EXTRA
00264 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
00265 #else
00266 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00267 #endif
00268 #endif
00269 }
00270 #endif
00271
00272 #endif
00273
00274
00275
00276
00282 static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg)
00283 {
00284 return _MAV_RETURN_float(msg, 0);
00285 }
00286
00292 static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg)
00293 {
00294 return _MAV_RETURN_float(msg, 4);
00295 }
00296
00302 static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg)
00303 {
00304 return _MAV_RETURN_int16_t(msg, 20);
00305 }
00306
00312 static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg)
00313 {
00314 return _MAV_RETURN_int16_t(msg, 22);
00315 }
00316
00322 static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg)
00323 {
00324 return _MAV_RETURN_uint16_t(msg, 24);
00325 }
00326
00332 static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg)
00333 {
00334 return _MAV_RETURN_float(msg, 8);
00335 }
00336
00342 static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg)
00343 {
00344 return _MAV_RETURN_float(msg, 12);
00345 }
00346
00352 static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg)
00353 {
00354 return _MAV_RETURN_float(msg, 16);
00355 }
00356
00363 static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output)
00364 {
00365 #if MAVLINK_NEED_BYTE_SWAP
00366 nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg);
00367 nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg);
00368 nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg);
00369 nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg);
00370 nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg);
00371 nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg);
00372 nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg);
00373 nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg);
00374 #else
00375 memcpy(nav_controller_output, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
00376 #endif
00377 }