gps.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"
00018 // AND
00019 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00022 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00023 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00024 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00025 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00026 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00027 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 //==============================================================================
00029 
00030 #ifndef UBLOX_GPS_H
00031 #define UBLOX_GPS_H
00032 // STL
00033 #include <map>
00034 #include <vector>
00035 #include <locale>
00036 #include <stdexcept>
00037 // Boost
00038 #include <boost/asio/ip/tcp.hpp>
00039 #include <boost/asio/serial_port.hpp>
00040 #include <boost/asio/io_service.hpp>
00041 #include <boost/atomic.hpp>
00042 // ROS
00043 #include <ros/console.h>
00044 // Other u-blox packages
00045 #include <ublox/serialization/ublox_msgs.h>
00046 // u-blox gps
00047 #include <ublox_gps/async_worker.h>
00048 #include <ublox_gps/callback.h>
00049 
00055 namespace ublox_gps {
00057 const static unsigned int kBaudrates[] = { 4800, 
00058                                            9600, 
00059                                            19200, 
00060                                            38400, 
00061                                            57600, 
00062                                            115200, 
00063                                            230400, 
00064                                            460800 }; 
00068 class Gps {
00069  public:
00071   const static int kSetBaudrateSleepMs = 500; 
00073   const static double kDefaultAckTimeout = 1.0; 
00075   const static int kWriterSize = 1024; 
00076 
00077   Gps();
00078   virtual ~Gps();
00079 
00084   bool setSaveOnShutdown(bool save_on_shutdown) {
00085     save_on_shutdown_ = save_on_shutdown;
00086   }
00087 
00093   void initializeTcp(std::string host, std::string port);
00094   
00102   void initializeSerial(std::string port, unsigned int baudrate,
00103                         uint16_t uart_in, uint16_t uart_out);
00104 
00112   void resetSerial(std::string port);
00113 
00118   void close();
00119 
00124   void reset(const boost::posix_time::time_duration& wait);
00125 
00132   bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode);
00133 
00141   bool configGnss(ublox_msgs::CfgGNSS gnss, 
00142                   const boost::posix_time::time_duration& wait);
00143 
00149   bool clearBbr();
00150 
00158   bool configUart1(unsigned int baudrate, uint16_t in_proto_mask, 
00159                    uint16_t out_proto_mask);
00160 
00168   bool disableUart1(ublox_msgs::CfgPRT& prev_cfg);
00169 
00177   bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask,
00178                  uint16_t out_proto_mask);
00179 
00187   bool configRate(uint16_t meas_rate, uint16_t nav_rate);
00188 
00195   bool configRtcm(std::vector<uint8_t> ids, std::vector<uint8_t> rates);
00196 
00205   bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas);
00206 
00221   bool configTmode3Fixed(bool lla_flag,
00222                          std::vector<float> arp_position, 
00223                          std::vector<int8_t> arp_position_hp,
00224                          float fixed_pos_acc);
00225 
00232   bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit);
00233 
00239   bool disableTmode3();
00240 
00248   bool setRate(uint8_t class_id, uint8_t message_id, uint8_t rate);
00249 
00255   bool setDynamicModel(uint8_t model);
00256 
00262   bool setFixMode(uint8_t mode);
00263 
00269   bool setDeadReckonLimit(uint8_t limit);
00270 
00279   bool setPpp(bool enable);
00280 
00286   bool setDgnss(uint8_t mode);
00287 
00293   bool setUseAdr(bool enable);
00294 
00301   template <typename T>
00302   void subscribe(typename CallbackHandler_<T>::Callback callback,
00303                  unsigned int rate);
00308   template <typename T>
00309   void subscribe(typename CallbackHandler_<T>::Callback callback);
00310 
00318   template <typename T>
00319   void subscribeId(typename CallbackHandler_<T>::Callback callback,
00320                    unsigned int message_id);
00321 
00327   template <typename T>
00328   bool read(T& message,
00329             const boost::posix_time::time_duration& timeout = default_timeout_);
00330 
00331   bool isInitialized() const { return worker_ != 0; }
00332   bool isConfigured() const { return isInitialized() && configured_; }
00333   bool isOpen() const { return worker_->isOpen(); }
00334 
00342   template <typename ConfigT>
00343   bool poll(ConfigT& message,
00344             const std::vector<uint8_t>& payload = std::vector<uint8_t>(),
00345             const boost::posix_time::time_duration& timeout = default_timeout_);
00354   bool poll(uint8_t class_id, uint8_t message_id,
00355             const std::vector<uint8_t>& payload = std::vector<uint8_t>());
00356 
00364   template <typename ConfigT>
00365   bool configure(const ConfigT& message, bool wait = true);
00366 
00374   bool waitForAcknowledge(const boost::posix_time::time_duration& timeout, 
00375                           uint8_t class_id, uint8_t msg_id);
00376 
00377  private:
00379   enum AckType { 
00380     NACK, 
00381     ACK, 
00382     WAIT 
00383   }; 
00384   
00386   struct Ack {
00387     AckType type; 
00388     uint8_t class_id; 
00389     uint8_t msg_id; 
00390   };
00391 
00396   void setWorker(const boost::shared_ptr<Worker>& worker);
00397 
00401   void subscribeAcks();
00402 
00407   void processAck(const ublox_msgs::Ack &m);
00408   
00413   void processNack(const ublox_msgs::Ack &m);
00414 
00419   void processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m);
00420 
00431   bool saveOnShutdown();
00432 
00434   boost::shared_ptr<Worker> worker_;
00436   bool configured_; 
00438   bool save_on_shutdown_; 
00439 
00441   static boost::posix_time::time_duration default_timeout_;
00443   mutable boost::atomic<Ack> ack_; 
00444 
00446   CallbackHandlers callbacks_; 
00447 
00448   std::string host_, port_;
00449 };
00450 
00451 template <typename T>
00452 void Gps::subscribe(
00453     typename CallbackHandler_<T>::Callback callback, unsigned int rate) {
00454   if (!setRate(T::CLASS_ID, T::MESSAGE_ID, rate)) return;
00455   subscribe<T>(callback);
00456 }
00457 
00458 template <typename T>
00459 void Gps::subscribe(typename CallbackHandler_<T>::Callback callback) {
00460   callbacks_.insert<T>(callback);
00461 }
00462 
00463 template <typename T>
00464 void Gps::subscribeId(typename CallbackHandler_<T>::Callback callback, 
00465                       unsigned int message_id) {
00466   callbacks_.insert<T>(callback, message_id);
00467 }
00468 
00469 template <typename ConfigT>
00470 bool Gps::poll(ConfigT& message,
00471                const std::vector<uint8_t>& payload,
00472                const boost::posix_time::time_duration& timeout) {
00473   if (!poll(ConfigT::CLASS_ID, ConfigT::MESSAGE_ID, payload)) return false;
00474   return read(message, timeout);
00475 }
00476 
00477 template <typename T>
00478 bool Gps::read(T& message, const boost::posix_time::time_duration& timeout) {
00479   if (!worker_) return false;
00480   return callbacks_.read(message, timeout);
00481 }
00482 
00483 template <typename ConfigT>
00484 bool Gps::configure(const ConfigT& message, bool wait) {
00485   if (!worker_) return false;
00486 
00487   // Reset ack
00488   Ack ack;
00489   ack.type = WAIT;
00490   ack_.store(ack, boost::memory_order_seq_cst);
00491 
00492   // Encode the message
00493   std::vector<unsigned char> out(kWriterSize);
00494   ublox::Writer writer(out.data(), out.size());
00495   if (!writer.write(message)) {
00496     ROS_ERROR("Failed to encode config message 0x%02x / 0x%02x", 
00497               message.CLASS_ID, message.MESSAGE_ID);
00498     return false;
00499   }
00500   // Send the message to the device
00501   worker_->send(out.data(), writer.end() - out.data());
00502 
00503   if (!wait) return true;
00504 
00505   // Wait for an acknowledgment and return whether or not it was received
00506   return waitForAcknowledge(default_timeout_, 
00507                             message.CLASS_ID,
00508                             message.MESSAGE_ID);
00509 }
00510 
00511 }  // namespace ublox_gps
00512 
00513 #endif  // UBLOX_GPS_H


ublox_gps
Author(s): Johannes Meyer
autogenerated on Fri Aug 11 2017 02:31:06