Classes | Public Member Functions | Static Public Attributes | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
ublox_gps::Gps Class Reference

Handles communication with and configuration of the u-blox device. More...

#include <gps.h>

Classes

struct  Ack
 Stores ACK/NACK messages. More...
 

Public Member Functions

bool clearBbr ()
 Send a message to the receiver to delete the BBR data stored in flash. More...
 
void close ()
 Closes the I/O port, and initiates save on shutdown procedure if enabled. More...
 
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. More...
 
bool configRate (uint16_t meas_rate, uint16_t nav_rate)
 Configure the device navigation and measurement rate settings. More...
 
bool configReset (uint16_t nav_bbr_mask, uint16_t reset_mode)
 Send a reset message to the u-blox device. More...
 
bool configRtcm (std::vector< uint8_t > ids, std::vector< uint8_t > rates)
 Configure the RTCM messages with the given IDs to the set rate. More...
 
bool configSbas (bool enable, uint8_t usage, uint8_t max_sbas)
 Configure the SBAS settings. More...
 
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. More...
 
bool configTmode3SurveyIn (unsigned int svin_min_dur, float svin_acc_limit)
 Set the TMODE3 settings to survey-in. More...
 
bool configUart1 (unsigned int baudrate, uint16_t in_proto_mask, uint16_t out_proto_mask)
 Configure the UART1 Port. More...
 
template<typename ConfigT >
bool configure (const ConfigT &message, bool wait=true)
 Send the given configuration message. More...
 
bool configUsb (uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask)
 Configure the USB Port. More...
 
bool disableTmode3 ()
 Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices, otherwise the device will return a NACK. More...
 
bool disableUart1 (ublox_msgs::CfgPRT &prev_cfg)
 Disable the UART Port. Sets in/out protocol masks to 0. Does not modify other values. More...
 
 Gps ()
 
void initializeSerial (std::string port, unsigned int baudrate, uint16_t uart_in, uint16_t uart_out)
 Initialize the Serial I/O port. More...
 
void initializeTcp (std::string host, std::string port)
 Initialize TCP I/O. More...
 
bool isConfigured () const
 
bool isInitialized () const
 
bool isOpen () const
 
template<typename ConfigT >
bool poll (ConfigT &message, const std::vector< uint8_t > &payload=std::vector< uint8_t >(), const boost::posix_time::time_duration &timeout=default_timeout_)
 
bool poll (uint8_t class_id, uint8_t message_id, const std::vector< uint8_t > &payload=std::vector< uint8_t >())
 
template<typename T >
bool read (T &message, const boost::posix_time::time_duration &timeout=default_timeout_)
 
void reset (const boost::posix_time::time_duration &wait)
 Reset I/O communications. More...
 
void resetSerial (std::string port)
 Reset the Serial I/O port after u-blox reset. More...
 
void setConfigOnStartup (const bool config_on_startup)
 Set the internal flag for enabling or disabling the initial configurations. More...
 
bool setDeadReckonLimit (uint8_t limit)
 Set the dead reckoning time limit. More...
 
bool setDgnss (uint8_t mode)
 Set the DGNSS mode (see CfgDGNSS message for details). More...
 
bool setDynamicModel (uint8_t model)
 Set the device dynamic model. More...
 
bool setFixMode (uint8_t mode)
 Set the device fix mode. More...
 
bool setPpp (bool enable, float protocol_version)
 Enable or disable PPP (precise-point-positioning). More...
 
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. More...
 
void setRawDataCallback (const Worker::Callback &callback)
 Set the callback function which handles raw data. More...
 
void setSaveOnShutdown (bool save_on_shutdown)
 If called, when the node shuts down, it will send a command to save the flash memory. More...
 
bool setTimtm2 (uint8_t rate)
 Enable or disable TIM-TM2 (time mark message). More...
 
bool setUseAdr (bool enable, float protocol_version)
 Enable or disable ADR (automotive dead reckoning). More...
 
bool setUTCtime ()
 Configure the U-Blox to UTC time. More...
 
template<typename T >
void subscribe (typename CallbackHandler_< T >::Callback callback, unsigned int rate)
 Configure the U-Blox send rate of the message & subscribe to the given message. More...
 
template<typename T >
void subscribe (typename CallbackHandler_< T >::Callback callback)
 Subscribe to the given Ublox message. More...
 
template<typename T >
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 different message IDs, e.g. INF messages. More...
 
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. More...
 
virtual ~Gps ()
 

Static Public Attributes

static constexpr double kDefaultAckTimeout = 1.0
 Default timeout for ACK messages in seconds. More...
 
static constexpr int kWriterSize = 2056
 Size of write buffer for output messages. More...
 

Private Types

enum  AckType { NACK, ACK, WAIT }
 Types for ACK/NACK messages, WAIT is used when waiting for an ACK. More...
 

Private Member Functions

void processAck (const ublox_msgs::Ack &m)
 Callback handler for UBX-ACK message. More...
 
void processNack (const ublox_msgs::Ack &m)
 Callback handler for UBX-NACK message. More...
 
void processUpdSosAck (const ublox_msgs::UpdSOS_Ack &m)
 Callback handler for UBX-UPD-SOS-ACK message. More...
 
bool saveOnShutdown ()
 Execute save on shutdown procedure. More...
 
void setWorker (const boost::shared_ptr< Worker > &worker)
 Set the I/O worker. More...
 
void subscribeAcks ()
 Subscribe to ACK/NACK messages and UPD-SOS-ACK messages. More...
 

Private Attributes

boost::atomic< Ackack_
 Stores last received ACK accessed by multiple threads. More...
 
CallbackHandlers callbacks_
 Callback handlers for u-blox messages. More...
 
bool config_on_startup_flag_
 
bool configured_
 Whether or not the I/O port has been configured. More...
 
std::string host_
 
std::string port_
 
bool save_on_shutdown_
 Whether or not to save Flash BBR on shutdown. More...
 
boost::shared_ptr< Workerworker_
 Processes I/O stream data. More...
 

Static Private Attributes

static const boost::posix_time::time_duration default_timeout_
 The default timeout for ACK messages. More...
 

Detailed Description

Handles communication with and configuration of the u-blox device.

Definition at line 68 of file gps.h.

Member Enumeration Documentation

Types for ACK/NACK messages, WAIT is used when waiting for an ACK.

Enumerator
NACK 
ACK 

Not acknowledged.

WAIT 

Acknowledge.

Waiting for ACK

Definition at line 408 of file gps.h.

Constructor & Destructor Documentation

ublox_gps::Gps::Gps ( )

Definition at line 44 of file gps.cpp.

ublox_gps::Gps::~Gps ( )
virtual

Definition at line 48 of file gps.cpp.

Member Function Documentation

bool ublox_gps::Gps::clearBbr ( )

Send a message to the receiver to delete the BBR data stored in flash.

Returns
true if sent message and received ACK, false otherwise

Definition at line 314 of file gps.cpp.

void ublox_gps::Gps::close ( )

Closes the I/O port, and initiates save on shutdown procedure if enabled.

Definition at line 249 of file gps.cpp.

bool ublox_gps::Gps::configGnss ( ublox_msgs::CfgGNSS  gnss,
const boost::posix_time::time_duration &  wait 
)

Configure the GNSS, cold reset the device, and reset the I/O.

Parameters
gnssthe desired GNSS configuration
waitthe time to wait after resetting I/O before restarting
Returns
true if the GNSS was configured, the device was reset, and the I/O reset successfully

Definition at line 285 of file gps.cpp.

bool ublox_gps::Gps::configRate ( uint16_t  meas_rate,
uint16_t  nav_rate 
)

Configure the device navigation and measurement rate settings.

Parameters
meas_ratePeriod in milliseconds between subsequent measurements.
nav_ratethe rate at which navigation solutions are generated by the receiver in number measurement cycles
Returns
true on ACK, false on other conditions.

Definition at line 381 of file gps.cpp.

bool ublox_gps::Gps::configReset ( uint16_t  nav_bbr_mask,
uint16_t  reset_mode 
)

Send a reset message to the u-blox device.

Parameters
nav_bbr_maskThe BBR sections to clear, see CfgRST message
reset_modeThe reset type, see CfgRST message
Returns
true if the message was successfully sent, false otherwise

Definition at line 271 of file gps.cpp.

bool ublox_gps::Gps::configRtcm ( std::vector< uint8_t >  ids,
std::vector< uint8_t >  rates 
)

Configure the RTCM messages with the given IDs to the set rate.

Parameters
idsthe RTCM message ids, valid range: [0, 255]
ratesthe send rates for each RTCM message ID, valid range: [0, 255]
Returns
true on ACK, false on other conditions.

Definition at line 392 of file gps.cpp.

bool ublox_gps::Gps::configSbas ( bool  enable,
uint8_t  usage,
uint8_t  max_sbas 
)

Configure the SBAS settings.

Parameters
enableIf true, enable SBAS. Deprecated in firmware 8, use CfgGNSS instead.
usageSBAS usage, see CfgSBAS for options
max_sbasMaximum Number of SBAS prioritized tracking channels
Returns
true on ACK, false on other conditions.

Definition at line 403 of file gps.cpp.

bool ublox_gps::Gps::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.

Sets the at the given antenna reference point (ARP) position in either Latitude Longitude Altitude (LLA) or ECEF coordinates.

Parameters
arp_positiona vector of size 3 representing the ARP position in ECEF coordinates [m] or LLA coordinates [deg]
arp_position_hpa vector of size 3 a vector of size 3 representing the ARP position in ECEF coordinates [0.1 mm] or LLA coordinates [deg * 1e-9]
lla_flagtrue if position is given in LAT/LON/ALT, false if ECEF
fixed_pos_accFixed position 3D accuracy [m]
Returns
true on ACK, false if settings are incorrect or on other conditions

Definition at line 413 of file gps.cpp.

bool ublox_gps::Gps::configTmode3SurveyIn ( unsigned int  svin_min_dur,
float  svin_acc_limit 
)

Set the TMODE3 settings to survey-in.

Parameters
svin_min_durSurvey-in minimum duration [s]
svin_acc_limitSurvey-in position accuracy limit [m]
Returns
true on ACK, false on other conditions.

Definition at line 449 of file gps.cpp.

bool ublox_gps::Gps::configUart1 ( unsigned int  baudrate,
uint16_t  in_proto_mask,
uint16_t  out_proto_mask 
)

Configure the UART1 Port.

Parameters
baudratethe baudrate of the port
in_proto_maskthe in protocol mask, see CfgPRT message
out_proto_maskthe out protocol mask, see CfgPRT message
Returns
true on ACK, false on other conditions.

Definition at line 322 of file gps.cpp.

template<typename ConfigT >
bool ublox_gps::Gps::configure ( const ConfigT &  message,
bool  wait = true 
)

Send the given configuration message.

Parameters
messagethe configuration message
waitif true, wait for an ACK
Returns
true if message sent successfully and either ACK was received or wait was set to false

Definition at line 516 of file gps.h.

bool ublox_gps::Gps::configUsb ( uint16_t  tx_ready,
uint16_t  in_proto_mask,
uint16_t  out_proto_mask 
)

Configure the USB Port.

Parameters
tx_readythe TX ready pin configuration, see CfgPRT message
in_proto_maskthe in protocol mask, see CfgPRT message
out_proto_maskthe out protocol mask, see CfgPRT message
Returns
true on ACK, false on other conditions.

Definition at line 365 of file gps.cpp.

bool ublox_gps::Gps::disableTmode3 ( )

Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices, otherwise the device will return a NACK.

Returns
true on ACK, false on other conditions.

Definition at line 460 of file gps.cpp.

bool ublox_gps::Gps::disableUart1 ( ublox_msgs::CfgPRT &  prev_cfg)

Disable the UART Port. Sets in/out protocol masks to 0. Does not modify other values.

Parameters
prev_cfgan empty message which will be filled with the previous configuration parameters
Returns
true on ACK, false on other conditions.

Definition at line 339 of file gps.cpp.

void ublox_gps::Gps::initializeSerial ( std::string  port,
unsigned int  baudrate,
uint16_t  uart_in,
uint16_t  uart_out 
)

Initialize the Serial I/O port.

Parameters
portthe device port address
baudratethe desired baud rate of the port
uart_inthe UART In protocol, see CfgPRT for options
uart_outthe UART Out protocol, see CfgPRT for options

Definition at line 108 of file gps.cpp.

void ublox_gps::Gps::initializeTcp ( std::string  host,
std::string  port 
)

Initialize TCP I/O.

Parameters
hostthe TCP host
portthe TCP port

Definition at line 213 of file gps.cpp.

bool ublox_gps::Gps::isConfigured ( ) const
inline

Definition at line 355 of file gps.h.

bool ublox_gps::Gps::isInitialized ( ) const
inline

Definition at line 354 of file gps.h.

bool ublox_gps::Gps::isOpen ( ) const
inline

Definition at line 356 of file gps.h.

template<typename ConfigT >
bool ublox_gps::Gps::poll ( ConfigT &  message,
const std::vector< uint8_t > &  payload = std::vector<uint8_t>(),
const boost::posix_time::time_duration &  timeout = default_timeout_ 
)

Poll a u-blox message of the given type.

Parameters
messagethe received u-blox message output
payloadthe poll message payload sent to the device defaults to empty
timeoutthe amount of time to wait for the desired message

Definition at line 502 of file gps.h.

bool ublox_gps::Gps::poll ( uint8_t  class_id,
uint8_t  message_id,
const std::vector< uint8_t > &  payload = std::vector<uint8_t>() 
)

Poll a u-blox message.

Parameters
class_idthe u-blox message class id
message_idthe u-blox message id
payloadthe poll message payload sent to the device, defaults to empty
timeoutthe amount of time to wait for the desired message

Definition at line 535 of file gps.cpp.

void ublox_gps::Gps::processAck ( const ublox_msgs::Ack &  m)
private

Callback handler for UBX-ACK message.

Parameters
mthe message to process

Definition at line 70 of file gps.cpp.

void ublox_gps::Gps::processNack ( const ublox_msgs::Ack &  m)
private

Callback handler for UBX-NACK message.

Parameters
mthe message to process

Definition at line 82 of file gps.cpp.

void ublox_gps::Gps::processUpdSosAck ( const ublox_msgs::UpdSOS_Ack &  m)
private

Callback handler for UBX-UPD-SOS-ACK message.

Parameters
mthe message to process

Definition at line 93 of file gps.cpp.

template<typename T >
bool ublox_gps::Gps::read ( T &  message,
const boost::posix_time::time_duration &  timeout = default_timeout_ 
)

Read a u-blox message of the given type.

Parameters
messagethe received u-blox message
timeoutthe amount of time to wait for the desired message

Definition at line 510 of file gps.h.

void ublox_gps::Gps::reset ( const boost::posix_time::time_duration &  wait)

Reset I/O communications.

Parameters
waitTime to wait before restarting communications

Definition at line 260 of file gps.cpp.

void ublox_gps::Gps::resetSerial ( std::string  port)

Reset the Serial I/O port after u-blox reset.

Parameters
portthe device port address
baudratethe desired baud rate of the port
uart_inthe UART In protocol, see CfgPRT for options
uart_outthe UART Out protocol, see CfgPRT for options

Definition at line 172 of file gps.cpp.

bool ublox_gps::Gps::saveOnShutdown ( )
private

Execute save on shutdown procedure.

Execute the procedure recommended in the u-blox 8 documentation. Send a stop message to the receiver and instruct it to dump its current state to the attached flash memory (where fitted) as part of the shutdown procedure. The flash data is automatically retrieved when the receiver is restarted.

Returns
true if the receiver reset & saved the BBR contents to flash

Definition at line 301 of file gps.cpp.

void ublox_gps::Gps::setConfigOnStartup ( const bool  config_on_startup)
inline

Set the internal flag for enabling or disabling the initial configurations.

Parameters
config_on_startupboolean flag

Definition at line 90 of file gps.h.

bool ublox_gps::Gps::setDeadReckonLimit ( uint8_t  limit)

Set the dead reckoning time limit.

Parameters
limitTime limit in seconds.
Returns
true on ACK, false on other conditions.

Definition at line 496 of file gps.cpp.

bool ublox_gps::Gps::setDgnss ( uint8_t  mode)

Set the DGNSS mode (see CfgDGNSS message for details).

Parameters
modethe DGNSS mode (see CfgDGNSS message for options)
Returns
true on ACK, false on other conditions

Definition at line 516 of file gps.cpp.

bool ublox_gps::Gps::setDynamicModel ( uint8_t  model)

Set the device dynamic model.

Parameters
modelDynamic model to use. Consult ublox protocol spec for details.
Returns
true on ACK, false on other conditions.

Definition at line 478 of file gps.cpp.

bool ublox_gps::Gps::setFixMode ( uint8_t  mode)

Set the device fix mode.

Parameters
mode2D only, 3D only or auto.
Returns
true on ACK, false on other conditions.

Definition at line 487 of file gps.cpp.

bool ublox_gps::Gps::setPpp ( bool  enable,
float  protocol_version 
)

Enable or disable PPP (precise-point-positioning).

Parameters
enableIf true, enable PPP.
Returns
true on ACK, false on other conditions.
Note
This is part of the expert settings. It is recommended you check the ublox manual first.

Definition at line 505 of file gps.cpp.

bool ublox_gps::Gps::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.

Parameters
class_idthe class identifier of the message
message_idthe message identifier
ratethe updated rate in Hz
Returns
true on ACK, false on other conditions.

Definition at line 468 of file gps.cpp.

void ublox_gps::Gps::setRawDataCallback ( const Worker::Callback callback)

Set the callback function which handles raw data.

Parameters
callbackthe write callback which handles raw data

Definition at line 569 of file gps.cpp.

void ublox_gps::Gps::setSaveOnShutdown ( bool  save_on_shutdown)
inline

If called, when the node shuts down, it will send a command to save the flash memory.

Definition at line 82 of file gps.h.

bool ublox_gps::Gps::setTimtm2 ( uint8_t  rate)

Enable or disable TIM-TM2 (time mark message).

Parameters
enableIf true, enable TIM-TM2.
Returns
true on ACK, false on other conditions.
Note
This is part of the expert settings. It is recommended you check the ublox manual first.

Definition at line 582 of file gps.cpp.

bool ublox_gps::Gps::setUseAdr ( bool  enable,
float  protocol_version 
)

Enable or disable ADR (automotive dead reckoning).

Parameters
enableIf true, enable ADR.
Returns
true on ACK, false on other conditions.

Definition at line 523 of file gps.cpp.

bool ublox_gps::Gps::setUTCtime ( )

Configure the U-Blox to UTC time.

Returns
true on ACK, false on other conditions.
Note
This is part of the expert settings. It is recommended you check the ublox manual first.

Definition at line 574 of file gps.cpp.

void ublox_gps::Gps::setWorker ( const boost::shared_ptr< Worker > &  worker)
private

Set the I/O worker.

Parameters
anI/O handler

Definition at line 50 of file gps.cpp.

template<typename T >
void ublox_gps::Gps::subscribe ( typename CallbackHandler_< T >::Callback  callback,
unsigned int  rate 
)

Configure the U-Blox send rate of the message & subscribe to the given message.

Parameters
thecallback handler for the message
ratethe rate in Hz of the message

Definition at line 484 of file gps.h.

template<typename T >
void ublox_gps::Gps::subscribe ( typename CallbackHandler_< T >::Callback  callback)

Subscribe to the given Ublox message.

Parameters
thecallback handler for the message

Definition at line 491 of file gps.h.

void ublox_gps::Gps::subscribeAcks ( )
private

Subscribe to ACK/NACK messages and UPD-SOS-ACK messages.

Definition at line 58 of file gps.cpp.

template<typename T >
void ublox_gps::Gps::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 different message IDs, e.g. INF messages.

Parameters
thecallback handler for the message
message_idthe U-Blox message ID

Definition at line 496 of file gps.h.

bool ublox_gps::Gps::waitForAcknowledge ( const boost::posix_time::time_duration &  timeout,
uint8_t  class_id,
uint8_t  msg_id 
)

Wait for an acknowledge message until the timeout.

Parameters
timeoutmaximum time to wait in seconds
class_idthe expected class ID of the ACK
msg_idthe expected message ID of the ACK
Returns
true if expected ACK received, false otherwise

Definition at line 548 of file gps.cpp.

Member Data Documentation

boost::atomic<Ack> ublox_gps::Gps::ack_
mutableprivate

Stores last received ACK accessed by multiple threads.

Definition at line 475 of file gps.h.

CallbackHandlers ublox_gps::Gps::callbacks_
private

Callback handlers for u-blox messages.

Definition at line 478 of file gps.h.

bool ublox_gps::Gps::config_on_startup_flag_
private

Definition at line 469 of file gps.h.

bool ublox_gps::Gps::configured_
private

Whether or not the I/O port has been configured.

Definition at line 465 of file gps.h.

const boost::posix_time::time_duration ublox_gps::Gps::default_timeout_
staticprivate
Initial value:
=
boost::posix_time::milliseconds(
static_cast<int>(Gps::kDefaultAckTimeout * 1000))

The default timeout for ACK messages.

Definition at line 473 of file gps.h.

std::string ublox_gps::Gps::host_
private

Definition at line 480 of file gps.h.

constexpr double ublox_gps::Gps::kDefaultAckTimeout = 1.0
static

Default timeout for ACK messages in seconds.

Definition at line 71 of file gps.h.

constexpr int ublox_gps::Gps::kWriterSize = 2056
static

Size of write buffer for output messages.

Definition at line 73 of file gps.h.

std::string ublox_gps::Gps::port_
private

Definition at line 480 of file gps.h.

bool ublox_gps::Gps::save_on_shutdown_
private

Whether or not to save Flash BBR on shutdown.

Whether or not initial configuration to the hardware is done

Definition at line 467 of file gps.h.

boost::shared_ptr<Worker> ublox_gps::Gps::worker_
private

Processes I/O stream data.

Definition at line 463 of file gps.h.


The documentation for this class was generated from the following files:


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