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

mavlink_msg_gps_date_time.h

00001 // MESSAGE GPS_DATE_TIME PACKING
00002 
00003 #define MAVLINK_MSG_ID_GPS_DATE_TIME 179
00004 
00005 typedef struct __mavlink_gps_date_time_t 
00006 {
00007     uint8_t year; ///< Year reported by Gps 
00008     uint8_t month; ///< Month reported by Gps 
00009     uint8_t day; ///< Day reported by Gps 
00010     uint8_t hour; ///< Hour reported by Gps 
00011     uint8_t min; ///< Min reported by Gps 
00012     uint8_t sec; ///< Sec reported by Gps  
00013     uint8_t visSat; ///< Visible sattelites reported by Gps  
00014 
00015 } mavlink_gps_date_time_t;
00016 
00017 
00018 
00019 /**
00020  * @brief Pack a gps_date_time 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 year Year reported by Gps 
00026  * @param month Month reported by Gps 
00027  * @param day Day reported by Gps 
00028  * @param hour Hour reported by Gps 
00029  * @param min Min reported by Gps 
00030  * @param sec Sec reported by Gps  
00031  * @param visSat Visible sattelites reported by Gps  
00032  * @return length of the message in bytes (excluding serial stream start sign)
00033  */
00034 static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
00035 {
00036     uint16_t i = 0;
00037     msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME;
00038 
00039     i += put_uint8_t_by_index(year, i, msg->payload); // Year reported by Gps 
00040     i += put_uint8_t_by_index(month, i, msg->payload); // Month reported by Gps 
00041     i += put_uint8_t_by_index(day, i, msg->payload); // Day reported by Gps 
00042     i += put_uint8_t_by_index(hour, i, msg->payload); // Hour reported by Gps 
00043     i += put_uint8_t_by_index(min, i, msg->payload); // Min reported by Gps 
00044     i += put_uint8_t_by_index(sec, i, msg->payload); // Sec reported by Gps  
00045     i += put_uint8_t_by_index(visSat, i, msg->payload); // Visible sattelites reported by Gps  
00046 
00047     return mavlink_finalize_message(msg, system_id, component_id, i);
00048 }
00049 
00050 /**
00051  * @brief Pack a gps_date_time 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 year Year reported by Gps 
00057  * @param month Month reported by Gps 
00058  * @param day Day reported by Gps 
00059  * @param hour Hour reported by Gps 
00060  * @param min Min reported by Gps 
00061  * @param sec Sec reported by Gps  
00062  * @param visSat Visible sattelites reported by Gps  
00063  * @return length of the message in bytes (excluding serial stream start sign)
00064  */
00065 static inline uint16_t mavlink_msg_gps_date_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
00066 {
00067     uint16_t i = 0;
00068     msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME;
00069 
00070     i += put_uint8_t_by_index(year, i, msg->payload); // Year reported by Gps 
00071     i += put_uint8_t_by_index(month, i, msg->payload); // Month reported by Gps 
00072     i += put_uint8_t_by_index(day, i, msg->payload); // Day reported by Gps 
00073     i += put_uint8_t_by_index(hour, i, msg->payload); // Hour reported by Gps 
00074     i += put_uint8_t_by_index(min, i, msg->payload); // Min reported by Gps 
00075     i += put_uint8_t_by_index(sec, i, msg->payload); // Sec reported by Gps  
00076     i += put_uint8_t_by_index(visSat, i, msg->payload); // Visible sattelites reported by Gps  
00077 
00078     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00079 }
00080 
00081 /**
00082  * @brief Encode a gps_date_time 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 gps_date_time C-struct to read the message contents from
00088  */
00089 static inline uint16_t mavlink_msg_gps_date_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_date_time_t* gps_date_time)
00090 {
00091     return mavlink_msg_gps_date_time_pack(system_id, component_id, msg, gps_date_time->year, gps_date_time->month, gps_date_time->day, gps_date_time->hour, gps_date_time->min, gps_date_time->sec, gps_date_time->visSat);
00092 }
00093 
00094 /**
00095  * @brief Send a gps_date_time message
00096  * @param chan MAVLink channel to send the message
00097  *
00098  * @param year Year reported by Gps 
00099  * @param month Month reported by Gps 
00100  * @param day Day reported by Gps 
00101  * @param hour Hour reported by Gps 
00102  * @param min Min reported by Gps 
00103  * @param sec Sec reported by Gps  
00104  * @param visSat Visible sattelites reported by Gps  
00105  */
00106 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00107 
00108 static inline void mavlink_msg_gps_date_time_send(mavlink_channel_t chan, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat)
00109 {
00110     mavlink_message_t msg;
00111     mavlink_msg_gps_date_time_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, year, month, day, hour, min, sec, visSat);
00112     mavlink_send_uart(chan, &msg);
00113 }
00114 
00115 #endif
00116 // MESSAGE GPS_DATE_TIME UNPACKING
00117 
00118 /**
00119  * @brief Get field year from gps_date_time message
00120  *
00121  * @return Year reported by Gps 
00122  */
00123 static inline uint8_t mavlink_msg_gps_date_time_get_year(const mavlink_message_t* msg)
00124 {
00125     return (uint8_t)(msg->payload)[0];
00126 }
00127 
00128 /**
00129  * @brief Get field month from gps_date_time message
00130  *
00131  * @return Month reported by Gps 
00132  */
00133 static inline uint8_t mavlink_msg_gps_date_time_get_month(const mavlink_message_t* msg)
00134 {
00135     return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
00136 }
00137 
00138 /**
00139  * @brief Get field day from gps_date_time message
00140  *
00141  * @return Day reported by Gps 
00142  */
00143 static inline uint8_t mavlink_msg_gps_date_time_get_day(const mavlink_message_t* msg)
00144 {
00145     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
00146 }
00147 
00148 /**
00149  * @brief Get field hour from gps_date_time message
00150  *
00151  * @return Hour reported by Gps 
00152  */
00153 static inline uint8_t mavlink_msg_gps_date_time_get_hour(const mavlink_message_t* msg)
00154 {
00155     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00156 }
00157 
00158 /**
00159  * @brief Get field min from gps_date_time message
00160  *
00161  * @return Min reported by Gps 
00162  */
00163 static inline uint8_t mavlink_msg_gps_date_time_get_min(const mavlink_message_t* msg)
00164 {
00165     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00166 }
00167 
00168 /**
00169  * @brief Get field sec from gps_date_time message
00170  *
00171  * @return Sec reported by Gps  
00172  */
00173 static inline uint8_t mavlink_msg_gps_date_time_get_sec(const mavlink_message_t* msg)
00174 {
00175     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00176 }
00177 
00178 /**
00179  * @brief Get field visSat from gps_date_time message
00180  *
00181  * @return Visible sattelites reported by Gps  
00182  */
00183 static inline uint8_t mavlink_msg_gps_date_time_get_visSat(const mavlink_message_t* msg)
00184 {
00185     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00186 }
00187 
00188 /**
00189  * @brief Decode a gps_date_time message into a struct
00190  *
00191  * @param msg The message to decode
00192  * @param gps_date_time C-struct to decode the message contents into
00193  */
00194 static inline void mavlink_msg_gps_date_time_decode(const mavlink_message_t* msg, mavlink_gps_date_time_t* gps_date_time)
00195 {
00196     gps_date_time->year = mavlink_msg_gps_date_time_get_year(msg);
00197     gps_date_time->month = mavlink_msg_gps_date_time_get_month(msg);
00198     gps_date_time->day = mavlink_msg_gps_date_time_get_day(msg);
00199     gps_date_time->hour = mavlink_msg_gps_date_time_get_hour(msg);
00200     gps_date_time->min = mavlink_msg_gps_date_time_get_min(msg);
00201     gps_date_time->sec = mavlink_msg_gps_date_time_get_sec(msg);
00202     gps_date_time->visSat = mavlink_msg_gps_date_time_get_visSat(msg);
00203 }