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

mavlink_msg_position_control_setpoint_set.h

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