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
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
140 #if MAVLINK_CRC_EXTRA
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
202 #if MAVLINK_CRC_EXTRA
218 #if MAVLINK_CRC_EXTRA
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;
247 #if MAVLINK_CRC_EXTRA
263 #if MAVLINK_CRC_EXTRA
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);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
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
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.
Definition: mavlink_helpers.h:105
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC
Definition: mavlink_msg_nav_controller_output.h:20
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
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
mavlink_channel_t
Definition: mavlink_types.h:178
struct __mavlink_nav_controller_output_t mavlink_nav_controller_output_t
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT
Definition: mavlink_msg_nav_controller_output.h:3
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN
Definition: mavlink_msg_nav_controller_output.h:17
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
float nav_pitch
Current desired pitch in degrees.
Definition: mavlink_msg_nav_controller_output.h:8
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.
Definition: mavlink_helpers.h:71
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140
float xtrack_error
Current crosstrack error on x-y plane in meters.
Definition: mavlink_msg_nav_controller_output.h:11