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_control_status.h
00001 // MESSAGE CONTROL_STATUS PACKING 00002 00003 #define MAVLINK_MSG_ID_CONTROL_STATUS 52 00004 00005 typedef struct __mavlink_control_status_t 00006 { 00007 uint8_t position_fix; ///< Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 00008 uint8_t vision_fix; ///< Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 00009 uint8_t gps_fix; ///< GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 00010 uint8_t ahrs_health; ///< Attitude estimation health: 0: poor, 255: excellent 00011 uint8_t control_att; ///< 0: Attitude control disabled, 1: enabled 00012 uint8_t control_pos_xy; ///< 0: X, Y position control disabled, 1: enabled 00013 uint8_t control_pos_z; ///< 0: Z position control disabled, 1: enabled 00014 uint8_t control_pos_yaw; ///< 0: Yaw angle control disabled, 1: enabled 00015 00016 } mavlink_control_status_t; 00017 00018 00019 00020 /** 00021 * @brief Pack a control_status 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 position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 00027 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 00028 * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 00029 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent 00030 * @param control_att 0: Attitude control disabled, 1: enabled 00031 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled 00032 * @param control_pos_z 0: Z position control disabled, 1: enabled 00033 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled 00034 * @return length of the message in bytes (excluding serial stream start sign) 00035 */ 00036 static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw) 00037 { 00038 uint16_t i = 0; 00039 msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS; 00040 00041 i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 00042 i += put_uint8_t_by_index(vision_fix, i, msg->payload); // Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 00043 i += put_uint8_t_by_index(gps_fix, i, msg->payload); // GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 00044 i += put_uint8_t_by_index(ahrs_health, i, msg->payload); // Attitude estimation health: 0: poor, 255: excellent 00045 i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled 00046 i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled 00047 i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled 00048 i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled 00049 00050 return mavlink_finalize_message(msg, system_id, component_id, i); 00051 } 00052 00053 /** 00054 * @brief Pack a control_status 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 position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 00060 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 00061 * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 00062 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent 00063 * @param control_att 0: Attitude control disabled, 1: enabled 00064 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled 00065 * @param control_pos_z 0: Z position control disabled, 1: enabled 00066 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled 00067 * @return length of the message in bytes (excluding serial stream start sign) 00068 */ 00069 static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw) 00070 { 00071 uint16_t i = 0; 00072 msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS; 00073 00074 i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 00075 i += put_uint8_t_by_index(vision_fix, i, msg->payload); // Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 00076 i += put_uint8_t_by_index(gps_fix, i, msg->payload); // GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 00077 i += put_uint8_t_by_index(ahrs_health, i, msg->payload); // Attitude estimation health: 0: poor, 255: excellent 00078 i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled 00079 i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled 00080 i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled 00081 i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled 00082 00083 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00084 } 00085 00086 /** 00087 * @brief Encode a control_status 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 control_status C-struct to read the message contents from 00093 */ 00094 static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_status_t* control_status) 00095 { 00096 return mavlink_msg_control_status_pack(system_id, component_id, msg, control_status->position_fix, control_status->vision_fix, control_status->gps_fix, control_status->ahrs_health, control_status->control_att, control_status->control_pos_xy, control_status->control_pos_z, control_status->control_pos_yaw); 00097 } 00098 00099 /** 00100 * @brief Send a control_status message 00101 * @param chan MAVLink channel to send the message 00102 * 00103 * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 00104 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 00105 * @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 00106 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent 00107 * @param control_att 0: Attitude control disabled, 1: enabled 00108 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled 00109 * @param control_pos_z 0: Z position control disabled, 1: enabled 00110 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled 00111 */ 00112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00113 00114 static inline void mavlink_msg_control_status_send(mavlink_channel_t chan, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw) 00115 { 00116 mavlink_message_t msg; 00117 mavlink_msg_control_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw); 00118 mavlink_send_uart(chan, &msg); 00119 } 00120 00121 #endif 00122 // MESSAGE CONTROL_STATUS UNPACKING 00123 00124 /** 00125 * @brief Get field position_fix from control_status message 00126 * 00127 * @return Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 00128 */ 00129 static inline uint8_t mavlink_msg_control_status_get_position_fix(const mavlink_message_t* msg) 00130 { 00131 return (uint8_t)(msg->payload)[0]; 00132 } 00133 00134 /** 00135 * @brief Get field vision_fix from control_status message 00136 * 00137 * @return Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 00138 */ 00139 static inline uint8_t mavlink_msg_control_status_get_vision_fix(const mavlink_message_t* msg) 00140 { 00141 return (uint8_t)(msg->payload+sizeof(uint8_t))[0]; 00142 } 00143 00144 /** 00145 * @brief Get field gps_fix from control_status message 00146 * 00147 * @return GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 00148 */ 00149 static inline uint8_t mavlink_msg_control_status_get_gps_fix(const mavlink_message_t* msg) 00150 { 00151 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00152 } 00153 00154 /** 00155 * @brief Get field ahrs_health from control_status message 00156 * 00157 * @return Attitude estimation health: 0: poor, 255: excellent 00158 */ 00159 static inline uint8_t mavlink_msg_control_status_get_ahrs_health(const mavlink_message_t* msg) 00160 { 00161 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00162 } 00163 00164 /** 00165 * @brief Get field control_att from control_status message 00166 * 00167 * @return 0: Attitude control disabled, 1: enabled 00168 */ 00169 static inline uint8_t mavlink_msg_control_status_get_control_att(const mavlink_message_t* msg) 00170 { 00171 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00172 } 00173 00174 /** 00175 * @brief Get field control_pos_xy from control_status message 00176 * 00177 * @return 0: X, Y position control disabled, 1: enabled 00178 */ 00179 static inline uint8_t mavlink_msg_control_status_get_control_pos_xy(const mavlink_message_t* msg) 00180 { 00181 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00182 } 00183 00184 /** 00185 * @brief Get field control_pos_z from control_status message 00186 * 00187 * @return 0: Z position control disabled, 1: enabled 00188 */ 00189 static inline uint8_t mavlink_msg_control_status_get_control_pos_z(const mavlink_message_t* msg) 00190 { 00191 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00192 } 00193 00194 /** 00195 * @brief Get field control_pos_yaw from control_status message 00196 * 00197 * @return 0: Yaw angle control disabled, 1: enabled 00198 */ 00199 static inline uint8_t mavlink_msg_control_status_get_control_pos_yaw(const mavlink_message_t* msg) 00200 { 00201 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0]; 00202 } 00203 00204 /** 00205 * @brief Decode a control_status message into a struct 00206 * 00207 * @param msg The message to decode 00208 * @param control_status C-struct to decode the message contents into 00209 */ 00210 static inline void mavlink_msg_control_status_decode(const mavlink_message_t* msg, mavlink_control_status_t* control_status) 00211 { 00212 control_status->position_fix = mavlink_msg_control_status_get_position_fix(msg); 00213 control_status->vision_fix = mavlink_msg_control_status_get_vision_fix(msg); 00214 control_status->gps_fix = mavlink_msg_control_status_get_gps_fix(msg); 00215 control_status->ahrs_health = mavlink_msg_control_status_get_ahrs_health(msg); 00216 control_status->control_att = mavlink_msg_control_status_get_control_att(msg); 00217 control_status->control_pos_xy = mavlink_msg_control_status_get_control_pos_xy(msg); 00218 control_status->control_pos_z = mavlink_msg_control_status_get_control_pos_z(msg); 00219 control_status->control_pos_yaw = mavlink_msg_control_status_get_control_pos_yaw(msg); 00220 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2