gps.h
Go to the documentation of this file.
1 //==============================================================================
2 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND
19 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
22 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
23 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
24 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
25 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
26 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
27 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 //==============================================================================
29 
30 #ifndef UBLOX_GPS_H
31 #define UBLOX_GPS_H
32 // STL
33 #include <map>
34 #include <vector>
35 #include <locale>
36 #include <stdexcept>
37 // Boost
38 #include <boost/asio/ip/tcp.hpp>
39 #include <boost/asio/serial_port.hpp>
40 #include <boost/asio/io_service.hpp>
41 #include <boost/atomic.hpp>
42 // ROS
43 #include <ros/console.h>
44 // Other u-blox packages
45 #include <ublox/serialization/ublox_msgs.h>
46 // u-blox gps
47 #include <ublox_gps/async_worker.h>
48 #include <ublox_gps/callback.h>
49 
55 namespace ublox_gps {
57 constexpr static unsigned int kBaudrates[] = { 4800,
58  9600,
59  19200,
60  38400,
61  57600,
62  115200,
63  230400,
64  460800 };
68 class Gps {
69  public:
71  constexpr static double kDefaultAckTimeout = 1.0;
73  constexpr static int kWriterSize = 2056;
74 
75  Gps();
76  virtual ~Gps();
77 
82  void setSaveOnShutdown(bool save_on_shutdown) {
83  save_on_shutdown_ = save_on_shutdown;
84  }
85 
90  void setConfigOnStartup(const bool config_on_startup) { config_on_startup_flag_ = config_on_startup; }
91 
97  void initializeTcp(std::string host, std::string port);
98 
106  void initializeSerial(std::string port, unsigned int baudrate,
107  uint16_t uart_in, uint16_t uart_out);
108 
116  void resetSerial(std::string port);
117 
122  void close();
123 
128  void reset(const boost::posix_time::time_duration& wait);
129 
136  bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode);
137 
145  bool configGnss(ublox_msgs::CfgGNSS gnss,
146  const boost::posix_time::time_duration& wait);
147 
153  bool clearBbr();
154 
162  bool configUart1(unsigned int baudrate, uint16_t in_proto_mask,
163  uint16_t out_proto_mask);
164 
172  bool disableUart1(ublox_msgs::CfgPRT& prev_cfg);
173 
181  bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask,
182  uint16_t out_proto_mask);
183 
191  bool configRate(uint16_t meas_rate, uint16_t nav_rate);
192 
199  bool configRtcm(std::vector<uint8_t> ids, std::vector<uint8_t> rates);
200 
209  bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas);
210 
225  bool configTmode3Fixed(bool lla_flag,
226  std::vector<float> arp_position,
227  std::vector<int8_t> arp_position_hp,
228  float fixed_pos_acc);
229 
236  bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit);
237 
243  bool disableTmode3();
244 
252  bool setRate(uint8_t class_id, uint8_t message_id, uint8_t rate);
253 
259  bool setDynamicModel(uint8_t model);
260 
266  bool setFixMode(uint8_t mode);
267 
273  bool setDeadReckonLimit(uint8_t limit);
274 
283  bool setPpp(bool enable, float protocol_version);
284 
290  bool setDgnss(uint8_t mode);
291 
297  bool setUseAdr(bool enable, float protocol_version);
298 
306  bool setUTCtime();
307 
316  bool setTimtm2(uint8_t rate);
317 
324  template <typename T>
325  void subscribe(typename CallbackHandler_<T>::Callback callback,
326  unsigned int rate);
331  template <typename T>
332  void subscribe(typename CallbackHandler_<T>::Callback callback);
333 
341  template <typename T>
342  void subscribeId(typename CallbackHandler_<T>::Callback callback,
343  unsigned int message_id);
344 
350  template <typename T>
351  bool read(T& message,
352  const boost::posix_time::time_duration& timeout = default_timeout_);
353 
354  bool isInitialized() const { return worker_ != 0; }
355  bool isConfigured() const { return isInitialized() && configured_; }
356  bool isOpen() const { return worker_->isOpen(); }
357 
365  template <typename ConfigT>
366  bool poll(ConfigT& message,
367  const std::vector<uint8_t>& payload = std::vector<uint8_t>(),
368  const boost::posix_time::time_duration& timeout = default_timeout_);
377  bool poll(uint8_t class_id, uint8_t message_id,
378  const std::vector<uint8_t>& payload = std::vector<uint8_t>());
379 
387  template <typename ConfigT>
388  bool configure(const ConfigT& message, bool wait = true);
389 
397  bool waitForAcknowledge(const boost::posix_time::time_duration& timeout,
398  uint8_t class_id, uint8_t msg_id);
399 
404  void setRawDataCallback(const Worker::Callback& callback);
405 
406  private:
408  enum AckType {
410  ACK,
412  };
413 
415  struct Ack {
417  uint8_t class_id;
418  uint8_t msg_id;
419  };
420 
425  void setWorker(const boost::shared_ptr<Worker>& worker);
426 
430  void subscribeAcks();
431 
436  void processAck(const ublox_msgs::Ack &m);
437 
442  void processNack(const ublox_msgs::Ack &m);
443 
448  void processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m);
449 
460  bool saveOnShutdown();
461 
470 
471 
473  static const boost::posix_time::time_duration default_timeout_;
475  mutable boost::atomic<Ack> ack_;
476 
479 
480  std::string host_, port_;
481 };
482 
483 template <typename T>
485  typename CallbackHandler_<T>::Callback callback, unsigned int rate) {
486  if (!setRate(T::CLASS_ID, T::MESSAGE_ID, rate)) return;
487  subscribe<T>(callback);
488 }
489 
490 template <typename T>
492  callbacks_.insert<T>(callback);
493 }
494 
495 template <typename T>
497  unsigned int message_id) {
498  callbacks_.insert<T>(callback, message_id);
499 }
500 
501 template <typename ConfigT>
502 bool Gps::poll(ConfigT& message,
503  const std::vector<uint8_t>& payload,
504  const boost::posix_time::time_duration& timeout) {
505  if (!poll(ConfigT::CLASS_ID, ConfigT::MESSAGE_ID, payload)) return false;
506  return read(message, timeout);
507 }
508 
509 template <typename T>
510 bool Gps::read(T& message, const boost::posix_time::time_duration& timeout) {
511  if (!worker_) return false;
512  return callbacks_.read(message, timeout);
513 }
514 
515 template <typename ConfigT>
516 bool Gps::configure(const ConfigT& message, bool wait) {
517  if (!worker_) return false;
518 
519  // Reset ack
520  Ack ack;
521  ack.type = WAIT;
522  ack_.store(ack, boost::memory_order_seq_cst);
523 
524  // Encode the message
525  std::vector<unsigned char> out(kWriterSize);
526  ublox::Writer writer(out.data(), out.size());
527  if (!writer.write(message)) {
528  ROS_ERROR("Failed to encode config message 0x%02x / 0x%02x",
529  message.CLASS_ID, message.MESSAGE_ID);
530  return false;
531  }
532  // Send the message to the device
533  worker_->send(out.data(), writer.end() - out.data());
534 
535  if (!wait) return true;
536 
537  // Wait for an acknowledgment and return whether or not it was received
539  message.CLASS_ID,
540  message.MESSAGE_ID);
541 }
542 
543 } // namespace ublox_gps
544 
545 #endif // UBLOX_GPS_H
bool isConfigured() const
Definition: gps.h:355
bool configGnss(ublox_msgs::CfgGNSS gnss, const boost::posix_time::time_duration &wait)
Configure the GNSS, cold reset the device, and reset the I/O.
Definition: gps.cpp:285
void close()
Closes the I/O port, and initiates save on shutdown procedure if enabled.
Definition: gps.cpp:249
bool poll(ConfigT &message, const std::vector< uint8_t > &payload=std::vector< uint8_t >(), const boost::posix_time::time_duration &timeout=default_timeout_)
Definition: gps.h:502
boost::atomic< Ack > ack_
Stores last received ACK accessed by multiple threads.
Definition: gps.h:475
bool configTmode3Fixed(bool lla_flag, std::vector< float > arp_position, std::vector< int8_t > arp_position_hp, float fixed_pos_acc)
Set the TMODE3 settings to fixed.
Definition: gps.cpp:413
bool save_on_shutdown_
Whether or not to save Flash BBR on shutdown.
Definition: gps.h:467
void processNack(const ublox_msgs::Ack &m)
Callback handler for UBX-NACK message.
Definition: gps.cpp:82
bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode)
Send a reset message to the u-blox device.
Definition: gps.cpp:271
bool read(T &message, const boost::posix_time::time_duration &timeout=default_timeout_)
Definition: gps.h:510
bool disableUart1(ublox_msgs::CfgPRT &prev_cfg)
Disable the UART Port. Sets in/out protocol masks to 0. Does not modify other values.
Definition: gps.cpp:339
uint8_t class_id
The class ID of the ACK.
Definition: gps.h:417
bool setUseAdr(bool enable, float protocol_version)
Enable or disable ADR (automotive dead reckoning).
Definition: gps.cpp:523
bool setFixMode(uint8_t mode)
Set the device fix mode.
Definition: gps.cpp:487
bool configRate(uint16_t meas_rate, uint16_t nav_rate)
Configure the device navigation and measurement rate settings.
Definition: gps.cpp:381
bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas)
Configure the SBAS settings.
Definition: gps.cpp:403
static constexpr unsigned int kBaudrates[]
Possible baudrates for u-blox devices.
Definition: gps.h:57
void setWorker(const boost::shared_ptr< Worker > &worker)
Set the I/O worker.
Definition: gps.cpp:50
bool setTimtm2(uint8_t rate)
Enable or disable TIM-TM2 (time mark message).
Definition: gps.cpp:582
void insert(typename CallbackHandler_< T >::Callback callback)
Definition: callback.h:129
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
Definition: node.h:120
Callback handlers for incoming u-blox messages.
Definition: callback.h:121
Stores ACK/NACK messages.
Definition: gps.h:415
bool disableTmode3()
Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices...
Definition: gps.cpp:460
boost::function< void(unsigned char *, std::size_t &)> Callback
Definition: worker.h:42
std::string host_
Definition: gps.h:480
bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit)
Set the TMODE3 settings to survey-in.
Definition: gps.cpp:449
bool waitForAcknowledge(const boost::posix_time::time_duration &timeout, uint8_t class_id, uint8_t msg_id)
Wait for an acknowledge message until the timeout.
Definition: gps.cpp:548
void reset(const boost::posix_time::time_duration &wait)
Reset I/O communications.
Definition: gps.cpp:260
void initializeSerial(std::string port, unsigned int baudrate, uint16_t uart_in, uint16_t uart_out)
Initialize the Serial I/O port.
Definition: gps.cpp:108
bool configUart1(unsigned int baudrate, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the UART1 Port.
Definition: gps.cpp:322
bool configured_
Whether or not the I/O port has been configured.
Definition: gps.h:465
bool config_on_startup_flag_
Definition: gps.h:469
bool isOpen() const
Definition: gps.h:356
std::string port_
Definition: gps.h:480
CallbackHandlers callbacks_
Callback handlers for u-blox messages.
Definition: gps.h:478
uint8_t msg_id
The message ID of the ACK.
Definition: gps.h:418
bool setRate(uint8_t class_id, uint8_t message_id, uint8_t rate)
Set the rate at which the U-Blox device sends the given message.
Definition: gps.cpp:468
boost::function< void(const T &)> Callback
A callback function.
Definition: callback.h:70
void setRawDataCallback(const Worker::Callback &callback)
Set the callback function which handles raw data.
Definition: gps.cpp:569
bool read(T &message, const boost::posix_time::time_duration &timeout)
Read a u-blox message of the given type.
Definition: callback.h:176
AckType type
The ACK type.
Definition: gps.h:416
bool setDgnss(uint8_t mode)
Set the DGNSS mode (see CfgDGNSS message for details).
Definition: gps.cpp:516
void setConfigOnStartup(const bool config_on_startup)
Set the internal flag for enabling or disabling the initial configurations.
Definition: gps.h:90
static constexpr double kDefaultAckTimeout
Default timeout for ACK messages in seconds.
Definition: gps.h:71
virtual ~Gps()
Definition: gps.cpp:48
bool setPpp(bool enable, float protocol_version)
Enable or disable PPP (precise-point-positioning).
Definition: gps.cpp:505
bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the USB Port.
Definition: gps.cpp:365
AckType
Types for ACK/NACK messages, WAIT is used when waiting for an ACK.
Definition: gps.h:408
static constexpr int kWriterSize
Size of write buffer for output messages.
Definition: gps.h:73
void resetSerial(std::string port)
Reset the Serial I/O port after u-blox reset.
Definition: gps.cpp:172
void subscribeAcks()
Subscribe to ACK/NACK messages and UPD-SOS-ACK messages.
Definition: gps.cpp:58
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
Definition: node.h:118
void processAck(const ublox_msgs::Ack &m)
Callback handler for UBX-ACK message.
Definition: gps.cpp:70
bool setDeadReckonLimit(uint8_t limit)
Set the dead reckoning time limit.
Definition: gps.cpp:496
void processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m)
Callback handler for UBX-UPD-SOS-ACK message.
Definition: gps.cpp:93
void setSaveOnShutdown(bool save_on_shutdown)
If called, when the node shuts down, it will send a command to save the flash memory.
Definition: gps.h:82
def usage(progname)
void subscribe(typename CallbackHandler_< T >::Callback callback, unsigned int rate)
Configure the U-Blox send rate of the message & subscribe to the given message.
Definition: gps.h:484
bool isInitialized() const
Definition: gps.h:354
Handles communication with and configuration of the u-blox device.
Definition: gps.h:68
void subscribeId(typename CallbackHandler_< T >::Callback callback, unsigned int message_id)
Subscribe to the message with the given ID. This is used for messages which have the same format but ...
Definition: gps.h:496
static const boost::posix_time::time_duration default_timeout_
The default timeout for ACK messages.
Definition: gps.h:473
boost::shared_ptr< Worker > worker_
Processes I/O stream data.
Definition: gps.h:463
#define ROS_ERROR(...)
bool saveOnShutdown()
Execute save on shutdown procedure.
Definition: gps.cpp:301
Not acknowledged.
Definition: gps.h:410
bool configRtcm(std::vector< uint8_t > ids, std::vector< uint8_t > rates)
Configure the RTCM messages with the given IDs to the set rate.
Definition: gps.cpp:392
bool configure(const ConfigT &message, bool wait=true)
Send the given configuration message.
Definition: gps.h:516
Acknowledge.
Definition: gps.h:411
bool setDynamicModel(uint8_t model)
Set the device dynamic model.
Definition: gps.cpp:478
bool clearBbr()
Send a message to the receiver to delete the BBR data stored in flash.
Definition: gps.cpp:314
void initializeTcp(std::string host, std::string port)
Initialize TCP I/O.
Definition: gps.cpp:213
bool setUTCtime()
Configure the U-Blox to UTC time.
Definition: gps.cpp:574


ublox_gps
Author(s): Johannes Meyer
autogenerated on Thu Jan 28 2021 03:13:52