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

mavlink_msg_gps_status.h

00001 // MESSAGE GPS_STATUS PACKING
00002 
00003 #define MAVLINK_MSG_ID_GPS_STATUS 27
00004 
00005 typedef struct __mavlink_gps_status_t 
00006 {
00007     uint8_t satellites_visible; ///< Number of satellites visible
00008     int8_t satellite_prn[20]; ///< Global satellite ID
00009     int8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization
00010     int8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
00011     int8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
00012     int8_t satellite_snr[20]; ///< Signal to noise ratio of satellite
00013 
00014 } mavlink_gps_status_t;
00015 
00016 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
00017 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
00018 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
00019 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
00020 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
00021 
00022 
00023 /**
00024  * @brief Pack a gps_status message
00025  * @param system_id ID of this system
00026  * @param component_id ID of this component (e.g. 200 for IMU)
00027  * @param msg The MAVLink message to compress the data into
00028  *
00029  * @param satellites_visible Number of satellites visible
00030  * @param satellite_prn Global satellite ID
00031  * @param satellite_used 0: Satellite not used, 1: used for localization
00032  * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
00033  * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
00034  * @param satellite_snr Signal to noise ratio of satellite
00035  * @return length of the message in bytes (excluding serial stream start sign)
00036  */
00037 static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
00038 {
00039     uint16_t i = 0;
00040     msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
00041 
00042     i += put_uint8_t_by_index(satellites_visible, i, msg->payload); // Number of satellites visible
00043     i += put_array_by_index(satellite_prn, 20, i, msg->payload); // Global satellite ID
00044     i += put_array_by_index(satellite_used, 20, i, msg->payload); // 0: Satellite not used, 1: used for localization
00045     i += put_array_by_index(satellite_elevation, 20, i, msg->payload); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
00046     i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); // Direction of satellite, 0: 0 deg, 255: 360 deg.
00047     i += put_array_by_index(satellite_snr, 20, i, msg->payload); // Signal to noise ratio of satellite
00048 
00049     return mavlink_finalize_message(msg, system_id, component_id, i);
00050 }
00051 
00052 /**
00053  * @brief Pack a gps_status message
00054  * @param system_id ID of this system
00055  * @param component_id ID of this component (e.g. 200 for IMU)
00056  * @param chan The MAVLink channel this message was sent over
00057  * @param msg The MAVLink message to compress the data into
00058  * @param satellites_visible Number of satellites visible
00059  * @param satellite_prn Global satellite ID
00060  * @param satellite_used 0: Satellite not used, 1: used for localization
00061  * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
00062  * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
00063  * @param satellite_snr Signal to noise ratio of satellite
00064  * @return length of the message in bytes (excluding serial stream start sign)
00065  */
00066 static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
00067 {
00068     uint16_t i = 0;
00069     msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
00070 
00071     i += put_uint8_t_by_index(satellites_visible, i, msg->payload); // Number of satellites visible
00072     i += put_array_by_index(satellite_prn, 20, i, msg->payload); // Global satellite ID
00073     i += put_array_by_index(satellite_used, 20, i, msg->payload); // 0: Satellite not used, 1: used for localization
00074     i += put_array_by_index(satellite_elevation, 20, i, msg->payload); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
00075     i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); // Direction of satellite, 0: 0 deg, 255: 360 deg.
00076     i += put_array_by_index(satellite_snr, 20, i, msg->payload); // Signal to noise ratio of satellite
00077 
00078     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00079 }
00080 
00081 /**
00082  * @brief Encode a gps_status 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_status C-struct to read the message contents from
00088  */
00089 static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
00090 {
00091     return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
00092 }
00093 
00094 /**
00095  * @brief Send a gps_status message
00096  * @param chan MAVLink channel to send the message
00097  *
00098  * @param satellites_visible Number of satellites visible
00099  * @param satellite_prn Global satellite ID
00100  * @param satellite_used 0: Satellite not used, 1: used for localization
00101  * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
00102  * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
00103  * @param satellite_snr Signal to noise ratio of satellite
00104  */
00105 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00106 
00107 static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
00108 {
00109     mavlink_message_t msg;
00110     mavlink_msg_gps_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr);
00111     mavlink_send_uart(chan, &msg);
00112 }
00113 
00114 #endif
00115 // MESSAGE GPS_STATUS UNPACKING
00116 
00117 /**
00118  * @brief Get field satellites_visible from gps_status message
00119  *
00120  * @return Number of satellites visible
00121  */
00122 static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
00123 {
00124     return (uint8_t)(msg->payload)[0];
00125 }
00126 
00127 /**
00128  * @brief Get field satellite_prn from gps_status message
00129  *
00130  * @return Global satellite ID
00131  */
00132 static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, int8_t* r_data)
00133 {
00134 
00135     memcpy(r_data, msg->payload+sizeof(uint8_t), 20);
00136     return 20;
00137 }
00138 
00139 /**
00140  * @brief Get field satellite_used from gps_status message
00141  *
00142  * @return 0: Satellite not used, 1: used for localization
00143  */
00144 static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, int8_t* r_data)
00145 {
00146 
00147     memcpy(r_data, msg->payload+sizeof(uint8_t)+20, 20);
00148     return 20;
00149 }
00150 
00151 /**
00152  * @brief Get field satellite_elevation from gps_status message
00153  *
00154  * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
00155  */
00156 static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, int8_t* r_data)
00157 {
00158 
00159     memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20, 20);
00160     return 20;
00161 }
00162 
00163 /**
00164  * @brief Get field satellite_azimuth from gps_status message
00165  *
00166  * @return Direction of satellite, 0: 0 deg, 255: 360 deg.
00167  */
00168 static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, int8_t* r_data)
00169 {
00170 
00171     memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20+20, 20);
00172     return 20;
00173 }
00174 
00175 /**
00176  * @brief Get field satellite_snr from gps_status message
00177  *
00178  * @return Signal to noise ratio of satellite
00179  */
00180 static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, int8_t* r_data)
00181 {
00182 
00183     memcpy(r_data, msg->payload+sizeof(uint8_t)+20+20+20+20, 20);
00184     return 20;
00185 }
00186 
00187 /**
00188  * @brief Decode a gps_status message into a struct
00189  *
00190  * @param msg The message to decode
00191  * @param gps_status C-struct to decode the message contents into
00192  */
00193 static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
00194 {
00195     gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
00196     mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
00197     mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used);
00198     mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation);
00199     mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
00200     mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
00201 }