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> 45 #include <ublox/serialization/ublox_msgs.h> 107 uint16_t uart_in, uint16_t uart_out);
128 void reset(
const boost::posix_time::time_duration& wait);
136 bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode);
146 const boost::posix_time::time_duration& wait);
162 bool configUart1(
unsigned int baudrate, uint16_t in_proto_mask,
163 uint16_t out_proto_mask);
181 bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask,
182 uint16_t out_proto_mask);
199 bool configRtcm(std::vector<uint8_t> ids, std::vector<uint8_t> rates);
226 std::vector<float> arp_position,
227 std::vector<int8_t> arp_position_hp,
228 float fixed_pos_acc);
252 bool setRate(uint8_t class_id, uint8_t message_id, uint8_t rate);
283 bool setPpp(
bool enable,
float protocol_version);
297 bool setUseAdr(
bool enable,
float protocol_version);
324 template <
typename T>
331 template <
typename T>
341 template <
typename T>
343 unsigned int message_id);
350 template <
typename T>
351 bool read(T& message,
365 template <
typename ConfigT>
366 bool poll(ConfigT& message,
367 const std::vector<uint8_t>& payload = std::vector<uint8_t>(),
377 bool poll(uint8_t class_id, uint8_t message_id,
378 const std::vector<uint8_t>& payload = std::vector<uint8_t>());
387 template <
typename ConfigT>
388 bool configure(
const ConfigT& message,
bool wait =
true);
398 uint8_t class_id, uint8_t msg_id);
475 mutable boost::atomic<Ack>
ack_;
483 template <
typename T>
486 if (!
setRate(T::CLASS_ID, T::MESSAGE_ID, rate))
return;
487 subscribe<T>(callback);
490 template <
typename T>
495 template <
typename T>
497 unsigned int message_id) {
501 template <
typename ConfigT>
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);
509 template <
typename T>
510 bool Gps::read(T& message,
const boost::posix_time::time_duration& timeout) {
515 template <
typename ConfigT>
522 ack_.store(ack, boost::memory_order_seq_cst);
527 if (!writer.write(message)) {
528 ROS_ERROR(
"Failed to encode config message 0x%02x / 0x%02x",
529 message.CLASS_ID, message.MESSAGE_ID);
533 worker_->send(out.data(), writer.end() - out.data());
535 if (!wait)
return true;
545 #endif // UBLOX_GPS_H bool isConfigured() const
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.
void close()
Closes the I/O port, and initiates save on shutdown procedure if enabled.
bool poll(ConfigT &message, const std::vector< uint8_t > &payload=std::vector< uint8_t >(), const boost::posix_time::time_duration &timeout=default_timeout_)
boost::atomic< Ack > ack_
Stores last received ACK accessed by multiple threads.
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.
bool save_on_shutdown_
Whether or not to save Flash BBR on shutdown.
void processNack(const ublox_msgs::Ack &m)
Callback handler for UBX-NACK message.
bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode)
Send a reset message to the u-blox device.
bool read(T &message, const boost::posix_time::time_duration &timeout=default_timeout_)
bool disableUart1(ublox_msgs::CfgPRT &prev_cfg)
Disable the UART Port. Sets in/out protocol masks to 0. Does not modify other values.
uint8_t class_id
The class ID of the ACK.
bool setUseAdr(bool enable, float protocol_version)
Enable or disable ADR (automotive dead reckoning).
bool setFixMode(uint8_t mode)
Set the device fix mode.
bool configRate(uint16_t meas_rate, uint16_t nav_rate)
Configure the device navigation and measurement rate settings.
bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas)
Configure the SBAS settings.
static constexpr unsigned int kBaudrates[]
Possible baudrates for u-blox devices.
void setWorker(const boost::shared_ptr< Worker > &worker)
Set the I/O worker.
bool setTimtm2(uint8_t rate)
Enable or disable TIM-TM2 (time mark message).
void insert(typename CallbackHandler_< T >::Callback callback)
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
Callback handlers for incoming u-blox messages.
Stores ACK/NACK messages.
bool disableTmode3()
Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices...
boost::function< void(unsigned char *, std::size_t &)> Callback
bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit)
Set the TMODE3 settings to survey-in.
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.
void reset(const boost::posix_time::time_duration &wait)
Reset I/O communications.
void initializeSerial(std::string port, unsigned int baudrate, uint16_t uart_in, uint16_t uart_out)
Initialize the Serial I/O port.
bool configUart1(unsigned int baudrate, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the UART1 Port.
bool configured_
Whether or not the I/O port has been configured.
bool config_on_startup_flag_
CallbackHandlers callbacks_
Callback handlers for u-blox messages.
uint8_t msg_id
The message ID of the ACK.
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.
boost::function< void(const T &)> Callback
A callback function.
void setRawDataCallback(const Worker::Callback &callback)
Set the callback function which handles raw data.
bool read(T &message, const boost::posix_time::time_duration &timeout)
Read a u-blox message of the given type.
AckType type
The ACK type.
bool setDgnss(uint8_t mode)
Set the DGNSS mode (see CfgDGNSS message for details).
void setConfigOnStartup(const bool config_on_startup)
Set the internal flag for enabling or disabling the initial configurations.
static constexpr double kDefaultAckTimeout
Default timeout for ACK messages in seconds.
bool setPpp(bool enable, float protocol_version)
Enable or disable PPP (precise-point-positioning).
bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the USB Port.
AckType
Types for ACK/NACK messages, WAIT is used when waiting for an ACK.
static constexpr int kWriterSize
Size of write buffer for output messages.
void resetSerial(std::string port)
Reset the Serial I/O port after u-blox reset.
void subscribeAcks()
Subscribe to ACK/NACK messages and UPD-SOS-ACK messages.
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
void processAck(const ublox_msgs::Ack &m)
Callback handler for UBX-ACK message.
bool setDeadReckonLimit(uint8_t limit)
Set the dead reckoning time limit.
void processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m)
Callback handler for UBX-UPD-SOS-ACK message.
void setSaveOnShutdown(bool save_on_shutdown)
If called, when the node shuts down, it will send a command to save the flash memory.
void subscribe(typename CallbackHandler_< T >::Callback callback, unsigned int rate)
Configure the U-Blox send rate of the message & subscribe to the given message.
bool isInitialized() const
Handles communication with and configuration of the u-blox device.
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 ...
static const boost::posix_time::time_duration default_timeout_
The default timeout for ACK messages.
boost::shared_ptr< Worker > worker_
Processes I/O stream data.
bool saveOnShutdown()
Execute save on shutdown procedure.
bool configRtcm(std::vector< uint8_t > ids, std::vector< uint8_t > rates)
Configure the RTCM messages with the given IDs to the set rate.
bool configure(const ConfigT &message, bool wait=true)
Send the given configuration message.
bool setDynamicModel(uint8_t model)
Set the device dynamic model.
bool clearBbr()
Send a message to the receiver to delete the BBR data stored in flash.
void initializeTcp(std::string host, std::string port)
Initialize TCP I/O.
bool setUTCtime()
Configure the U-Blox to UTC time.