Class Gps
Defined in File gps.hpp
Nested Relationships
Nested Types
Class Documentation
-
class Gps
Handles communication with and configuration of the u-blox device.
Public Functions
-
explicit Gps(int debug, const rclcpp::Logger &logger)
-
~Gps()
-
inline void setSaveOnShutdown(bool save_on_shutdown)
If called, when the node shuts down, it will send a command to save the flash memory.
-
inline void setConfigOnStartup(bool config_on_startup)
Set the internal flag for enabling or disabling the initial configurations.
- Parameters:
config_on_startup – boolean flag
-
void initializeTcp(const std::string &host, const std::string &port)
Initialize TCP I/O.
- Parameters:
host – the TCP host
port – the TCP port
-
void initializeUdp(const std::string &host, const std::string &port)
Initialize UDP I/O.
- Parameters:
host – the UDP host
port – the UDP port
-
void initializeSerial(const std::string &port, unsigned int baudrate, uint16_t uart_in, uint16_t uart_out)
Initialize the Serial I/O port.
- Parameters:
port – the device port address
baudrate – the desired baud rate of the port
uart_in – the UART In protocol, see CfgPRT for options
uart_out – the UART Out protocol, see CfgPRT for options
-
void resetSerial(const std::string &port)
Reset the Serial I/O port after u-blox reset.
- Parameters:
port – the device port address
baudrate – the desired baud rate of the port
uart_in – the UART In protocol, see CfgPRT for options
uart_out – the UART Out protocol, see CfgPRT for options
-
bool sendRtcm(const std::vector<uint8_t> &message)
Send rtcm correction messages to the connected device.
- Parameters:
message – the RTCM correction data as a vector
-
void close()
Closes the I/O port, and initiates save on shutdown procedure if enabled.
-
void reset(const std::chrono::milliseconds &wait)
Reset I/O communications.
- Parameters:
wait – Time to wait before restarting communications
-
bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode)
Send a reset message to the u-blox device.
- Parameters:
nav_bbr_mask – The BBR sections to clear, see CfgRST message
reset_mode – The reset type, see CfgRST message
- Returns:
true if the message was successfully sent, false otherwise
-
bool configGnss(ublox_msgs::msg::CfgGNSS gnss, const std::chrono::milliseconds &wait)
Configure the GNSS, cold reset the device, and reset the I/O.
- Parameters:
gnss – the desired GNSS configuration
wait – the 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
-
bool 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
-
bool configUart1(unsigned int baudrate, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the UART1 Port.
- Parameters:
baudrate – the baudrate of the port
in_proto_mask – the in protocol mask, see CfgPRT message
out_proto_mask – the out protocol mask, see CfgPRT message
- Returns:
true on ACK, false on other conditions.
-
bool disableUart1(ublox_msgs::msg::CfgPRT &prev_config)
Disable the UART Port. Sets in/out protocol masks to 0. Does not modify other values.
- Parameters:
prev_cfg – an empty message which will be filled with the previous configuration parameters
- Returns:
true on ACK, false on other conditions.
-
bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the USB Port.
- Parameters:
tx_ready – the TX ready pin configuration, see CfgPRT message
in_proto_mask – the in protocol mask, see CfgPRT message
out_proto_mask – the out protocol mask, see CfgPRT message
- Returns:
true on ACK, false on other conditions.
-
bool configRate(uint16_t meas_rate, uint16_t nav_rate)
Configure the device navigation and measurement rate settings.
- Parameters:
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
- Returns:
true on ACK, false on other conditions.
-
bool configRtcm(const std::vector<Rtcm> &rtcms)
Configure the RTCM messages with the given IDs to the set rate.
- Parameters:
ids – the RTCM message ids, valid range: [0, 255]
rates – the send rates for each RTCM message ID, valid range: [0, 255]
- Returns:
true on ACK, false on other conditions.
-
bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas)
Configure the SBAS settings.
- Parameters:
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
- Returns:
true on ACK, false on other conditions.
-
bool configTmode3Fixed(bool lla_flag, std::vector<double> 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_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]
- Returns:
true on ACK, false if settings are incorrect or on other conditions
-
bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit)
Set the TMODE3 settings to survey-in.
- Parameters:
svin_min_dur – Survey-in minimum duration [s]
svin_acc_limit – Survey-in position accuracy limit [m]
- Returns:
true on ACK, false on other conditions.
-
bool 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.
-
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.
- Parameters:
class_id – the class identifier of the message
message_id – the message identifier
rate – the updated rate in Hz
- Returns:
true on ACK, false on other conditions.
-
bool setDynamicModel(uint8_t model)
Set the device dynamic model.
- Parameters:
model – Dynamic model to use. Consult ublox protocol spec for details.
- Returns:
true on ACK, false on other conditions.
-
bool setFixMode(uint8_t mode)
Set the device fix mode.
- Parameters:
mode – 2D only, 3D only or auto.
- Returns:
true on ACK, false on other conditions.
-
bool setDeadReckonLimit(uint8_t limit)
Set the dead reckoning time limit.
- Parameters:
limit – Time limit in seconds.
- Returns:
true on ACK, false on other conditions.
-
bool setPpp(bool enable)
Enable or disable PPP (precise-point-positioning).
Note
This is part of the expert settings. It is recommended you check the ublox manual first.
- Parameters:
enable – If true, enable PPP.
- Returns:
true on ACK, false on other conditions.
-
bool setDgnss(uint8_t mode)
Set the DGNSS mode (see CfgDGNSS message for details).
- Parameters:
mode – the DGNSS mode (see CfgDGNSS message for options)
- Returns:
true on ACK, false on other conditions
-
bool setUseAdr(bool enable)
Enable or disable ADR (automotive dead reckoning).
- Parameters:
enable – If true, enable ADR.
- Returns:
true on ACK, false on other conditions.
-
bool setUTCtime()
Configure the U-Blox to UTC time.
Note
This is part of the expert settings. It is recommended you check the ublox manual first.
- Returns:
true on ACK, false on other conditions.
-
bool setTimtm2(uint8_t rate)
Enable or disable TIM-TM2 (time mark message).
Note
This is part of the expert settings. It is recommended you check the ublox manual first.
- Parameters:
enable – If true, enable TIM-TM2.
- Returns:
true on ACK, false on other conditions.
-
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.
- Parameters:
the – callback handler for the message
rate – the rate in Hz of the message
-
template<typename T>
void subscribe(typename CallbackHandler_<T>::Callback callback) Subscribe to the given Ublox message.
- Parameters:
the – callback handler for the message
-
void subscribe_nmea(std::function<void(const std::string&)> callback)
Subscribe to the given Ublox message.
- Parameters:
callback – the callback handler for the 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.
- Parameters:
the – callback handler for the message
message_id – the U-Blox message ID
-
template<typename T>
bool read(T &message, const std::chrono::milliseconds &timeout = default_timeout_) Read a u-blox message of the given type.
- Parameters:
message – the received u-blox message
timeout – the amount of time to wait for the desired message
-
inline bool isInitialized() const
-
inline bool isConfigured() const
-
inline bool isOpen() const
-
template<typename ConfigT>
bool poll(ConfigT &message, const std::vector<uint8_t> &payload = std::vector<uint8_t>(), const std::chrono::milliseconds &timeout = default_timeout_) Poll a u-blox message of the given type.
- Parameters:
message – the received u-blox message output
payload – the poll message payload sent to the device defaults to empty
timeout – the amount of time to wait for the desired message
-
bool 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_id – the u-blox message class id
message_id – the u-blox message id
payload – the poll message payload sent to the device, defaults to empty
timeout – the amount of time to wait for the desired message
-
template<typename ConfigT>
bool configure(const ConfigT &message, bool wait = true) Send the given configuration message.
- Parameters:
message – the configuration message
wait – if true, wait for an ACK
- Returns:
true if message sent successfully and either ACK was received or wait was set to false
-
bool waitForAcknowledge(const std::chrono::milliseconds &timeout, uint8_t class_id, uint8_t msg_id)
Wait for an acknowledge message until the timeout.
- Parameters:
timeout – maximum time to wait in seconds
class_id – the expected class ID of the ACK
msg_id – the expected message ID of the ACK
- Returns:
true if expected ACK received, false otherwise
-
void setRawDataCallback(const Worker::WorkerRawCallback &callback)
Set the callback function which handles raw data.
- Parameters:
callback – the write callback which handles raw data
Public Members
-
const int kSetBaudrateSleepMs = 500
Sleep time [ms] after setting the baudrate.
-
explicit Gps(int debug, const rclcpp::Logger &logger)