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. | |
void | close () |
Closes the I/O port, and initiates save on shutdown procedure if enabled. | |
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. | |
bool | configRate (uint16_t meas_rate, uint16_t nav_rate) |
Configure the device navigation and measurement rate settings. | |
bool | configReset (uint16_t nav_bbr_mask, uint16_t reset_mode) |
Send a reset message to the u-blox device. | |
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 | configSbas (bool enable, uint8_t usage, uint8_t max_sbas) |
Configure the SBAS settings. | |
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 | configTmode3SurveyIn (unsigned int svin_min_dur, float svin_acc_limit) |
Set the TMODE3 settings to survey-in. | |
bool | configUart1 (unsigned int baudrate, uint16_t in_proto_mask, uint16_t out_proto_mask) |
Configure the UART1 Port. | |
template<typename ConfigT > | |
bool | configure (const ConfigT &message, bool wait=true) |
Send the given configuration message. | |
bool | configUsb (uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask) |
Configure the USB Port. | |
bool | disableTmode3 () |
Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices, otherwise the device will return a NACK. | |
bool | disableUart1 (ublox_msgs::CfgPRT &prev_cfg) |
Disable the UART Port. Sets in/out protocol masks to 0. Does not modify other values. | |
Gps () | |
void | initializeSerial (std::string port, unsigned int baudrate, uint16_t uart_in, uint16_t uart_out) |
Initialize the Serial I/O port. | |
void | initializeTcp (std::string host, std::string port) |
Initialize TCP I/O. | |
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. | |
void | resetSerial (std::string port) |
Reset the Serial I/O port after u-blox reset. | |
void | setConfigOnStartup (const bool config_on_startup) |
Set the internal flag for enabling or disabling the initial configurations. | |
bool | setDeadReckonLimit (uint8_t limit) |
Set the dead reckoning time limit. | |
bool | setDgnss (uint8_t mode) |
Set the DGNSS mode (see CfgDGNSS message for details). | |
bool | setDynamicModel (uint8_t model) |
Set the device dynamic model. | |
bool | setFixMode (uint8_t mode) |
Set the device fix mode. | |
bool | setPpp (bool enable) |
Enable or disable PPP (precise-point-positioning). | |
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. | |
void | setRawDataCallback (const Worker::Callback &callback) |
Set the callback function which handles raw data. | |
void | setSaveOnShutdown (bool save_on_shutdown) |
If called, when the node shuts down, it will send a command to save the flash memory. | |
bool | setTimtm2 (uint8_t rate) |
Enable or disable TIM-TM2 (time mark message). | |
bool | setUseAdr (bool enable) |
Enable or disable ADR (automotive dead reckoning). | |
bool | setUTCtime () |
Configure the U-Blox to UTC time. | |
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. | |
template<typename T > | |
void | subscribe (typename CallbackHandler_< T >::Callback callback) |
Subscribe to the given Ublox message. | |
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. | |
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. | |
virtual | ~Gps () |
Static Public Attributes | |
static constexpr double | kDefaultAckTimeout = 1.0 |
Default timeout for ACK messages in seconds. | |
static constexpr int | kSetBaudrateSleepMs = 500 |
Sleep time [ms] after setting the baudrate. | |
static constexpr int | kWriterSize = 2056 |
Size of write buffer for output messages. | |
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. | |
void | processNack (const ublox_msgs::Ack &m) |
Callback handler for UBX-NACK message. | |
void | processUpdSosAck (const ublox_msgs::UpdSOS_Ack &m) |
Callback handler for UBX-UPD-SOS-ACK message. | |
bool | saveOnShutdown () |
Execute save on shutdown procedure. | |
void | setWorker (const boost::shared_ptr< Worker > &worker) |
Set the I/O worker. | |
void | subscribeAcks () |
Subscribe to ACK/NACK messages and UPD-SOS-ACK messages. | |
Private Attributes | |
boost::atomic< Ack > | ack_ |
Stores last received ACK accessed by multiple threads. | |
CallbackHandlers | callbacks_ |
Callback handlers for u-blox messages. | |
bool | config_on_startup_flag_ |
bool | configured_ |
Whether or not the I/O port has been configured. | |
std::string | host_ |
std::string | port_ |
bool | save_on_shutdown_ |
Whether or not to save Flash BBR on shutdown. | |
boost::shared_ptr< Worker > | worker_ |
Processes I/O stream data. | |
Static Private Attributes | |
static const boost::posix_time::time_duration | default_timeout_ |
The default timeout for ACK messages. |
Handles communication with and configuration of the u-blox device.
enum ublox_gps::Gps::AckType [private] |
ublox_gps::Gps::~Gps | ( | ) | [virtual] |
bool ublox_gps::Gps::clearBbr | ( | ) |
void ublox_gps::Gps::close | ( | ) |
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.
gnss | the desired GNSS configuration |
wait | the time to wait after resetting I/O before restarting |
bool ublox_gps::Gps::configRate | ( | uint16_t | meas_rate, |
uint16_t | nav_rate | ||
) |
Configure the device navigation and measurement rate settings.
meas_rate | Period in milliseconds between subsequent measurements. |
nav_rate | the rate at which navigation solutions are generated by the receiver in number measurement cycles |
bool ublox_gps::Gps::configReset | ( | uint16_t | nav_bbr_mask, |
uint16_t | reset_mode | ||
) |
bool ublox_gps::Gps::configRtcm | ( | std::vector< uint8_t > | ids, |
std::vector< uint8_t > | rates | ||
) |
bool ublox_gps::Gps::configSbas | ( | bool | enable, |
uint8_t | usage, | ||
uint8_t | max_sbas | ||
) |
Configure the SBAS settings.
enable | If true, enable SBAS. Deprecated in firmware 8, use CfgGNSS instead. |
usage | SBAS usage, see CfgSBAS for options |
max_sbas | Maximum Number of SBAS prioritized tracking channels |
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.
arp_position | a vector of size 3 representing the ARP position in ECEF coordinates [m] or LLA coordinates [deg] |
arp_position_hp | a 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_flag | true if position is given in LAT/LON/ALT, false if ECEF |
fixed_pos_acc | Fixed position 3D accuracy [m] |
bool ublox_gps::Gps::configTmode3SurveyIn | ( | unsigned int | svin_min_dur, |
float | svin_acc_limit | ||
) |
bool ublox_gps::Gps::configUart1 | ( | unsigned int | baudrate, |
uint16_t | in_proto_mask, | ||
uint16_t | out_proto_mask | ||
) |
bool ublox_gps::Gps::configure | ( | const ConfigT & | message, |
bool | wait = true |
||
) |
bool ublox_gps::Gps::configUsb | ( | uint16_t | tx_ready, |
uint16_t | in_proto_mask, | ||
uint16_t | out_proto_mask | ||
) |
bool ublox_gps::Gps::disableTmode3 | ( | ) |
bool ublox_gps::Gps::disableUart1 | ( | ublox_msgs::CfgPRT & | prev_cfg | ) |
void ublox_gps::Gps::initializeSerial | ( | std::string | port, |
unsigned int | baudrate, | ||
uint16_t | uart_in, | ||
uint16_t | uart_out | ||
) |
void ublox_gps::Gps::initializeTcp | ( | std::string | host, |
std::string | port | ||
) |
bool ublox_gps::Gps::isConfigured | ( | ) | const [inline] |
bool ublox_gps::Gps::isInitialized | ( | ) | const [inline] |
bool ublox_gps::Gps::isOpen | ( | ) | const [inline] |
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_ |
||
) |
bool ublox_gps::Gps::poll | ( | uint8_t | class_id, |
uint8_t | message_id, | ||
const std::vector< uint8_t > & | payload = std::vector<uint8_t>() |
||
) |
void ublox_gps::Gps::processAck | ( | const ublox_msgs::Ack & | m | ) | [private] |
void ublox_gps::Gps::processNack | ( | const ublox_msgs::Ack & | m | ) | [private] |
void ublox_gps::Gps::processUpdSosAck | ( | const ublox_msgs::UpdSOS_Ack & | m | ) | [private] |
bool ublox_gps::Gps::read | ( | T & | message, |
const boost::posix_time::time_duration & | timeout = default_timeout_ |
||
) |
void ublox_gps::Gps::reset | ( | const boost::posix_time::time_duration & | wait | ) |
void ublox_gps::Gps::resetSerial | ( | std::string | port | ) |
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.
void ublox_gps::Gps::setConfigOnStartup | ( | const bool | config_on_startup | ) | [inline] |
bool ublox_gps::Gps::setDeadReckonLimit | ( | uint8_t | limit | ) |
bool ublox_gps::Gps::setDgnss | ( | uint8_t | mode | ) |
bool ublox_gps::Gps::setDynamicModel | ( | uint8_t | model | ) |
bool ublox_gps::Gps::setFixMode | ( | uint8_t | mode | ) |
bool ublox_gps::Gps::setPpp | ( | bool | enable | ) |
bool ublox_gps::Gps::setRate | ( | uint8_t | class_id, |
uint8_t | message_id, | ||
uint8_t | rate | ||
) |
void ublox_gps::Gps::setRawDataCallback | ( | const Worker::Callback & | callback | ) |
void ublox_gps::Gps::setSaveOnShutdown | ( | bool | save_on_shutdown | ) | [inline] |
bool ublox_gps::Gps::setTimtm2 | ( | uint8_t | rate | ) |
bool ublox_gps::Gps::setUseAdr | ( | bool | enable | ) |
bool ublox_gps::Gps::setUTCtime | ( | ) |
void ublox_gps::Gps::setWorker | ( | const boost::shared_ptr< Worker > & | worker | ) | [private] |
void ublox_gps::Gps::subscribe | ( | typename CallbackHandler_< T >::Callback | callback, |
unsigned int | rate | ||
) |
void ublox_gps::Gps::subscribe | ( | typename CallbackHandler_< T >::Callback | callback | ) |
void ublox_gps::Gps::subscribeAcks | ( | ) | [private] |
void ublox_gps::Gps::subscribeId | ( | typename CallbackHandler_< T >::Callback | callback, |
unsigned int | message_id | ||
) |
bool ublox_gps::Gps::waitForAcknowledge | ( | const boost::posix_time::time_duration & | timeout, |
uint8_t | class_id, | ||
uint8_t | msg_id | ||
) |
boost::atomic<Ack> ublox_gps::Gps::ack_ [mutable, private] |
CallbackHandlers ublox_gps::Gps::callbacks_ [private] |
bool ublox_gps::Gps::config_on_startup_flag_ [private] |
bool ublox_gps::Gps::configured_ [private] |
const boost::posix_time::time_duration ublox_gps::Gps::default_timeout_ [static, private] |
boost::posix_time::milliseconds( static_cast<int>(Gps::kDefaultAckTimeout * 1000))
The default timeout for ACK messages.
std::string ublox_gps::Gps::host_ [private] |
constexpr double ublox_gps::Gps::kDefaultAckTimeout = 1.0 [static] |
constexpr int ublox_gps::Gps::kSetBaudrateSleepMs = 500 [static] |
constexpr int ublox_gps::Gps::kWriterSize = 2056 [static] |
std::string ublox_gps::Gps::port_ [private] |
bool ublox_gps::Gps::save_on_shutdown_ [private] |
boost::shared_ptr<Worker> ublox_gps::Gps::worker_ [private] |