Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
mavlink_msg_position_control_setpoint.h
00001 // MESSAGE POSITION_CONTROL_SETPOINT PACKING 00002 00003 #define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT 121 00004 00005 typedef struct __mavlink_position_control_setpoint_t 00006 { 00007 uint16_t id; ///< ID of waypoint, 0 for plain position 00008 float x; ///< x position 00009 float y; ///< y position 00010 float z; ///< z position 00011 float yaw; ///< yaw orientation in radians, 0 = NORTH 00012 00013 } mavlink_position_control_setpoint_t; 00014 00015 00016 00017 /** 00018 * @brief Pack a position_control_setpoint message 00019 * @param system_id ID of this system 00020 * @param component_id ID of this component (e.g. 200 for IMU) 00021 * @param msg The MAVLink message to compress the data into 00022 * 00023 * @param id ID of waypoint, 0 for plain position 00024 * @param x x position 00025 * @param y y position 00026 * @param z z position 00027 * @param yaw yaw orientation in radians, 0 = NORTH 00028 * @return length of the message in bytes (excluding serial stream start sign) 00029 */ 00030 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) 00031 { 00032 uint16_t i = 0; 00033 msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; 00034 00035 i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position 00036 i += put_float_by_index(x, i, msg->payload); // x position 00037 i += put_float_by_index(y, i, msg->payload); // y position 00038 i += put_float_by_index(z, i, msg->payload); // z position 00039 i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH 00040 00041 return mavlink_finalize_message(msg, system_id, component_id, i); 00042 } 00043 00044 /** 00045 * @brief Pack a position_control_setpoint message 00046 * @param system_id ID of this system 00047 * @param component_id ID of this component (e.g. 200 for IMU) 00048 * @param chan The MAVLink channel this message was sent over 00049 * @param msg The MAVLink message to compress the data into 00050 * @param id ID of waypoint, 0 for plain position 00051 * @param x x position 00052 * @param y y position 00053 * @param z z position 00054 * @param yaw yaw orientation in radians, 0 = NORTH 00055 * @return length of the message in bytes (excluding serial stream start sign) 00056 */ 00057 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) 00058 { 00059 uint16_t i = 0; 00060 msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; 00061 00062 i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position 00063 i += put_float_by_index(x, i, msg->payload); // x position 00064 i += put_float_by_index(y, i, msg->payload); // y position 00065 i += put_float_by_index(z, i, msg->payload); // z position 00066 i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH 00067 00068 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00069 } 00070 00071 /** 00072 * @brief Encode a position_control_setpoint struct into a message 00073 * 00074 * @param system_id ID of this system 00075 * @param component_id ID of this component (e.g. 200 for IMU) 00076 * @param msg The MAVLink message to compress the data into 00077 * @param position_control_setpoint C-struct to read the message contents from 00078 */ 00079 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) 00080 { 00081 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); 00082 } 00083 00084 /** 00085 * @brief Send a position_control_setpoint message 00086 * @param chan MAVLink channel to send the message 00087 * 00088 * @param id ID of waypoint, 0 for plain position 00089 * @param x x position 00090 * @param y y position 00091 * @param z z position 00092 * @param yaw yaw orientation in radians, 0 = NORTH 00093 */ 00094 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00095 00096 static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw) 00097 { 00098 mavlink_message_t msg; 00099 mavlink_msg_position_control_setpoint_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, yaw); 00100 mavlink_send_uart(chan, &msg); 00101 } 00102 00103 #endif 00104 // MESSAGE POSITION_CONTROL_SETPOINT UNPACKING 00105 00106 /** 00107 * @brief Get field id from position_control_setpoint message 00108 * 00109 * @return ID of waypoint, 0 for plain position 00110 */ 00111 static inline uint16_t mavlink_msg_position_control_setpoint_get_id(const mavlink_message_t* msg) 00112 { 00113 generic_16bit r; 00114 r.b[1] = (msg->payload)[0]; 00115 r.b[0] = (msg->payload)[1]; 00116 return (uint16_t)r.s; 00117 } 00118 00119 /** 00120 * @brief Get field x from position_control_setpoint message 00121 * 00122 * @return x position 00123 */ 00124 static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_message_t* msg) 00125 { 00126 generic_32bit r; 00127 r.b[3] = (msg->payload+sizeof(uint16_t))[0]; 00128 r.b[2] = (msg->payload+sizeof(uint16_t))[1]; 00129 r.b[1] = (msg->payload+sizeof(uint16_t))[2]; 00130 r.b[0] = (msg->payload+sizeof(uint16_t))[3]; 00131 return (float)r.f; 00132 } 00133 00134 /** 00135 * @brief Get field y from position_control_setpoint message 00136 * 00137 * @return y position 00138 */ 00139 static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_message_t* msg) 00140 { 00141 generic_32bit r; 00142 r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0]; 00143 r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1]; 00144 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2]; 00145 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3]; 00146 return (float)r.f; 00147 } 00148 00149 /** 00150 * @brief Get field z from position_control_setpoint message 00151 * 00152 * @return z position 00153 */ 00154 static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_message_t* msg) 00155 { 00156 generic_32bit r; 00157 r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0]; 00158 r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1]; 00159 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2]; 00160 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3]; 00161 return (float)r.f; 00162 } 00163 00164 /** 00165 * @brief Get field yaw from position_control_setpoint message 00166 * 00167 * @return yaw orientation in radians, 0 = NORTH 00168 */ 00169 static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_message_t* msg) 00170 { 00171 generic_32bit r; 00172 r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00173 r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00174 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00175 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00176 return (float)r.f; 00177 } 00178 00179 /** 00180 * @brief Decode a position_control_setpoint message into a struct 00181 * 00182 * @param msg The message to decode 00183 * @param position_control_setpoint C-struct to decode the message contents into 00184 */ 00185 static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint) 00186 { 00187 position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg); 00188 position_control_setpoint->x = mavlink_msg_position_control_setpoint_get_x(msg); 00189 position_control_setpoint->y = mavlink_msg_position_control_setpoint_get_y(msg); 00190 position_control_setpoint->z = mavlink_msg_position_control_setpoint_get_z(msg); 00191 position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg); 00192 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2