Go to the documentation of this file.
30 #ifndef UBLOX_GPS_NODE_H
31 #define UBLOX_GPS_NODE_H
37 #include <boost/algorithm/string.hpp>
38 #include <boost/lexical_cast.hpp>
39 #include <boost/regex.hpp>
48 #include <geometry_msgs/TwistWithCovarianceStamped.h>
49 #include <geometry_msgs/Vector3Stamped.h>
50 #include <sensor_msgs/NavSatFix.h>
51 #include <sensor_msgs/TimeReference.h>
52 #include <sensor_msgs/Imu.h>
53 #include <nmea_msgs/Sentence.h>
55 #include <ublox_msgs/ublox_msgs.h>
61 #include <rtcm_msgs/Message.h>
152 freq_tol, freq_window);
169 double freq_tol,
int freq_window) {
173 freq_tol, freq_window);
209 freq_tol, freq_window);
210 double stamp_max =
meas_rate * 1e-3 * (1 + freq_tol);
264 template <
typename V,
typename T>
267 std::stringstream oss;
268 oss <<
"Invalid settings: " << name <<
" must be > " <<
min;
269 throw std::runtime_error(oss.str());
281 template <
typename V,
typename T>
283 if(val < min || val > max) {
284 std::stringstream oss;
285 oss <<
"Invalid settings: " << name <<
" must be in range [" <<
min <<
287 throw std::runtime_error(oss.str());
299 template <
typename V,
typename T>
300 void checkRange(std::vector<V> val, T min, T max, std::string name) {
301 for(
size_t i = 0; i < val.size(); i++) {
302 std::stringstream oss;
303 oss << name <<
"[" << i <<
"]";
315 template <
typename U>
318 if (!
nh->getParam(key,
param))
return false;
320 U
min = std::numeric_limits<U>::lowest();
321 U max = std::numeric_limits<U>::max();
336 template <
typename U,
typename V>
337 void getRosUint(
const std::string& key, U &u, V default_val) {
347 template <
typename U>
349 std::vector<int>
param;
350 if (!
nh->getParam(key,
param))
return false;
353 U
min = std::numeric_limits<U>::lowest();
354 U max = std::numeric_limits<U>::max();
358 u.insert(u.begin(),
param.begin(),
param.end());
369 template <
typename I>
372 if (!
nh->getParam(key,
param))
return false;
374 I
min = std::numeric_limits<I>::lowest();
375 I max = std::numeric_limits<I>::max();
390 template <
typename U,
typename V>
391 void getRosInt(
const std::string& key, U &u, V default_val) {
401 template <
typename I>
402 bool getRosInt(
const std::string& key, std::vector<I> &i) {
403 std::vector<int>
param;
404 if (!
nh->getParam(key,
param))
return false;
407 I
min = std::numeric_limits<I>::lowest();
408 I max = std::numeric_limits<I>::max();
412 i.insert(i.begin(),
param.begin(),
param.end());
424 template <
typename MessageT>
425 void publish(
const MessageT& m,
const std::string& topic) {
431 void publish_nmea(
const std::string& sentence,
const std::string& topic) {
434 nmea_msgs::Sentence m;
437 m.sentence = sentence;
546 void printInf(
const ublox_msgs::Inf &m, uint8_t
id);
593 std::string ref_rov =
"");
776 template<
typename NavPVT>
801 sensor_msgs::NavSatFix fix;
804 uint8_t valid_time = m.VALID_DATE | m.VALID_TIME | m.VALID_FULLY_RESOLVED;
805 if (((m.valid & valid_time) == valid_time) &&
806 (m.flags2 & m.FLAGS2_CONFIRMED_AVAILABLE)) {
813 fix.header.stamp.nsec = (uint32_t)(m.nano + 1e9);
817 fix.header.stamp.nsec = (uint32_t)(m.nano);
824 fix.latitude = m.lat * 1e-7;
825 fix.longitude = m.lon * 1e-7;
826 fix.altitude = m.height * 1e-3;
828 bool fixOk = m.flags & m.FLAGS_GNSS_FIX_OK;
829 if (fixOk && m.fixType >= m.FIX_TYPE_2D) {
830 fix.status.status = fix.status.STATUS_FIX;
831 if(m.flags & m.CARRIER_PHASE_FIXED)
832 fix.status.status = fix.status.STATUS_GBAS_FIX;
835 fix.status.status = fix.status.STATUS_NO_FIX;
841 const double varH = pow(m.hAcc / 1000.0, 2);
842 const double varV = pow(m.vAcc / 1000.0, 2);
843 fix.position_covariance[0] = varH;
844 fix.position_covariance[4] = varH;
845 fix.position_covariance[8] = varV;
846 fix.position_covariance_type =
847 sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
855 nh->advertise<geometry_msgs::TwistWithCovarianceStamped>(
"fix_velocity",
857 geometry_msgs::TwistWithCovarianceStamped velocity;
858 velocity.header.stamp = fix.header.stamp;
859 velocity.header.frame_id =
frame_id;
862 velocity.twist.twist.linear.x = m.velE * 1e-3;
863 velocity.twist.twist.linear.y = m.velN * 1e-3;
864 velocity.twist.twist.linear.z = -m.velD * 1e-3;
866 const double covSpeed = pow(m.sAcc * 1e-3, 2);
868 velocity.twist.covariance[cols * 0 + 0] = covSpeed;
869 velocity.twist.covariance[cols * 1 + 1] = covSpeed;
870 velocity.twist.covariance[cols * 2 + 2] = covSpeed;
871 velocity.twist.covariance[cols * 3 + 3] = -1;
873 velocityPublisher.
publish(velocity);
879 freq_diag->diagnostic->tick(fix.header.stamp);
891 ublox_msgs::NavPVT::FIX_TYPE_DEAD_RECKONING_ONLY) {
892 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
893 stat.message =
"Dead reckoning only";
894 }
else if (
last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_2D) {
895 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
896 stat.message =
"2D fix";
897 }
else if (
last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_3D) {
898 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
899 stat.message =
"3D fix";
901 ublox_msgs::NavPVT::FIX_TYPE_GNSS_DEAD_RECKONING_COMBINED) {
902 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
903 stat.message =
"GPS and dead reckoning combined";
905 ublox_msgs::NavPVT::FIX_TYPE_TIME_ONLY) {
906 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
907 stat.message =
"Time only fix";
911 if (
last_nav_pvt_.flags & ublox_msgs::NavPVT::FLAGS_DIFF_SOLN) {
912 stat.message +=
", DGNSS";
915 if (
last_nav_pvt_.flags & ublox_msgs::NavPVT::CARRIER_PHASE_FLOAT) {
916 stat.message +=
", FLOAT FIX";
917 }
else if (
last_nav_pvt_.flags & ublox_msgs::NavPVT::CARRIER_PHASE_FIXED) {
918 stat.message +=
", RTK FIX";
922 if (!(
last_nav_pvt_.flags & ublox_msgs::NavPVT::FLAGS_GNSS_FIX_OK)) {
923 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
924 stat.message +=
", fix not ok";
927 if (
last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_NO_FIX) {
928 stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
929 stat.message =
"No fix";
934 std::ostringstream gnss_coor;
935 gnss_coor << std::fixed << std::setprecision(7);
937 stat.
add(
"Latitude [deg]", gnss_coor.str());
941 stat.
add(
"Longitude [deg]", gnss_coor.str());
1127 ROS_WARN(
"ROS Diagnostics specific to u-blox ADR/UDR devices is %s",
1128 "unimplemented. See AdrUdrProduct class in node.h & node.cpp.");
1154 ROS_WARN(
"Functionality specific to u-blox FTS devices is %s",
1155 "unimplemented. See FtsProduct class in node.h & node.cpp.");
constexpr static double kRtcmFreqMin
Diagnostic updater: RTCM topic frequency min [Hz].
constexpr static double kRtcmFreqTol
Diagnostic updater: RTCM topic frequency tolerance [%].
@ SURVEY_IN
Survey-In mode.
constexpr static uint16_t kDefaultMeasPeriod
Default measurement period for HPG devices.
float sv_in_acc_lim_
Survey in accuracy limit [m].
boost::shared_ptr< ComponentInterface > ComponentPtr
void initializeRosDiagnostics()
Adds diagnostic updaters for FTS status.
AdrUdrProduct(float protocol_version)
uint8_t dgnss_mode_
The DGNSS mode.
void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Updates fix diagnostic from NavPOSLLH, NavVELNED, and NavSOL messages.
constexpr static double kFixFreqWindow
Window [num messages] for Fix Frequency Diagnostic.
uint8_t fmode_
Set from fix mode string.
ublox_msgs::CfgCFG load_
Parameters to load from non-volatile memory during configuration.
bool supportsGnss(std::string gnss)
double min_freq
Minimum allow frequency of topic.
static constexpr double kRtcmFreqTol
Implements functions for FTS products. Currently unimplemented.
bool svin_reset_
Whether to always reset the survey-in during configuration.
uint16_t usb_out_
USB out protocol (see CfgPRT message for constants)
void subscribe()
Subscribe to Raw Data Product messages and set up ROS publishers.
Implements functions for firmware version 9. For now it simply re-uses the firmware version 8 class b...
bool set_dat_
If true, set configure the User-Defined Datum.
void getRosParams()
Get the Time Sync parameters.
bool configureUblox()
Configure GNSS individually. Only configures GLONASS.
void add(const std::string &key, const bool &b)
@ FIXED
Fixed mode (should switch to time mode almost immediately)
bool lla_flag_
True if coordinates are in LLA, false if ECEF.
void subscribe()
Subscribe to messages which are not generic to all firmware.
diagnostic_updater::HeaderlessTopicDiagnostic * diagnostic
Topic frequency diagnostic updater.
void getRosParams()
Get the ROS parameters specific to the Reference Station configuration.
uint8_t modelFromString(const std::string &model)
Determine dynamic model from human-readable string.
void pollMessages(const ros::TimerEvent &event)
Poll messages from the U-Blox device.
ublox_msgs::CfgDAT cfg_dat_
User-defined Datum.
constexpr static double kKeepAlivePeriod
How often (in seconds) to send keep-alive message.
virtual void getRosParams()=0
Get the ROS parameters.
uint8_t dmodel_
Set from dynamic model string.
bool config_on_startup_flag_
Flag for enabling configuration on startup.
void addFirmwareInterface()
Add the interface for firmware specific configuration, subscribers, & diagnostics....
bool enable_ppp_
Whether or not to enable PPP (advanced setting)
void configureInf()
Configure INF messages, call after subscribe.
void initializeRosDiagnostics()
Initialize the ROS diagnostics for the ADR/UDR device.
Implements functions for High Precision GNSS Reference station devices.
bool getRosInt(const std::string &key, I &u)
Get a integer (size 8 or 16) value from the parameter server.
ublox_msgs::CfgNMEA7 cfg_nmea_
Used to configure NMEA (if set_nmea_)
@ TIME
Time mode, after survey-in or after configuring fixed mode.
bool clear_bbr_
Whether to clear the flash memory during configuration.
sensor_msgs::NavSatFix fix_
The last NavSatFix based on last_nav_pos_.
Implements functions for High Precision GNSS Rover devices.
bool setTimeMode()
Set the device mode to time mode (internal state variable).
bool enable_sbas_
Whether or not to enable SBAS.
ublox_msgs::NavRELPOSNED9 last_rel_pos_
Last relative position (used for diagnostic updater)
enum ublox_node::HpgRefProduct::@0 mode_
Status of device time mode.
void tmode3Diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the TMODE3 diagnostics.
bool configureUblox()
Configure ADR/UDR settings.
void getRosParams()
Get the FTS parameters.
This abstract class represents a firmware component.
ublox_msgs::NavPOSLLH last_nav_pos_
The last received navigation position.
void publish(const boost::shared_ptr< M > &message) const
void initializeRosDiagnostics()
Add diagnostic updaters for rover GNSS status, including status of RTCM messages.
bool getRosUint(const std::string &key, U &u)
Get a unsigned integer value from the parameter server.
uint8_t dr_limit_
Dead reckoning limit parameter.
FixDiagnostic(std::string name, double freq_tol, int freq_window, double stamp_min)
Add a topic diagnostic to the diagnostic updater for fix topics.
void initialize()
Initialize the U-Blox node. Configure the U-Blox and subscribe to messages.
bool enable_glonass_
Whether or not to enable GLONASS.
bool enable_beidou_
Whether or not to enable the BeiDuo GNSS.
bool set_nmea_
Whether or not to configure the NMEA settings.
bool enable_galileo_
Whether or not to enable the Galileo GNSS.
void keepAlive(const ros::TimerEvent &event)
Poll version message from the U-Blox device to keep socket active.
bool enable_sbas_
Whether or not to enable SBAS.
constexpr static double kFixFreqTol
Tolerance for Fix topic frequency as percentage of target frequency.
uint16_t usb_in_
USB in protocol (see CfgPRT message for constants)
std::vector< float > arp_position_
Antenna Reference Point Position [m] or [deg].
void getRosParams()
Get the ADR/UDR parameters.
Topic diagnostics for fix / fix_velocity messages.
This class represents u-blox ROS node for all firmware and product versions.
sensor_msgs::TimeReference t_ref_
void initializeRosDiagnostics()
Adds diagnostic updaters for Time Sync status.
bool configureUblox()
Prints a warning, GNSS configuration not available in this version.
virtual void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)=0
Handle to send fix status to ROS diagnostics.
double max_freq
Maximum allow frequency of topic.
void getRosParams()
Get the node parameters from the ROS Parameter Server.
void carrierPhaseDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the rover diagnostics, including the carrier phase solution status (float or fixed).
void processMonVer()
Process the MonVer message and add firmware and product components.
bool configureUblox()
Configure the device based on ROS parameters.
Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices.
uint32_t sv_in_min_dur_
Measurement period used during Survey-In [s].
uint32_t qzss_sig_cfg_
The QZSS Signal configuration, see CfgGNSS message.
ublox_msgs::NavVELNED last_nav_vel_
The last received navigation velocity.
ublox_msgs::NavSOL last_nav_sol_
The last received num SVs used.
virtual void subscribe()=0
Subscribe to u-blox messages and publish to ROS topics.
geometry_msgs::TwistWithCovarianceStamped velocity_
The last Twist based on last_nav_vel_.
Implements functions for firmware version 6.
bool set_nmea_
Whether or not to configure the NMEA settings.
bool configureUblox()
Configure the u-blox Reference Station settings.
void callbackNavVelNed(const ublox_msgs::NavVELNED &m)
Update the last known velocity.
constexpr static int kRtcmFreqWindow
Diagnostic updater: RTCM topic frequency window [num messages].
void subscribe()
Subscribe to all requested u-blox messages.
ublox_msgs::TimTM2 timtm2
bool configureUblox()
Configure rover settings.
bool resetDevice()
Send a reset message the u-blox device & re-initialize the I/O.
void getRosParams()
Sets the fix status service type to GPS.
std::vector< boost::shared_ptr< ComponentInterface > > components_
The u-blox node components.
std::vector< uint8_t > rtcm_ids
IDs of RTCM out messages to configure.
void callbackNavSol(const ublox_msgs::NavSOL &m)
Update the number of SVs used for the fix.
void subscribe()
Subscribe to u-blox messages which are not generic to all firmware versions.
bool enable_imes_
Whether or not to enable the IMES GNSS.
constexpr static uint32_t kNavSvInfoSubscribeRate
Subscribe Rate for u-blox SV Info messages.
constexpr static double kRtcmFreqMax
Diagnostic updater: RTCM topic frequency max [Hz].
void callbackNavPvt(const NavPVT &m)
Publish a NavSatFix and TwistWithCovarianceStamped messages.
bool configureUblox()
Configure Time Sync settings.
uint32_t baudrate_
UART1 baudrate.
Implements functions for firmware version 7.
RawDataStreamPa rawDataStreamPa_
raw data stream logging
ublox_msgs::CfgCFG save_
Parameters to save to non-volatile memory after configuration.
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED9 &m)
Set the last received message and call rover diagnostic updater.
void checkMin(V val, T min, std::string name)
Check that the parameter is above the minimum.
UbloxTopicDiagnostic freq_rtcm_
The RTCM topic frequency diagnostic updater.
bool set_usb_
Whether to configure the USB port.
std::vector< boost::shared_ptr< UbloxTopicDiagnostic > > freq_diagnostics_
Topic diagnostic updaters.
void publish(const MessageT &m, const std::string &topic)
Publish a ROS message of type MessageT.
sensor_msgs::TimeReference t_ref_
virtual bool configureUblox()=0
Configure the U-Blox settings.
bool enable_gps_
Whether or not to enable GPS.
void getRosParams()
Does nothing since there are no Raw Data product specific settings.
void checkRange(V val, T min, T max, std::string name)
Check that the parameter is in the range.
void initializeRosDiagnostics()
Add the fix diagnostics to the updater.
Handles communication with and configuration of the u-blox device.
boost::shared_ptr< ros::NodeHandle > nh
Node Handle for GPS node.
This interface is used to add functionality to the main node.
bool enable_qzss_
Whether or not to enable QZSS.
bool configureUblox()
Configure settings specific to firmware 8 based on ROS parameters.
std::string fix_mode_
Fix mode type.
Implements functions for raw data stream.
constexpr static uint32_t kROSQueueSize
Queue size for ROS publishers.
float fixed_pos_acc_
Fixed Position Accuracy [m].
void callbackNavSvIn(ublox_msgs::NavSVIN m)
Update the last received NavSVIN message and call diagnostic updater.
uint8_t tim_rate_
rate for TIM-TM2
void subscribe()
Subscribe to ADR/UDR messages.
std::vector< uint8_t > rtcm_rates
Rates of RTCM out messages. Size must be the same as rtcm_ids.
double rate_
The measurement rate in Hz.
void getRosParams()
Get the parameters specific to firmware version 7.
void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the fix diagnostics from Nav PVT message.
diagnostic_updater::TopicDiagnostic * diagnostic
Topic frequency diagnostic updater.
void initializeRosDiagnostics()
Add diagnostic updaters for the TMODE3 status.
std::string dynamic_model_
dynamic model type
uint8_t sbas_usage_
SBAS Usage parameter (see CfgSBAS message)
void subscribe()
Subscribe to Rover messages, such as NavRELPOSNED.
Implements functions for Raw Data products.
std::vector< int8_t > arp_position_hp_
Antenna Reference Point Position High Precision [0.1 mm] or [deg * 1e-9].
std::string frame_id
The ROS frame ID of this device.
UbloxTopicDiagnostic(std::string topic, double freq_tol, int freq_window)
Add a topic diagnostic to the diagnostic updater for.
UbloxNode()
Initialize and run the u-blox node.
uint8_t tmode3_
TMODE3 to set, such as disabled, survey-in, fixed.
ublox_gps::Gps gps
Handles communication with the U-Blox Device.
uint16_t uart_in_
UART in protocol (see CfgPRT message for constants)
Implements functions for firmware version 8.
NavPVT last_nav_pvt_
The last received NavPVT message.
uint16_t uart_out_
UART out protocol (see CfgPRT message for constants)
std::map< std::string, bool > enabled
Whether or not to publish the given ublox message.
Implements functions for Time Sync products.
constexpr static double kTimeStampStatusMin
Minimum Time Stamp Status for fix frequency diagnostic.
ublox_msgs::NavSVIN last_nav_svin_
The last received Nav SVIN message.
void subscribe()
Subscribe to NavPVT, RxmRAW, and RxmSFRB messages.
Topic diagnostics for u-blox messages.
void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED &m)
Set the last received message and call rover diagnostic updater.
constexpr static float kDiagnosticPeriod
[s] 5Hz diagnostic period
uint8_t max_sbas_
Max SBAS parameter (see CfgSBAS message)
void subscribe()
Subscribe to u-blox Reference Station messages.
bool set_nmea_
Whether or not to Configure the NMEA settings.
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
void callbackNavHpPosLlh(const ublox_msgs::NavHPPOSLLH &m)
Publish a sensor_msgs/NavSatFix message upon receiving a HPPOSLLH UBX message.
void callbackEsfMEAS(const ublox_msgs::EsfMEAS &m)
void subscribe()
Subscribe to FTS messages.
static constexpr int kRtcmFreqWindow
void callbackNavPosLlh(const ublox_msgs::NavPOSLLH &m)
Publish the fix and call the fix diagnostic updater.
std::string device_
Device port.
double min_freq
Minimum allow frequency of topic.
T param(const std::string ¶m_name, const T &default_val)
@ INIT
Initialization mode (before configuration)
bool configureUblox()
Configure FTS settings.
UbloxTopicDiagnostic(std::string topic, double freq_min, double freq_max, double freq_tol, int freq_window)
Add a topic diagnostic to the diagnostic updater for.
uint8_t fixModeFromString(const std::string &mode)
Determine fix mode from human-readable string.
void initializeRosDiagnostics()
Adds frequency diagnostics for RTCM topics.
long toUtcSeconds(const NavPVT &msg)
Convert date/time to UTC time in seconds.
std::set< std::string > supported
Which GNSS are supported by the device.
void initializeRosDiagnostics()
Initialize the diagnostic updater and add the fix diagnostic.
ublox_msgs::CfgNMEA cfg_nmea_
Desired NMEA configuration.
void getRosParams()
Get the ROS parameters specific to the Rover configuration.
ublox_msgs::NavRELPOSNED last_rel_pos_
Last relative position (used for diagnostic updater)
virtual void initializeRosDiagnostics()=0
Initialize the diagnostics.
boost::shared_ptr< FixDiagnostic > freq_diag
fix frequency diagnostic updater
constexpr static uint32_t kSubscribeRate
Default subscribe Rate to u-blox messages [Hz].
bool use_adr_
Whether or not to enable dead reckoning.
void subscribe()
Subscribe to Time Sync messages.
constexpr static double kPollDuration
How often (in seconds) to call poll messages.
float protocol_version_
Determined From Mon VER.
bool configureUblox()
Does nothing since there are no Raw Data product specific settings.
boost::shared_ptr< diagnostic_updater::Updater > updater
ROS diagnostic updater.
void subscribe()
Subscribe to Rover messages, such as NavRELPOSNED.
void addProductInterface(std::string product_category, std::string ref_rov="")
Add the interface which is used for product category configuration, subscribers, & diagnostics.
double max_freq
Maximum allow frequency of topic.
void callbackTimTM2(const ublox_msgs::TimTM2 &m)
void publish_nmea(const std::string &sentence, const std::string &topic)
void shutdown()
Shutdown the node. Closes the serial port.
ublox_msgs::CfgNMEA6 cfg_nmea_
Used to configure NMEA (if set_nmea_) filled with ROS parameters.
@ DISABLED
Time mode disabled.
void printInf(const ublox_msgs::Inf &m, uint8_t id)
Print an INF message to the ROS console.
void initializeIo()
Initialize the I/O handling.
uint16_t usb_tx_
USB TX Ready Pin configuration (see CfgPRT message for constants)
void getRosParams()
Get the ROS parameters specific to firmware version 8.
ublox_gps
Author(s): Johannes Meyer
autogenerated on Wed Dec 7 2022 03:47:53