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_control_offset_set.h Source File

mavlink_msg_position_control_offset_set.h

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