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_vision_speed_estimate.h
00001 // MESSAGE VISION_SPEED_ESTIMATE PACKING 00002 00003 #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 113 00004 00005 typedef struct __mavlink_vision_speed_estimate_t 00006 { 00007 uint64_t usec; ///< Timestamp (milliseconds) 00008 float x; ///< Global X speed 00009 float y; ///< Global Y speed 00010 float z; ///< Global Z speed 00011 00012 } mavlink_vision_speed_estimate_t; 00013 00014 00015 00016 /** 00017 * @brief Pack a vision_speed_estimate 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 usec Timestamp (milliseconds) 00023 * @param x Global X speed 00024 * @param y Global Y speed 00025 * @param z Global Z speed 00026 * @return length of the message in bytes (excluding serial stream start sign) 00027 */ 00028 static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float x, float y, float z) 00029 { 00030 uint16_t i = 0; 00031 msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; 00032 00033 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds) 00034 i += put_float_by_index(x, i, msg->payload); // Global X speed 00035 i += put_float_by_index(y, i, msg->payload); // Global Y speed 00036 i += put_float_by_index(z, i, msg->payload); // Global Z speed 00037 00038 return mavlink_finalize_message(msg, system_id, component_id, i); 00039 } 00040 00041 /** 00042 * @brief Pack a vision_speed_estimate 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 usec Timestamp (milliseconds) 00048 * @param x Global X speed 00049 * @param y Global Y speed 00050 * @param z Global Z speed 00051 * @return length of the message in bytes (excluding serial stream start sign) 00052 */ 00053 static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z) 00054 { 00055 uint16_t i = 0; 00056 msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; 00057 00058 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds) 00059 i += put_float_by_index(x, i, msg->payload); // Global X speed 00060 i += put_float_by_index(y, i, msg->payload); // Global Y speed 00061 i += put_float_by_index(z, i, msg->payload); // Global Z speed 00062 00063 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00064 } 00065 00066 /** 00067 * @brief Encode a vision_speed_estimate 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 vision_speed_estimate C-struct to read the message contents from 00073 */ 00074 static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) 00075 { 00076 return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); 00077 } 00078 00079 /** 00080 * @brief Send a vision_speed_estimate message 00081 * @param chan MAVLink channel to send the message 00082 * 00083 * @param usec Timestamp (milliseconds) 00084 * @param x Global X speed 00085 * @param y Global Y speed 00086 * @param z Global Z speed 00087 */ 00088 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00089 00090 static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) 00091 { 00092 mavlink_message_t msg; 00093 mavlink_msg_vision_speed_estimate_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, x, y, z); 00094 mavlink_send_uart(chan, &msg); 00095 } 00096 00097 #endif 00098 // MESSAGE VISION_SPEED_ESTIMATE UNPACKING 00099 00100 /** 00101 * @brief Get field usec from vision_speed_estimate message 00102 * 00103 * @return Timestamp (milliseconds) 00104 */ 00105 static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) 00106 { 00107 generic_64bit r; 00108 r.b[7] = (msg->payload)[0]; 00109 r.b[6] = (msg->payload)[1]; 00110 r.b[5] = (msg->payload)[2]; 00111 r.b[4] = (msg->payload)[3]; 00112 r.b[3] = (msg->payload)[4]; 00113 r.b[2] = (msg->payload)[5]; 00114 r.b[1] = (msg->payload)[6]; 00115 r.b[0] = (msg->payload)[7]; 00116 return (uint64_t)r.ll; 00117 } 00118 00119 /** 00120 * @brief Get field x from vision_speed_estimate message 00121 * 00122 * @return Global X speed 00123 */ 00124 static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) 00125 { 00126 generic_32bit r; 00127 r.b[3] = (msg->payload+sizeof(uint64_t))[0]; 00128 r.b[2] = (msg->payload+sizeof(uint64_t))[1]; 00129 r.b[1] = (msg->payload+sizeof(uint64_t))[2]; 00130 r.b[0] = (msg->payload+sizeof(uint64_t))[3]; 00131 return (float)r.f; 00132 } 00133 00134 /** 00135 * @brief Get field y from vision_speed_estimate message 00136 * 00137 * @return Global Y speed 00138 */ 00139 static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) 00140 { 00141 generic_32bit r; 00142 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; 00143 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; 00144 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; 00145 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; 00146 return (float)r.f; 00147 } 00148 00149 /** 00150 * @brief Get field z from vision_speed_estimate message 00151 * 00152 * @return Global Z speed 00153 */ 00154 static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) 00155 { 00156 generic_32bit r; 00157 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; 00158 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; 00159 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; 00160 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; 00161 return (float)r.f; 00162 } 00163 00164 /** 00165 * @brief Decode a vision_speed_estimate message into a struct 00166 * 00167 * @param msg The message to decode 00168 * @param vision_speed_estimate C-struct to decode the message contents into 00169 */ 00170 static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) 00171 { 00172 vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); 00173 vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); 00174 vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); 00175 vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); 00176 }
Generated on Tue Jul 12 2022 14:09:27 by 1.7.2