ublox_msgs.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef UBLOX_MSGS_H
00030 #define UBLOX_MSGS_H
00031 
00032 #include <ublox_msgs/NavCLOCK.h>
00033 #include <ublox_msgs/NavDGPS.h>
00034 #include <ublox_msgs/NavDOP.h>
00035 #include <ublox_msgs/NavPOSECEF.h>
00036 #include <ublox_msgs/NavPOSLLH.h>
00037 #include <ublox_msgs/NavSBAS.h>
00038 #include <ublox_msgs/NavSOL.h>
00039 #include <ublox_msgs/NavSTATUS.h>
00040 #include <ublox_msgs/NavSVINFO.h>
00041 #include <ublox_msgs/NavTIMEGPS.h>
00042 #include <ublox_msgs/NavTIMEUTC.h>
00043 #include <ublox_msgs/NavVELECEF.h>
00044 #include <ublox_msgs/NavVELNED.h>
00045 
00046 #include <ublox_msgs/RxmALM.h>
00047 #include <ublox_msgs/RxmEPH.h>
00048 #include <ublox_msgs/RxmRAW.h>
00049 #include <ublox_msgs/RxmRAW_SV.h>
00050 #include <ublox_msgs/RxmSFRB.h>
00051 #include <ublox_msgs/RxmSVSI.h>
00052 
00053 #include <ublox_msgs/AidALM.h>
00054 #include <ublox_msgs/AidEPH.h>
00055 #include <ublox_msgs/AidHUI.h>
00056 
00057 #include <ublox_msgs/CfgANT.h>
00058 #include <ublox_msgs/CfgCFG.h>
00059 #include <ublox_msgs/CfgMSG.h>
00060 #include <ublox_msgs/CfgNAV5.h>
00061 #include <ublox_msgs/CfgPRT.h>
00062 #include <ublox_msgs/CfgRATE.h>
00063 #include <ublox_msgs/CfgSBAS.h>
00064 
00065 namespace ublox_msgs {
00066 
00067 namespace Class {
00068   static const uint8_t NAV = 0x01; // Navigation Results: Position, Speed, Time, Acc, Heading, DOP, SVs used
00069   static const uint8_t RXM = 0x02; // Receiver Manager Messages: Satellite Status, RTC Status
00070   static const uint8_t INF = 0x04; // Information Messages: Printf-Style Messages, with IDs such as Error, Warning, Notice
00071   static const uint8_t ACK = 0x05; // Ack/Nack Messages: as replies to CFG Input Messages
00072   static const uint8_t CFG = 0x06; // Configuration Input Messages: Set Dynamic Model, Set DOP Mask, Set Baud Rate, etc.
00073   static const uint8_t MON = 0x0A; // Monitoring Messages: Comunication Status, CPU Load, Stack Usage, Task Status
00074   static const uint8_t AID = 0x0B; // AssistNow Aiding Messages: Ephemeris, Almanac, other A-GPS data input
00075   static const uint8_t TIM = 0x0D; // Timing Messages: Timepulse Output, Timemark Results
00076   static const uint8_t ESF = 0x10; // External Sensor Fusion Messages: External sensor measurements and status information
00077 }
00078 
00079 namespace Message {
00080   namespace NAV {
00081     static const uint8_t CLOCK = NavCLOCK::MESSAGE_ID;
00082     static const uint8_t DGPS = NavDGPS::MESSAGE_ID;
00083     static const uint8_t DOP = NavDOP::MESSAGE_ID;
00084     static const uint8_t POSECEF = NavPOSECEF::MESSAGE_ID;
00085     static const uint8_t POSLLH = NavPOSLLH::MESSAGE_ID;
00086     static const uint8_t SBAS = NavSBAS::MESSAGE_ID;
00087     static const uint8_t SOL = NavSOL::MESSAGE_ID;
00088     static const uint8_t STATUS = NavSTATUS::MESSAGE_ID;
00089     static const uint8_t SVINFO = NavSVINFO::MESSAGE_ID;
00090     static const uint8_t TIMEGPS = NavTIMEGPS::MESSAGE_ID;
00091     static const uint8_t TIMEUTC = NavTIMEUTC::MESSAGE_ID;
00092     static const uint8_t VELECEF = NavVELECEF::MESSAGE_ID;
00093     static const uint8_t VELNED = NavVELNED::MESSAGE_ID;
00094   }
00095 
00096   namespace RXM {
00097     static const uint8_t ALM = RxmALM::MESSAGE_ID;
00098     static const uint8_t EPH = RxmEPH::MESSAGE_ID;
00099     static const uint8_t RAW = RxmRAW::MESSAGE_ID;
00100     static const uint8_t SFRB = RxmSFRB::MESSAGE_ID;
00101     static const uint8_t SVSI = RxmSVSI::MESSAGE_ID;
00102   }
00103 
00104   namespace AID {
00105     static const uint8_t ALM = AidALM::MESSAGE_ID;
00106     static const uint8_t EPH = AidEPH::MESSAGE_ID;
00107     static const uint8_t HUI = AidHUI::MESSAGE_ID;
00108   }
00109 
00110   namespace CFG {
00111     static const uint8_t ANT  = CfgANT::MESSAGE_ID;
00112     static const uint8_t CFG  = CfgCFG::MESSAGE_ID;
00113     static const uint8_t MSG  = CfgMSG::MESSAGE_ID;
00114     static const uint8_t NAV5 = CfgNAV5::MESSAGE_ID;
00115     static const uint8_t PRT  = CfgPRT::MESSAGE_ID;
00116     static const uint8_t RATE = CfgRATE::MESSAGE_ID;
00117     static const uint8_t SBAS = CfgSBAS::MESSAGE_ID;
00118   }
00119 }
00120 
00121 } // namespace ublox_msgs
00122 
00123 #endif // UBLOX_MSGS_H


ublox_msgs
Author(s): Johannes Meyer
autogenerated on Wed Aug 26 2015 16:35:58