Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mavlink_msg_position_target.h Source File

mavlink_msg_position_target.h

00001 // MESSAGE POSITION_TARGET PACKING
00002 
00003 #define MAVLINK_MSG_ID_POSITION_TARGET 63
00004 
00005 typedef struct __mavlink_position_target_t 
00006 {
00007     float x; ///< x position
00008     float y; ///< y position
00009     float z; ///< z position
00010     float yaw; ///< yaw orientation in radians, 0 = NORTH
00011 
00012 } mavlink_position_target_t;
00013 
00014 
00015 
00016 /**
00017  * @brief Pack a position_target message
00018  * @param system_id ID of this system
00019  * @param component_id ID of this component (e.g. 200 for IMU)
00020  * @param msg The MAVLink message to compress the data into
00021  *
00022  * @param x x position
00023  * @param y y position
00024  * @param z z position
00025  * @param yaw yaw orientation in radians, 0 = NORTH
00026  * @return length of the message in bytes (excluding serial stream start sign)
00027  */
00028 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)
00029 {
00030     uint16_t i = 0;
00031     msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
00032 
00033     i += put_float_by_index(x, i, msg->payload); // x position
00034     i += put_float_by_index(y, i, msg->payload); // y position
00035     i += put_float_by_index(z, i, msg->payload); // z position
00036     i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
00037 
00038     return mavlink_finalize_message(msg, system_id, component_id, i);
00039 }
00040 
00041 /**
00042  * @brief Pack a position_target message
00043  * @param system_id ID of this system
00044  * @param component_id ID of this component (e.g. 200 for IMU)
00045  * @param chan The MAVLink channel this message was sent over
00046  * @param msg The MAVLink message to compress the data into
00047  * @param x x position
00048  * @param y y position
00049  * @param z z position
00050  * @param yaw yaw orientation in radians, 0 = NORTH
00051  * @return length of the message in bytes (excluding serial stream start sign)
00052  */
00053 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)
00054 {
00055     uint16_t i = 0;
00056     msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
00057 
00058     i += put_float_by_index(x, i, msg->payload); // x position
00059     i += put_float_by_index(y, i, msg->payload); // y position
00060     i += put_float_by_index(z, i, msg->payload); // z position
00061     i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
00062 
00063     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00064 }
00065 
00066 /**
00067  * @brief Encode a position_target struct into a message
00068  *
00069  * @param system_id ID of this system
00070  * @param component_id ID of this component (e.g. 200 for IMU)
00071  * @param msg The MAVLink message to compress the data into
00072  * @param position_target C-struct to read the message contents from
00073  */
00074 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)
00075 {
00076     return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw);
00077 }
00078 
00079 /**
00080  * @brief Send a position_target message
00081  * @param chan MAVLink channel to send the message
00082  *
00083  * @param x x position
00084  * @param y y position
00085  * @param z z position
00086  * @param yaw yaw orientation in radians, 0 = NORTH
00087  */
00088 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00089 
00090 static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
00091 {
00092     mavlink_message_t msg;
00093     mavlink_msg_position_target_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, x, y, z, yaw);
00094     mavlink_send_uart(chan, &msg);
00095 }
00096 
00097 #endif
00098 // MESSAGE POSITION_TARGET UNPACKING
00099 
00100 /**
00101  * @brief Get field x from position_target message
00102  *
00103  * @return x position
00104  */
00105 static inline float mavlink_msg_position_target_get_x(const mavlink_message_t* msg)
00106 {
00107     generic_32bit r;
00108     r.b[3] = (msg->payload)[0];
00109     r.b[2] = (msg->payload)[1];
00110     r.b[1] = (msg->payload)[2];
00111     r.b[0] = (msg->payload)[3];
00112     return (float)r.f;
00113 }
00114 
00115 /**
00116  * @brief Get field y from position_target message
00117  *
00118  * @return y position
00119  */
00120 static inline float mavlink_msg_position_target_get_y(const mavlink_message_t* msg)
00121 {
00122     generic_32bit r;
00123     r.b[3] = (msg->payload+sizeof(float))[0];
00124     r.b[2] = (msg->payload+sizeof(float))[1];
00125     r.b[1] = (msg->payload+sizeof(float))[2];
00126     r.b[0] = (msg->payload+sizeof(float))[3];
00127     return (float)r.f;
00128 }
00129 
00130 /**
00131  * @brief Get field z from position_target message
00132  *
00133  * @return z position
00134  */
00135 static inline float mavlink_msg_position_target_get_z(const mavlink_message_t* msg)
00136 {
00137     generic_32bit r;
00138     r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
00139     r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
00140     r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
00141     r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
00142     return (float)r.f;
00143 }
00144 
00145 /**
00146  * @brief Get field yaw from position_target message
00147  *
00148  * @return yaw orientation in radians, 0 = NORTH
00149  */
00150 static inline float mavlink_msg_position_target_get_yaw(const mavlink_message_t* msg)
00151 {
00152     generic_32bit r;
00153     r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
00154     r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
00155     r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
00156     r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
00157     return (float)r.f;
00158 }
00159 
00160 /**
00161  * @brief Decode a position_target message into a struct
00162  *
00163  * @param msg The message to decode
00164  * @param position_target C-struct to decode the message contents into
00165  */
00166 static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target)
00167 {
00168     position_target->x = mavlink_msg_position_target_get_x(msg);
00169     position_target->y = mavlink_msg_position_target_get_y(msg);
00170     position_target->z = mavlink_msg_position_target_get_z(msg);
00171     position_target->yaw = mavlink_msg_position_target_get_yaw(msg);
00172 }