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

mavlink_msg_set_cam_shutter.h

00001 // MESSAGE SET_CAM_SHUTTER PACKING
00002 
00003 #define MAVLINK_MSG_ID_SET_CAM_SHUTTER 190
00004 
00005 typedef struct __mavlink_set_cam_shutter_t 
00006 {
00007     uint8_t cam_no; ///< Camera id
00008     uint8_t cam_mode; ///< Camera mode: 0 = auto, 1 = manual
00009     uint8_t trigger_pin; ///< Trigger pin, 0-3 for PtGrey FireFly
00010     uint16_t interval; ///< Shutter interval, in microseconds
00011     uint16_t exposure; ///< Exposure time, in microseconds
00012     float gain; ///< Camera gain
00013 
00014 } mavlink_set_cam_shutter_t;
00015 
00016 
00017 
00018 /**
00019  * @brief Pack a set_cam_shutter 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 cam_no Camera id
00025  * @param cam_mode Camera mode: 0 = auto, 1 = manual
00026  * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
00027  * @param interval Shutter interval, in microseconds
00028  * @param exposure Exposure time, in microseconds
00029  * @param gain Camera gain
00030  * @return length of the message in bytes (excluding serial stream start sign)
00031  */
00032 static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
00033 {
00034     uint16_t i = 0;
00035     msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
00036 
00037     i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera id
00038     i += put_uint8_t_by_index(cam_mode, i, msg->payload); // Camera mode: 0 = auto, 1 = manual
00039     i += put_uint8_t_by_index(trigger_pin, i, msg->payload); // Trigger pin, 0-3 for PtGrey FireFly
00040     i += put_uint16_t_by_index(interval, i, msg->payload); // Shutter interval, in microseconds
00041     i += put_uint16_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
00042     i += put_float_by_index(gain, i, msg->payload); // Camera gain
00043 
00044     return mavlink_finalize_message(msg, system_id, component_id, i);
00045 }
00046 
00047 /**
00048  * @brief Pack a set_cam_shutter 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 cam_no Camera id
00054  * @param cam_mode Camera mode: 0 = auto, 1 = manual
00055  * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
00056  * @param interval Shutter interval, in microseconds
00057  * @param exposure Exposure time, in microseconds
00058  * @param gain Camera gain
00059  * @return length of the message in bytes (excluding serial stream start sign)
00060  */
00061 static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
00062 {
00063     uint16_t i = 0;
00064     msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
00065 
00066     i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera id
00067     i += put_uint8_t_by_index(cam_mode, i, msg->payload); // Camera mode: 0 = auto, 1 = manual
00068     i += put_uint8_t_by_index(trigger_pin, i, msg->payload); // Trigger pin, 0-3 for PtGrey FireFly
00069     i += put_uint16_t_by_index(interval, i, msg->payload); // Shutter interval, in microseconds
00070     i += put_uint16_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
00071     i += put_float_by_index(gain, i, msg->payload); // Camera gain
00072 
00073     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00074 }
00075 
00076 /**
00077  * @brief Encode a set_cam_shutter 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 set_cam_shutter C-struct to read the message contents from
00083  */
00084 static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter)
00085 {
00086     return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain);
00087 }
00088 
00089 /**
00090  * @brief Send a set_cam_shutter message
00091  * @param chan MAVLink channel to send the message
00092  *
00093  * @param cam_no Camera id
00094  * @param cam_mode Camera mode: 0 = auto, 1 = manual
00095  * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
00096  * @param interval Shutter interval, in microseconds
00097  * @param exposure Exposure time, in microseconds
00098  * @param gain Camera gain
00099  */
00100 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00101 
00102 static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
00103 {
00104     mavlink_message_t msg;
00105     mavlink_msg_set_cam_shutter_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_no, cam_mode, trigger_pin, interval, exposure, gain);
00106     mavlink_send_uart(chan, &msg);
00107 }
00108 
00109 #endif
00110 // MESSAGE SET_CAM_SHUTTER UNPACKING
00111 
00112 /**
00113  * @brief Get field cam_no from set_cam_shutter message
00114  *
00115  * @return Camera id
00116  */
00117 static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_message_t* msg)
00118 {
00119     return (uint8_t)(msg->payload)[0];
00120 }
00121 
00122 /**
00123  * @brief Get field cam_mode from set_cam_shutter message
00124  *
00125  * @return Camera mode: 0 = auto, 1 = manual
00126  */
00127 static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_message_t* msg)
00128 {
00129     return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
00130 }
00131 
00132 /**
00133  * @brief Get field trigger_pin from set_cam_shutter message
00134  *
00135  * @return Trigger pin, 0-3 for PtGrey FireFly
00136  */
00137 static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_message_t* msg)
00138 {
00139     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
00140 }
00141 
00142 /**
00143  * @brief Get field interval from set_cam_shutter message
00144  *
00145  * @return Shutter interval, in microseconds
00146  */
00147 static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(const mavlink_message_t* msg)
00148 {
00149     generic_16bit r;
00150     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00151     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
00152     return (uint16_t)r.s;
00153 }
00154 
00155 /**
00156  * @brief Get field exposure from set_cam_shutter message
00157  *
00158  * @return Exposure time, in microseconds
00159  */
00160 static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_message_t* msg)
00161 {
00162     generic_16bit r;
00163     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
00164     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[1];
00165     return (uint16_t)r.s;
00166 }
00167 
00168 /**
00169  * @brief Get field gain from set_cam_shutter message
00170  *
00171  * @return Camera gain
00172  */
00173 static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t* msg)
00174 {
00175     generic_32bit r;
00176     r.b[3] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
00177     r.b[2] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
00178     r.b[1] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[2];
00179     r.b[0] = (msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[3];
00180     return (float)r.f;
00181 }
00182 
00183 /**
00184  * @brief Decode a set_cam_shutter message into a struct
00185  *
00186  * @param msg The message to decode
00187  * @param set_cam_shutter C-struct to decode the message contents into
00188  */
00189 static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter)
00190 {
00191     set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg);
00192     set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg);
00193     set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg);
00194     set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg);
00195     set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg);
00196     set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg);
00197 }