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

mavlink_msg_optical_flow.h

00001 // MESSAGE OPTICAL_FLOW PACKING
00002 
00003 #define MAVLINK_MSG_ID_OPTICAL_FLOW 100
00004 
00005 typedef struct __mavlink_optical_flow_t 
00006 {
00007     uint64_t time; ///< Timestamp (UNIX)
00008     uint8_t sensor_id; ///< Sensor ID
00009     int16_t flow_x; ///< Flow in pixels in x-sensor direction
00010     int16_t flow_y; ///< Flow in pixels in y-sensor direction
00011     uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
00012     float ground_distance; ///< Ground distance in meters
00013 
00014 } mavlink_optical_flow_t;
00015 
00016 
00017 
00018 /**
00019  * @brief Pack a optical_flow 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 time Timestamp (UNIX)
00025  * @param sensor_id Sensor ID
00026  * @param flow_x Flow in pixels in x-sensor direction
00027  * @param flow_y Flow in pixels in y-sensor direction
00028  * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
00029  * @param ground_distance Ground distance in meters
00030  * @return length of the message in bytes (excluding serial stream start sign)
00031  */
00032 static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
00033 {
00034     uint16_t i = 0;
00035     msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
00036 
00037     i += put_uint64_t_by_index(time, i, msg->payload); // Timestamp (UNIX)
00038     i += put_uint8_t_by_index(sensor_id, i, msg->payload); // Sensor ID
00039     i += put_int16_t_by_index(flow_x, i, msg->payload); // Flow in pixels in x-sensor direction
00040     i += put_int16_t_by_index(flow_y, i, msg->payload); // Flow in pixels in y-sensor direction
00041     i += put_uint8_t_by_index(quality, i, msg->payload); // Optical flow quality / confidence. 0: bad, 255: maximum quality
00042     i += put_float_by_index(ground_distance, i, msg->payload); // Ground distance in meters
00043 
00044     return mavlink_finalize_message(msg, system_id, component_id, i);
00045 }
00046 
00047 /**
00048  * @brief Pack a optical_flow 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 time Timestamp (UNIX)
00054  * @param sensor_id Sensor ID
00055  * @param flow_x Flow in pixels in x-sensor direction
00056  * @param flow_y Flow in pixels in y-sensor direction
00057  * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
00058  * @param ground_distance Ground distance in meters
00059  * @return length of the message in bytes (excluding serial stream start sign)
00060  */
00061 static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
00062 {
00063     uint16_t i = 0;
00064     msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
00065 
00066     i += put_uint64_t_by_index(time, i, msg->payload); // Timestamp (UNIX)
00067     i += put_uint8_t_by_index(sensor_id, i, msg->payload); // Sensor ID
00068     i += put_int16_t_by_index(flow_x, i, msg->payload); // Flow in pixels in x-sensor direction
00069     i += put_int16_t_by_index(flow_y, i, msg->payload); // Flow in pixels in y-sensor direction
00070     i += put_uint8_t_by_index(quality, i, msg->payload); // Optical flow quality / confidence. 0: bad, 255: maximum quality
00071     i += put_float_by_index(ground_distance, i, msg->payload); // Ground distance in meters
00072 
00073     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00074 }
00075 
00076 /**
00077  * @brief Encode a optical_flow 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 optical_flow C-struct to read the message contents from
00083  */
00084 static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
00085 {
00086     return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->quality, optical_flow->ground_distance);
00087 }
00088 
00089 /**
00090  * @brief Send a optical_flow message
00091  * @param chan MAVLink channel to send the message
00092  *
00093  * @param time Timestamp (UNIX)
00094  * @param sensor_id Sensor ID
00095  * @param flow_x Flow in pixels in x-sensor direction
00096  * @param flow_y Flow in pixels in y-sensor direction
00097  * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
00098  * @param ground_distance Ground distance in meters
00099  */
00100 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00101 
00102 static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
00103 {
00104     mavlink_message_t msg;
00105     mavlink_msg_optical_flow_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, time, sensor_id, flow_x, flow_y, quality, ground_distance);
00106     mavlink_send_uart(chan, &msg);
00107 }
00108 
00109 #endif
00110 // MESSAGE OPTICAL_FLOW UNPACKING
00111 
00112 /**
00113  * @brief Get field time from optical_flow message
00114  *
00115  * @return Timestamp (UNIX)
00116  */
00117 static inline uint64_t mavlink_msg_optical_flow_get_time(const mavlink_message_t* msg)
00118 {
00119     generic_64bit r;
00120     r.b[7] = (msg->payload)[0];
00121     r.b[6] = (msg->payload)[1];
00122     r.b[5] = (msg->payload)[2];
00123     r.b[4] = (msg->payload)[3];
00124     r.b[3] = (msg->payload)[4];
00125     r.b[2] = (msg->payload)[5];
00126     r.b[1] = (msg->payload)[6];
00127     r.b[0] = (msg->payload)[7];
00128     return (uint64_t)r.ll;
00129 }
00130 
00131 /**
00132  * @brief Get field sensor_id from optical_flow message
00133  *
00134  * @return Sensor ID
00135  */
00136 static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg)
00137 {
00138     return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
00139 }
00140 
00141 /**
00142  * @brief Get field flow_x from optical_flow message
00143  *
00144  * @return Flow in pixels in x-sensor direction
00145  */
00146 static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg)
00147 {
00148     generic_16bit r;
00149     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
00150     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
00151     return (int16_t)r.s;
00152 }
00153 
00154 /**
00155  * @brief Get field flow_y from optical_flow message
00156  *
00157  * @return Flow in pixels in y-sensor direction
00158  */
00159 static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg)
00160 {
00161     generic_16bit r;
00162     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t))[0];
00163     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t))[1];
00164     return (int16_t)r.s;
00165 }
00166 
00167 /**
00168  * @brief Get field quality from optical_flow message
00169  *
00170  * @return Optical flow quality / confidence. 0: bad, 255: maximum quality
00171  */
00172 static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg)
00173 {
00174     return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t))[0];
00175 }
00176 
00177 /**
00178  * @brief Get field ground_distance from optical_flow message
00179  *
00180  * @return Ground distance in meters
00181  */
00182 static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg)
00183 {
00184     generic_32bit r;
00185     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint8_t))[0];
00186     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint8_t))[1];
00187     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint8_t))[2];
00188     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(uint8_t))[3];
00189     return (float)r.f;
00190 }
00191 
00192 /**
00193  * @brief Decode a optical_flow message into a struct
00194  *
00195  * @param msg The message to decode
00196  * @param optical_flow C-struct to decode the message contents into
00197  */
00198 static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow)
00199 {
00200     optical_flow->time = mavlink_msg_optical_flow_get_time(msg);
00201     optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg);
00202     optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg);
00203     optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg);
00204     optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg);
00205     optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg);
00206 }