Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
mavlink_msg_nav_controller_output.h
00001 // MESSAGE NAV_CONTROLLER_OUTPUT PACKING 00002 00003 #define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 00004 00005 typedef struct __mavlink_nav_controller_output_t 00006 { 00007 float nav_roll; ///< Current desired roll in degrees 00008 float nav_pitch; ///< Current desired pitch in degrees 00009 int16_t nav_bearing; ///< Current desired heading in degrees 00010 int16_t target_bearing; ///< Bearing to current waypoint/target in degrees 00011 uint16_t wp_dist; ///< Distance to active waypoint in meters 00012 float alt_error; ///< Current altitude error in meters 00013 float aspd_error; ///< Current airspeed error in meters/second 00014 float xtrack_error; ///< Current crosstrack error on x-y plane in meters 00015 00016 } mavlink_nav_controller_output_t; 00017 00018 00019 00020 /** 00021 * @brief Pack a nav_controller_output message 00022 * @param system_id ID of this system 00023 * @param component_id ID of this component (e.g. 200 for IMU) 00024 * @param msg The MAVLink message to compress the data into 00025 * 00026 * @param nav_roll Current desired roll in degrees 00027 * @param nav_pitch Current desired pitch in degrees 00028 * @param nav_bearing Current desired heading in degrees 00029 * @param target_bearing Bearing to current waypoint/target in degrees 00030 * @param wp_dist Distance to active waypoint in meters 00031 * @param alt_error Current altitude error in meters 00032 * @param aspd_error Current airspeed error in meters/second 00033 * @param xtrack_error Current crosstrack error on x-y plane in meters 00034 * @return length of the message in bytes (excluding serial stream start sign) 00035 */ 00036 static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, 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) 00037 { 00038 uint16_t i = 0; 00039 msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; 00040 00041 i += put_float_by_index(nav_roll, i, msg->payload); // Current desired roll in degrees 00042 i += put_float_by_index(nav_pitch, i, msg->payload); // Current desired pitch in degrees 00043 i += put_int16_t_by_index(nav_bearing, i, msg->payload); // Current desired heading in degrees 00044 i += put_int16_t_by_index(target_bearing, i, msg->payload); // Bearing to current waypoint/target in degrees 00045 i += put_uint16_t_by_index(wp_dist, i, msg->payload); // Distance to active waypoint in meters 00046 i += put_float_by_index(alt_error, i, msg->payload); // Current altitude error in meters 00047 i += put_float_by_index(aspd_error, i, msg->payload); // Current airspeed error in meters/second 00048 i += put_float_by_index(xtrack_error, i, msg->payload); // Current crosstrack error on x-y plane in meters 00049 00050 return mavlink_finalize_message(msg, system_id, component_id, i); 00051 } 00052 00053 /** 00054 * @brief Pack a nav_controller_output message 00055 * @param system_id ID of this system 00056 * @param component_id ID of this component (e.g. 200 for IMU) 00057 * @param chan The MAVLink channel this message was sent over 00058 * @param msg The MAVLink message to compress the data into 00059 * @param nav_roll Current desired roll in degrees 00060 * @param nav_pitch Current desired pitch in degrees 00061 * @param nav_bearing Current desired heading in degrees 00062 * @param target_bearing Bearing to current waypoint/target in degrees 00063 * @param wp_dist Distance to active waypoint in meters 00064 * @param alt_error Current altitude error in meters 00065 * @param aspd_error Current airspeed error in meters/second 00066 * @param xtrack_error Current crosstrack error on x-y plane in meters 00067 * @return length of the message in bytes (excluding serial stream start sign) 00068 */ 00069 static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, 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) 00070 { 00071 uint16_t i = 0; 00072 msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; 00073 00074 i += put_float_by_index(nav_roll, i, msg->payload); // Current desired roll in degrees 00075 i += put_float_by_index(nav_pitch, i, msg->payload); // Current desired pitch in degrees 00076 i += put_int16_t_by_index(nav_bearing, i, msg->payload); // Current desired heading in degrees 00077 i += put_int16_t_by_index(target_bearing, i, msg->payload); // Bearing to current waypoint/target in degrees 00078 i += put_uint16_t_by_index(wp_dist, i, msg->payload); // Distance to active waypoint in meters 00079 i += put_float_by_index(alt_error, i, msg->payload); // Current altitude error in meters 00080 i += put_float_by_index(aspd_error, i, msg->payload); // Current airspeed error in meters/second 00081 i += put_float_by_index(xtrack_error, i, msg->payload); // Current crosstrack error on x-y plane in meters 00082 00083 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00084 } 00085 00086 /** 00087 * @brief Encode a nav_controller_output struct into a message 00088 * 00089 * @param system_id ID of this system 00090 * @param component_id ID of this component (e.g. 200 for IMU) 00091 * @param msg The MAVLink message to compress the data into 00092 * @param nav_controller_output C-struct to read the message contents from 00093 */ 00094 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) 00095 { 00096 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); 00097 } 00098 00099 /** 00100 * @brief Send a nav_controller_output message 00101 * @param chan MAVLink channel to send the message 00102 * 00103 * @param nav_roll Current desired roll in degrees 00104 * @param nav_pitch Current desired pitch in degrees 00105 * @param nav_bearing Current desired heading in degrees 00106 * @param target_bearing Bearing to current waypoint/target in degrees 00107 * @param wp_dist Distance to active waypoint in meters 00108 * @param alt_error Current altitude error in meters 00109 * @param aspd_error Current airspeed error in meters/second 00110 * @param xtrack_error Current crosstrack error on x-y plane in meters 00111 */ 00112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00113 00114 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) 00115 { 00116 mavlink_message_t msg; 00117 mavlink_msg_nav_controller_output_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error); 00118 mavlink_send_uart(chan, &msg); 00119 } 00120 00121 #endif 00122 // MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING 00123 00124 /** 00125 * @brief Get field nav_roll from nav_controller_output message 00126 * 00127 * @return Current desired roll in degrees 00128 */ 00129 static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) 00130 { 00131 generic_32bit r; 00132 r.b[3] = (msg->payload)[0]; 00133 r.b[2] = (msg->payload)[1]; 00134 r.b[1] = (msg->payload)[2]; 00135 r.b[0] = (msg->payload)[3]; 00136 return (float)r.f; 00137 } 00138 00139 /** 00140 * @brief Get field nav_pitch from nav_controller_output message 00141 * 00142 * @return Current desired pitch in degrees 00143 */ 00144 static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) 00145 { 00146 generic_32bit r; 00147 r.b[3] = (msg->payload+sizeof(float))[0]; 00148 r.b[2] = (msg->payload+sizeof(float))[1]; 00149 r.b[1] = (msg->payload+sizeof(float))[2]; 00150 r.b[0] = (msg->payload+sizeof(float))[3]; 00151 return (float)r.f; 00152 } 00153 00154 /** 00155 * @brief Get field nav_bearing from nav_controller_output message 00156 * 00157 * @return Current desired heading in degrees 00158 */ 00159 static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) 00160 { 00161 generic_16bit r; 00162 r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[0]; 00163 r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[1]; 00164 return (int16_t)r.s; 00165 } 00166 00167 /** 00168 * @brief Get field target_bearing from nav_controller_output message 00169 * 00170 * @return Bearing to current waypoint/target in degrees 00171 */ 00172 static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) 00173 { 00174 generic_16bit r; 00175 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[0]; 00176 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t))[1]; 00177 return (int16_t)r.s; 00178 } 00179 00180 /** 00181 * @brief Get field wp_dist from nav_controller_output message 00182 * 00183 * @return Distance to active waypoint in meters 00184 */ 00185 static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) 00186 { 00187 generic_16bit r; 00188 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[0]; 00189 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t))[1]; 00190 return (uint16_t)r.s; 00191 } 00192 00193 /** 00194 * @brief Get field alt_error from nav_controller_output message 00195 * 00196 * @return Current altitude error in meters 00197 */ 00198 static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) 00199 { 00200 generic_32bit r; 00201 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[0]; 00202 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[1]; 00203 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[2]; 00204 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t))[3]; 00205 return (float)r.f; 00206 } 00207 00208 /** 00209 * @brief Get field aspd_error from nav_controller_output message 00210 * 00211 * @return Current airspeed error in meters/second 00212 */ 00213 static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) 00214 { 00215 generic_32bit r; 00216 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[0]; 00217 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[1]; 00218 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[2]; 00219 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float))[3]; 00220 return (float)r.f; 00221 } 00222 00223 /** 00224 * @brief Get field xtrack_error from nav_controller_output message 00225 * 00226 * @return Current crosstrack error on x-y plane in meters 00227 */ 00228 static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) 00229 { 00230 generic_32bit r; 00231 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; 00232 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; 00233 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; 00234 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; 00235 return (float)r.f; 00236 } 00237 00238 /** 00239 * @brief Decode a nav_controller_output message into a struct 00240 * 00241 * @param msg The message to decode 00242 * @param nav_controller_output C-struct to decode the message contents into 00243 */ 00244 static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) 00245 { 00246 nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); 00247 nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); 00248 nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); 00249 nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); 00250 nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); 00251 nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); 00252 nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); 00253 nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); 00254 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2