3 #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62
17 #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26
18 #define MAVLINK_MSG_ID_62_LEN 26
20 #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183
21 #define MAVLINK_MSG_ID_62_CRC 183
25 #define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \
26 "NAV_CONTROLLER_OUTPUT", \
28 { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \
29 { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \
30 { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
31 { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
32 { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
33 { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \
34 { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \
35 { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \
56 static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
57 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)
59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
60 char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
61 _mav_put_float(buf, 0, nav_roll);
62 _mav_put_float(buf, 4, nav_pitch);
63 _mav_put_float(buf, 8, alt_error);
64 _mav_put_float(buf, 12, aspd_error);
65 _mav_put_float(buf, 16, xtrack_error);
66 _mav_put_int16_t(buf, 20, nav_bearing);
67 _mav_put_int16_t(buf, 22, target_bearing);
68 _mav_put_uint16_t(buf, 24, wp_dist);
70 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
82 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
85 msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
87 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
89 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
109 static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
110 mavlink_message_t* msg,
111 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)
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
114 char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
115 _mav_put_float(buf, 0, nav_roll);
116 _mav_put_float(buf, 4, nav_pitch);
117 _mav_put_float(buf, 8, alt_error);
118 _mav_put_float(buf, 12, aspd_error);
119 _mav_put_float(buf, 16, xtrack_error);
120 _mav_put_int16_t(buf, 20, nav_bearing);
121 _mav_put_int16_t(buf, 22, target_bearing);
122 _mav_put_uint16_t(buf, 24, wp_dist);
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
136 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
139 msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
140 #if MAVLINK_CRC_EXTRA
141 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);
143 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
155 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)
157 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);
169 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)
171 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);
187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
189 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)
191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
192 char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
193 _mav_put_float(buf, 0, nav_roll);
194 _mav_put_float(buf, 4, nav_pitch);
195 _mav_put_float(buf, 8, alt_error);
196 _mav_put_float(buf, 12, aspd_error);
197 _mav_put_float(buf, 16, xtrack_error);
198 _mav_put_int16_t(buf, 20, nav_bearing);
199 _mav_put_int16_t(buf, 22, target_bearing);
200 _mav_put_uint16_t(buf, 24, wp_dist);
202 #if MAVLINK_CRC_EXTRA
203 _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);
205 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
218 #if MAVLINK_CRC_EXTRA
219 _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);
221 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (
const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
226 #if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
234 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)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
237 char *buf = (
char *)msgbuf;
238 _mav_put_float(buf, 0, nav_roll);
239 _mav_put_float(buf, 4, nav_pitch);
240 _mav_put_float(buf, 8, alt_error);
241 _mav_put_float(buf, 12, aspd_error);
242 _mav_put_float(buf, 16, xtrack_error);
243 _mav_put_int16_t(buf, 20, nav_bearing);
244 _mav_put_int16_t(buf, 22, target_bearing);
245 _mav_put_uint16_t(buf, 24, wp_dist);
247 #if MAVLINK_CRC_EXTRA
248 _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);
250 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
263 #if MAVLINK_CRC_EXTRA
264 _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);
266 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (
const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
282 static inline float mavlink_msg_nav_controller_output_get_nav_roll(
const mavlink_message_t* msg)
284 return _MAV_RETURN_float(msg, 0);
292 static inline float mavlink_msg_nav_controller_output_get_nav_pitch(
const mavlink_message_t* msg)
294 return _MAV_RETURN_float(msg, 4);
302 static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(
const mavlink_message_t* msg)
304 return _MAV_RETURN_int16_t(msg, 20);
312 static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(
const mavlink_message_t* msg)
314 return _MAV_RETURN_int16_t(msg, 22);
322 static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(
const mavlink_message_t* msg)
324 return _MAV_RETURN_uint16_t(msg, 24);
332 static inline float mavlink_msg_nav_controller_output_get_alt_error(
const mavlink_message_t* msg)
334 return _MAV_RETURN_float(msg, 8);
342 static inline float mavlink_msg_nav_controller_output_get_aspd_error(
const mavlink_message_t* msg)
344 return _MAV_RETURN_float(msg, 12);
352 static inline float mavlink_msg_nav_controller_output_get_xtrack_error(
const mavlink_message_t* msg)
354 return _MAV_RETURN_float(msg, 16);
365 #if MAVLINK_NEED_BYTE_SWAP
366 nav_controller_output->
nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg);
367 nav_controller_output->
nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg);
368 nav_controller_output->
alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg);
369 nav_controller_output->
aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg);
370 nav_controller_output->
xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg);
371 nav_controller_output->
nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg);
372 nav_controller_output->
target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg);
373 nav_controller_output->
wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg);
375 memcpy(nav_controller_output, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
int16_t nav_bearing
Current desired heading in degrees.
Definition: mavlink_msg_nav_controller_output.h:12
Definition: mavlink_msg_nav_controller_output.h:5
float nav_roll
Current desired roll in degrees.
Definition: mavlink_msg_nav_controller_output.h:7
float aspd_error
Current airspeed error in meters/second.
Definition: mavlink_msg_nav_controller_output.h:10
uint16_t wp_dist
Distance to active MISSION in meters.
Definition: mavlink_msg_nav_controller_output.h:14
float alt_error
Current altitude error in meters.
Definition: mavlink_msg_nav_controller_output.h:9
int16_t target_bearing
Bearing to current MISSION/target in degrees.
Definition: mavlink_msg_nav_controller_output.h:13
float nav_pitch
Current desired pitch in degrees.
Definition: mavlink_msg_nav_controller_output.h:8
float xtrack_error
Current crosstrack error on x-y plane in meters.
Definition: mavlink_msg_nav_controller_output.h:11