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