Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Committer:
shimniok
Date:
Wed Jun 20 14:57:48 2012 +0000
Revision:
0:826c6171fc1b
Updated documentation

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimniok 0:826c6171fc1b 1 // MESSAGE CONTROL_STATUS PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_CONTROL_STATUS 52
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_control_status_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint8_t position_fix; ///< Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
shimniok 0:826c6171fc1b 8 uint8_t vision_fix; ///< Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
shimniok 0:826c6171fc1b 9 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
shimniok 0:826c6171fc1b 10 uint8_t ahrs_health; ///< Attitude estimation health: 0: poor, 255: excellent
shimniok 0:826c6171fc1b 11 uint8_t control_att; ///< 0: Attitude control disabled, 1: enabled
shimniok 0:826c6171fc1b 12 uint8_t control_pos_xy; ///< 0: X, Y position control disabled, 1: enabled
shimniok 0:826c6171fc1b 13 uint8_t control_pos_z; ///< 0: Z position control disabled, 1: enabled
shimniok 0:826c6171fc1b 14 uint8_t control_pos_yaw; ///< 0: Yaw angle control disabled, 1: enabled
shimniok 0:826c6171fc1b 15
shimniok 0:826c6171fc1b 16 } mavlink_control_status_t;
shimniok 0:826c6171fc1b 17
shimniok 0:826c6171fc1b 18
shimniok 0:826c6171fc1b 19
shimniok 0:826c6171fc1b 20 /**
shimniok 0:826c6171fc1b 21 * @brief Pack a control_status message
shimniok 0:826c6171fc1b 22 * @param system_id ID of this system
shimniok 0:826c6171fc1b 23 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 24 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 25 *
shimniok 0:826c6171fc1b 26 * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
shimniok 0:826c6171fc1b 27 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
shimniok 0:826c6171fc1b 28 * @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
shimniok 0:826c6171fc1b 29 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
shimniok 0:826c6171fc1b 30 * @param control_att 0: Attitude control disabled, 1: enabled
shimniok 0:826c6171fc1b 31 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
shimniok 0:826c6171fc1b 32 * @param control_pos_z 0: Z position control disabled, 1: enabled
shimniok 0:826c6171fc1b 33 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
shimniok 0:826c6171fc1b 34 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 35 */
shimniok 0:826c6171fc1b 36 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)
shimniok 0:826c6171fc1b 37 {
shimniok 0:826c6171fc1b 38 uint16_t i = 0;
shimniok 0:826c6171fc1b 39 msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
shimniok 0:826c6171fc1b 40
shimniok 0:826c6171fc1b 41 i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
shimniok 0:826c6171fc1b 42 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
shimniok 0:826c6171fc1b 43 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
shimniok 0:826c6171fc1b 44 i += put_uint8_t_by_index(ahrs_health, i, msg->payload); // Attitude estimation health: 0: poor, 255: excellent
shimniok 0:826c6171fc1b 45 i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled
shimniok 0:826c6171fc1b 46 i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled
shimniok 0:826c6171fc1b 47 i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled
shimniok 0:826c6171fc1b 48 i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled
shimniok 0:826c6171fc1b 49
shimniok 0:826c6171fc1b 50 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 51 }
shimniok 0:826c6171fc1b 52
shimniok 0:826c6171fc1b 53 /**
shimniok 0:826c6171fc1b 54 * @brief Pack a control_status message
shimniok 0:826c6171fc1b 55 * @param system_id ID of this system
shimniok 0:826c6171fc1b 56 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 57 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 58 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 59 * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
shimniok 0:826c6171fc1b 60 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
shimniok 0:826c6171fc1b 61 * @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
shimniok 0:826c6171fc1b 62 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
shimniok 0:826c6171fc1b 63 * @param control_att 0: Attitude control disabled, 1: enabled
shimniok 0:826c6171fc1b 64 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
shimniok 0:826c6171fc1b 65 * @param control_pos_z 0: Z position control disabled, 1: enabled
shimniok 0:826c6171fc1b 66 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
shimniok 0:826c6171fc1b 67 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 68 */
shimniok 0:826c6171fc1b 69 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)
shimniok 0:826c6171fc1b 70 {
shimniok 0:826c6171fc1b 71 uint16_t i = 0;
shimniok 0:826c6171fc1b 72 msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
shimniok 0:826c6171fc1b 73
shimniok 0:826c6171fc1b 74 i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
shimniok 0:826c6171fc1b 75 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
shimniok 0:826c6171fc1b 76 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
shimniok 0:826c6171fc1b 77 i += put_uint8_t_by_index(ahrs_health, i, msg->payload); // Attitude estimation health: 0: poor, 255: excellent
shimniok 0:826c6171fc1b 78 i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled
shimniok 0:826c6171fc1b 79 i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled
shimniok 0:826c6171fc1b 80 i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled
shimniok 0:826c6171fc1b 81 i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled
shimniok 0:826c6171fc1b 82
shimniok 0:826c6171fc1b 83 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 84 }
shimniok 0:826c6171fc1b 85
shimniok 0:826c6171fc1b 86 /**
shimniok 0:826c6171fc1b 87 * @brief Encode a control_status struct into a message
shimniok 0:826c6171fc1b 88 *
shimniok 0:826c6171fc1b 89 * @param system_id ID of this system
shimniok 0:826c6171fc1b 90 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 91 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 92 * @param control_status C-struct to read the message contents from
shimniok 0:826c6171fc1b 93 */
shimniok 0:826c6171fc1b 94 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)
shimniok 0:826c6171fc1b 95 {
shimniok 0:826c6171fc1b 96 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);
shimniok 0:826c6171fc1b 97 }
shimniok 0:826c6171fc1b 98
shimniok 0:826c6171fc1b 99 /**
shimniok 0:826c6171fc1b 100 * @brief Send a control_status message
shimniok 0:826c6171fc1b 101 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 102 *
shimniok 0:826c6171fc1b 103 * @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
shimniok 0:826c6171fc1b 104 * @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
shimniok 0:826c6171fc1b 105 * @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
shimniok 0:826c6171fc1b 106 * @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
shimniok 0:826c6171fc1b 107 * @param control_att 0: Attitude control disabled, 1: enabled
shimniok 0:826c6171fc1b 108 * @param control_pos_xy 0: X, Y position control disabled, 1: enabled
shimniok 0:826c6171fc1b 109 * @param control_pos_z 0: Z position control disabled, 1: enabled
shimniok 0:826c6171fc1b 110 * @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
shimniok 0:826c6171fc1b 111 */
shimniok 0:826c6171fc1b 112 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 113
shimniok 0:826c6171fc1b 114 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)
shimniok 0:826c6171fc1b 115 {
shimniok 0:826c6171fc1b 116 mavlink_message_t msg;
shimniok 0:826c6171fc1b 117 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);
shimniok 0:826c6171fc1b 118 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 119 }
shimniok 0:826c6171fc1b 120
shimniok 0:826c6171fc1b 121 #endif
shimniok 0:826c6171fc1b 122 // MESSAGE CONTROL_STATUS UNPACKING
shimniok 0:826c6171fc1b 123
shimniok 0:826c6171fc1b 124 /**
shimniok 0:826c6171fc1b 125 * @brief Get field position_fix from control_status message
shimniok 0:826c6171fc1b 126 *
shimniok 0:826c6171fc1b 127 * @return Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
shimniok 0:826c6171fc1b 128 */
shimniok 0:826c6171fc1b 129 static inline uint8_t mavlink_msg_control_status_get_position_fix(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 130 {
shimniok 0:826c6171fc1b 131 return (uint8_t)(msg->payload)[0];
shimniok 0:826c6171fc1b 132 }
shimniok 0:826c6171fc1b 133
shimniok 0:826c6171fc1b 134 /**
shimniok 0:826c6171fc1b 135 * @brief Get field vision_fix from control_status message
shimniok 0:826c6171fc1b 136 *
shimniok 0:826c6171fc1b 137 * @return Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
shimniok 0:826c6171fc1b 138 */
shimniok 0:826c6171fc1b 139 static inline uint8_t mavlink_msg_control_status_get_vision_fix(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 140 {
shimniok 0:826c6171fc1b 141 return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 142 }
shimniok 0:826c6171fc1b 143
shimniok 0:826c6171fc1b 144 /**
shimniok 0:826c6171fc1b 145 * @brief Get field gps_fix from control_status message
shimniok 0:826c6171fc1b 146 *
shimniok 0:826c6171fc1b 147 * @return GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
shimniok 0:826c6171fc1b 148 */
shimniok 0:826c6171fc1b 149 static inline uint8_t mavlink_msg_control_status_get_gps_fix(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 150 {
shimniok 0:826c6171fc1b 151 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 152 }
shimniok 0:826c6171fc1b 153
shimniok 0:826c6171fc1b 154 /**
shimniok 0:826c6171fc1b 155 * @brief Get field ahrs_health from control_status message
shimniok 0:826c6171fc1b 156 *
shimniok 0:826c6171fc1b 157 * @return Attitude estimation health: 0: poor, 255: excellent
shimniok 0:826c6171fc1b 158 */
shimniok 0:826c6171fc1b 159 static inline uint8_t mavlink_msg_control_status_get_ahrs_health(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 160 {
shimniok 0:826c6171fc1b 161 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 162 }
shimniok 0:826c6171fc1b 163
shimniok 0:826c6171fc1b 164 /**
shimniok 0:826c6171fc1b 165 * @brief Get field control_att from control_status message
shimniok 0:826c6171fc1b 166 *
shimniok 0:826c6171fc1b 167 * @return 0: Attitude control disabled, 1: enabled
shimniok 0:826c6171fc1b 168 */
shimniok 0:826c6171fc1b 169 static inline uint8_t mavlink_msg_control_status_get_control_att(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 170 {
shimniok 0:826c6171fc1b 171 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 172 }
shimniok 0:826c6171fc1b 173
shimniok 0:826c6171fc1b 174 /**
shimniok 0:826c6171fc1b 175 * @brief Get field control_pos_xy from control_status message
shimniok 0:826c6171fc1b 176 *
shimniok 0:826c6171fc1b 177 * @return 0: X, Y position control disabled, 1: enabled
shimniok 0:826c6171fc1b 178 */
shimniok 0:826c6171fc1b 179 static inline uint8_t mavlink_msg_control_status_get_control_pos_xy(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 180 {
shimniok 0:826c6171fc1b 181 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 182 }
shimniok 0:826c6171fc1b 183
shimniok 0:826c6171fc1b 184 /**
shimniok 0:826c6171fc1b 185 * @brief Get field control_pos_z from control_status message
shimniok 0:826c6171fc1b 186 *
shimniok 0:826c6171fc1b 187 * @return 0: Z position control disabled, 1: enabled
shimniok 0:826c6171fc1b 188 */
shimniok 0:826c6171fc1b 189 static inline uint8_t mavlink_msg_control_status_get_control_pos_z(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 190 {
shimniok 0:826c6171fc1b 191 return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:826c6171fc1b 192 }
shimniok 0:826c6171fc1b 193
shimniok 0:826c6171fc1b 194 /**
shimniok 0:826c6171fc1b 195 * @brief Get field control_pos_yaw from control_status message
shimniok 0:826c6171fc1b 196 *
shimniok 0:826c6171fc1b 197 * @return 0: Yaw angle control disabled, 1: enabled
shimniok 0:826c6171fc1b 198 */
shimniok 0:826c6171fc1b 199 static inline uint8_t mavlink_msg_control_status_get_control_pos_yaw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 200 {
shimniok 0:826c6171fc1b 201 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];
shimniok 0:826c6171fc1b 202 }
shimniok 0:826c6171fc1b 203
shimniok 0:826c6171fc1b 204 /**
shimniok 0:826c6171fc1b 205 * @brief Decode a control_status message into a struct
shimniok 0:826c6171fc1b 206 *
shimniok 0:826c6171fc1b 207 * @param msg The message to decode
shimniok 0:826c6171fc1b 208 * @param control_status C-struct to decode the message contents into
shimniok 0:826c6171fc1b 209 */
shimniok 0:826c6171fc1b 210 static inline void mavlink_msg_control_status_decode(const mavlink_message_t* msg, mavlink_control_status_t* control_status)
shimniok 0:826c6171fc1b 211 {
shimniok 0:826c6171fc1b 212 control_status->position_fix = mavlink_msg_control_status_get_position_fix(msg);
shimniok 0:826c6171fc1b 213 control_status->vision_fix = mavlink_msg_control_status_get_vision_fix(msg);
shimniok 0:826c6171fc1b 214 control_status->gps_fix = mavlink_msg_control_status_get_gps_fix(msg);
shimniok 0:826c6171fc1b 215 control_status->ahrs_health = mavlink_msg_control_status_get_ahrs_health(msg);
shimniok 0:826c6171fc1b 216 control_status->control_att = mavlink_msg_control_status_get_control_att(msg);
shimniok 0:826c6171fc1b 217 control_status->control_pos_xy = mavlink_msg_control_status_get_control_pos_xy(msg);
shimniok 0:826c6171fc1b 218 control_status->control_pos_z = mavlink_msg_control_status_get_control_pos_z(msg);
shimniok 0:826c6171fc1b 219 control_status->control_pos_yaw = mavlink_msg_control_status_get_control_pos_yaw(msg);
shimniok 0:826c6171fc1b 220 }