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