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