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 POSITION_CONTROL_SETPOINT_SET PACKING
shimniok 0:a6a169de725f 2
shimniok 0:a6a169de725f 3 #define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET 120
shimniok 0:a6a169de725f 4
shimniok 0:a6a169de725f 5 typedef struct __mavlink_position_control_setpoint_set_t
shimniok 0:a6a169de725f 6 {
shimniok 0:a6a169de725f 7 uint8_t target_system; ///< System ID
shimniok 0:a6a169de725f 8 uint8_t target_component; ///< Component ID
shimniok 0:a6a169de725f 9 uint16_t id; ///< ID of waypoint, 0 for plain position
shimniok 0:a6a169de725f 10 float x; ///< x position
shimniok 0:a6a169de725f 11 float y; ///< y position
shimniok 0:a6a169de725f 12 float z; ///< z position
shimniok 0:a6a169de725f 13 float yaw; ///< yaw orientation in radians, 0 = NORTH
shimniok 0:a6a169de725f 14
shimniok 0:a6a169de725f 15 } mavlink_position_control_setpoint_set_t;
shimniok 0:a6a169de725f 16
shimniok 0:a6a169de725f 17
shimniok 0:a6a169de725f 18
shimniok 0:a6a169de725f 19 /**
shimniok 0:a6a169de725f 20 * @brief Pack a position_control_setpoint_set message
shimniok 0:a6a169de725f 21 * @param system_id ID of this system
shimniok 0:a6a169de725f 22 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 23 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 24 *
shimniok 0:a6a169de725f 25 * @param target_system System ID
shimniok 0:a6a169de725f 26 * @param target_component Component ID
shimniok 0:a6a169de725f 27 * @param id ID of waypoint, 0 for plain position
shimniok 0:a6a169de725f 28 * @param x x position
shimniok 0:a6a169de725f 29 * @param y y position
shimniok 0:a6a169de725f 30 * @param z z position
shimniok 0:a6a169de725f 31 * @param yaw yaw orientation in radians, 0 = NORTH
shimniok 0:a6a169de725f 32 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:a6a169de725f 33 */
shimniok 0:a6a169de725f 34 static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
shimniok 0:a6a169de725f 35 {
shimniok 0:a6a169de725f 36 uint16_t i = 0;
shimniok 0:a6a169de725f 37 msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
shimniok 0:a6a169de725f 38
shimniok 0:a6a169de725f 39 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
shimniok 0:a6a169de725f 40 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
shimniok 0:a6a169de725f 41 i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
shimniok 0:a6a169de725f 42 i += put_float_by_index(x, i, msg->payload); // x position
shimniok 0:a6a169de725f 43 i += put_float_by_index(y, i, msg->payload); // y position
shimniok 0:a6a169de725f 44 i += put_float_by_index(z, i, msg->payload); // z position
shimniok 0:a6a169de725f 45 i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
shimniok 0:a6a169de725f 46
shimniok 0:a6a169de725f 47 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:a6a169de725f 48 }
shimniok 0:a6a169de725f 49
shimniok 0:a6a169de725f 50 /**
shimniok 0:a6a169de725f 51 * @brief Pack a position_control_setpoint_set message
shimniok 0:a6a169de725f 52 * @param system_id ID of this system
shimniok 0:a6a169de725f 53 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 54 * @param chan The MAVLink channel this message was sent over
shimniok 0:a6a169de725f 55 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 56 * @param target_system System ID
shimniok 0:a6a169de725f 57 * @param target_component Component ID
shimniok 0:a6a169de725f 58 * @param id ID of waypoint, 0 for plain position
shimniok 0:a6a169de725f 59 * @param x x position
shimniok 0:a6a169de725f 60 * @param y y position
shimniok 0:a6a169de725f 61 * @param z z position
shimniok 0:a6a169de725f 62 * @param yaw yaw orientation in radians, 0 = NORTH
shimniok 0:a6a169de725f 63 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:a6a169de725f 64 */
shimniok 0:a6a169de725f 65 static inline uint16_t mavlink_msg_position_control_setpoint_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
shimniok 0:a6a169de725f 66 {
shimniok 0:a6a169de725f 67 uint16_t i = 0;
shimniok 0:a6a169de725f 68 msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
shimniok 0:a6a169de725f 69
shimniok 0:a6a169de725f 70 i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
shimniok 0:a6a169de725f 71 i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
shimniok 0:a6a169de725f 72 i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
shimniok 0:a6a169de725f 73 i += put_float_by_index(x, i, msg->payload); // x position
shimniok 0:a6a169de725f 74 i += put_float_by_index(y, i, msg->payload); // y position
shimniok 0:a6a169de725f 75 i += put_float_by_index(z, i, msg->payload); // z position
shimniok 0:a6a169de725f 76 i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
shimniok 0:a6a169de725f 77
shimniok 0:a6a169de725f 78 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:a6a169de725f 79 }
shimniok 0:a6a169de725f 80
shimniok 0:a6a169de725f 81 /**
shimniok 0:a6a169de725f 82 * @brief Encode a position_control_setpoint_set struct into a message
shimniok 0:a6a169de725f 83 *
shimniok 0:a6a169de725f 84 * @param system_id ID of this system
shimniok 0:a6a169de725f 85 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:a6a169de725f 86 * @param msg The MAVLink message to compress the data into
shimniok 0:a6a169de725f 87 * @param position_control_setpoint_set C-struct to read the message contents from
shimniok 0:a6a169de725f 88 */
shimniok 0:a6a169de725f 89 static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
shimniok 0:a6a169de725f 90 {
shimniok 0:a6a169de725f 91 return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw);
shimniok 0:a6a169de725f 92 }
shimniok 0:a6a169de725f 93
shimniok 0:a6a169de725f 94 /**
shimniok 0:a6a169de725f 95 * @brief Send a position_control_setpoint_set message
shimniok 0:a6a169de725f 96 * @param chan MAVLink channel to send the message
shimniok 0:a6a169de725f 97 *
shimniok 0:a6a169de725f 98 * @param target_system System ID
shimniok 0:a6a169de725f 99 * @param target_component Component ID
shimniok 0:a6a169de725f 100 * @param id ID of waypoint, 0 for plain position
shimniok 0:a6a169de725f 101 * @param x x position
shimniok 0:a6a169de725f 102 * @param y y position
shimniok 0:a6a169de725f 103 * @param z z position
shimniok 0:a6a169de725f 104 * @param yaw yaw orientation in radians, 0 = NORTH
shimniok 0:a6a169de725f 105 */
shimniok 0:a6a169de725f 106 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:a6a169de725f 107
shimniok 0:a6a169de725f 108 static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
shimniok 0:a6a169de725f 109 {
shimniok 0:a6a169de725f 110 mavlink_message_t msg;
shimniok 0:a6a169de725f 111 mavlink_msg_position_control_setpoint_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target_system, target_component, id, x, y, z, yaw);
shimniok 0:a6a169de725f 112 mavlink_send_uart(chan, &msg);
shimniok 0:a6a169de725f 113 }
shimniok 0:a6a169de725f 114
shimniok 0:a6a169de725f 115 #endif
shimniok 0:a6a169de725f 116 // MESSAGE POSITION_CONTROL_SETPOINT_SET UNPACKING
shimniok 0:a6a169de725f 117
shimniok 0:a6a169de725f 118 /**
shimniok 0:a6a169de725f 119 * @brief Get field target_system from position_control_setpoint_set message
shimniok 0:a6a169de725f 120 *
shimniok 0:a6a169de725f 121 * @return System ID
shimniok 0:a6a169de725f 122 */
shimniok 0:a6a169de725f 123 static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_system(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 124 {
shimniok 0:a6a169de725f 125 return (uint8_t)(msg->payload)[0];
shimniok 0:a6a169de725f 126 }
shimniok 0:a6a169de725f 127
shimniok 0:a6a169de725f 128 /**
shimniok 0:a6a169de725f 129 * @brief Get field target_component from position_control_setpoint_set message
shimniok 0:a6a169de725f 130 *
shimniok 0:a6a169de725f 131 * @return Component ID
shimniok 0:a6a169de725f 132 */
shimniok 0:a6a169de725f 133 static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_component(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 134 {
shimniok 0:a6a169de725f 135 return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
shimniok 0:a6a169de725f 136 }
shimniok 0:a6a169de725f 137
shimniok 0:a6a169de725f 138 /**
shimniok 0:a6a169de725f 139 * @brief Get field id from position_control_setpoint_set message
shimniok 0:a6a169de725f 140 *
shimniok 0:a6a169de725f 141 * @return ID of waypoint, 0 for plain position
shimniok 0:a6a169de725f 142 */
shimniok 0:a6a169de725f 143 static inline uint16_t mavlink_msg_position_control_setpoint_set_get_id(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 144 {
shimniok 0:a6a169de725f 145 generic_16bit r;
shimniok 0:a6a169de725f 146 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
shimniok 0:a6a169de725f 147 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[1];
shimniok 0:a6a169de725f 148 return (uint16_t)r.s;
shimniok 0:a6a169de725f 149 }
shimniok 0:a6a169de725f 150
shimniok 0:a6a169de725f 151 /**
shimniok 0:a6a169de725f 152 * @brief Get field x from position_control_setpoint_set message
shimniok 0:a6a169de725f 153 *
shimniok 0:a6a169de725f 154 * @return x position
shimniok 0:a6a169de725f 155 */
shimniok 0:a6a169de725f 156 static inline float mavlink_msg_position_control_setpoint_set_get_x(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 157 {
shimniok 0:a6a169de725f 158 generic_32bit r;
shimniok 0:a6a169de725f 159 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
shimniok 0:a6a169de725f 160 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
shimniok 0:a6a169de725f 161 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[2];
shimniok 0:a6a169de725f 162 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[3];
shimniok 0:a6a169de725f 163 return (float)r.f;
shimniok 0:a6a169de725f 164 }
shimniok 0:a6a169de725f 165
shimniok 0:a6a169de725f 166 /**
shimniok 0:a6a169de725f 167 * @brief Get field y from position_control_setpoint_set message
shimniok 0:a6a169de725f 168 *
shimniok 0:a6a169de725f 169 * @return y position
shimniok 0:a6a169de725f 170 */
shimniok 0:a6a169de725f 171 static inline float mavlink_msg_position_control_setpoint_set_get_y(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 172 {
shimniok 0:a6a169de725f 173 generic_32bit r;
shimniok 0:a6a169de725f 174 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[0];
shimniok 0:a6a169de725f 175 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[1];
shimniok 0:a6a169de725f 176 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[2];
shimniok 0:a6a169de725f 177 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float))[3];
shimniok 0:a6a169de725f 178 return (float)r.f;
shimniok 0:a6a169de725f 179 }
shimniok 0:a6a169de725f 180
shimniok 0:a6a169de725f 181 /**
shimniok 0:a6a169de725f 182 * @brief Get field z from position_control_setpoint_set message
shimniok 0:a6a169de725f 183 *
shimniok 0:a6a169de725f 184 * @return z position
shimniok 0:a6a169de725f 185 */
shimniok 0:a6a169de725f 186 static inline float mavlink_msg_position_control_setpoint_set_get_z(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 187 {
shimniok 0:a6a169de725f 188 generic_32bit r;
shimniok 0:a6a169de725f 189 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
shimniok 0:a6a169de725f 190 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
shimniok 0:a6a169de725f 191 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
shimniok 0:a6a169de725f 192 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
shimniok 0:a6a169de725f 193 return (float)r.f;
shimniok 0:a6a169de725f 194 }
shimniok 0:a6a169de725f 195
shimniok 0:a6a169de725f 196 /**
shimniok 0:a6a169de725f 197 * @brief Get field yaw from position_control_setpoint_set message
shimniok 0:a6a169de725f 198 *
shimniok 0:a6a169de725f 199 * @return yaw orientation in radians, 0 = NORTH
shimniok 0:a6a169de725f 200 */
shimniok 0:a6a169de725f 201 static inline float mavlink_msg_position_control_setpoint_set_get_yaw(const mavlink_message_t* msg)
shimniok 0:a6a169de725f 202 {
shimniok 0:a6a169de725f 203 generic_32bit r;
shimniok 0:a6a169de725f 204 r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:a6a169de725f 205 r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:a6a169de725f 206 r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:a6a169de725f 207 r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:a6a169de725f 208 return (float)r.f;
shimniok 0:a6a169de725f 209 }
shimniok 0:a6a169de725f 210
shimniok 0:a6a169de725f 211 /**
shimniok 0:a6a169de725f 212 * @brief Decode a position_control_setpoint_set message into a struct
shimniok 0:a6a169de725f 213 *
shimniok 0:a6a169de725f 214 * @param msg The message to decode
shimniok 0:a6a169de725f 215 * @param position_control_setpoint_set C-struct to decode the message contents into
shimniok 0:a6a169de725f 216 */
shimniok 0:a6a169de725f 217 static inline void mavlink_msg_position_control_setpoint_set_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
shimniok 0:a6a169de725f 218 {
shimniok 0:a6a169de725f 219 position_control_setpoint_set->target_system = mavlink_msg_position_control_setpoint_set_get_target_system(msg);
shimniok 0:a6a169de725f 220 position_control_setpoint_set->target_component = mavlink_msg_position_control_setpoint_set_get_target_component(msg);
shimniok 0:a6a169de725f 221 position_control_setpoint_set->id = mavlink_msg_position_control_setpoint_set_get_id(msg);
shimniok 0:a6a169de725f 222 position_control_setpoint_set->x = mavlink_msg_position_control_setpoint_set_get_x(msg);
shimniok 0:a6a169de725f 223 position_control_setpoint_set->y = mavlink_msg_position_control_setpoint_set_get_y(msg);
shimniok 0:a6a169de725f 224 position_control_setpoint_set->z = mavlink_msg_position_control_setpoint_set_get_z(msg);
shimniok 0:a6a169de725f 225 position_control_setpoint_set->yaw = mavlink_msg_position_control_setpoint_set_get_yaw(msg);
shimniok 0:a6a169de725f 226 }