Code for autonomous rover for Sparkfun AVC. DataBus won 3rd in 2012 and the same code was used on Troubled Child, a 1986 Jeep Grand Wagoneer to win 1st in 2014.

Dependencies:   mbed Watchdog SDFileSystem DigoleSerialDisp

Committer:
shimniok
Date:
Fri Nov 30 16:11:53 2018 +0000
Revision:
25:bb5356402687
Parent:
0:a6a169de725f
Initial publish of revised version.

Who changed what in which revision?

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