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> 54 #include <ublox_msgs/ublox_msgs.h> 145 const double target_freq = 1.0 / (meas_rate * 1e-3 *
nav_rate);
149 freq_tol, freq_window);
166 double freq_tol,
int freq_window) {
170 freq_tol, freq_window);
202 const double target_freq = 1.0 / (meas_rate * 1e-3 *
nav_rate);
206 freq_tol, freq_window);
207 double stamp_max = meas_rate * 1e-3 * (1 + freq_tol);
261 template <
typename V,
typename T>
264 std::stringstream oss;
265 oss <<
"Invalid settings: " << name <<
" must be > " << min;
266 throw std::runtime_error(oss.str());
278 template <
typename V,
typename T>
280 if(val < min || val > max) {
281 std::stringstream oss;
282 oss <<
"Invalid settings: " << name <<
" must be in range [" << min <<
284 throw std::runtime_error(oss.str());
296 template <
typename V,
typename T>
297 void checkRange(std::vector<V> val, T min, T max, std::string name) {
298 for(
size_t i = 0; i < val.size(); i++) {
299 std::stringstream oss;
300 oss << name <<
"[" << i <<
"]";
312 template <
typename U>
315 if (!nh->getParam(key, param))
return false;
317 U
min = std::numeric_limits<U>::lowest();
318 U max = std::numeric_limits<U>::max();
333 template <
typename U,
typename V>
334 void getRosUint(
const std::string& key, U &u, V default_val) {
344 template <
typename U>
346 std::vector<int>
param;
347 if (!nh->getParam(key, param))
return false;
350 U
min = std::numeric_limits<U>::lowest();
351 U max = std::numeric_limits<U>::max();
355 u.insert(u.begin(), param.begin(), param.end());
366 template <
typename I>
369 if (!nh->getParam(key, param))
return false;
371 I
min = std::numeric_limits<I>::lowest();
372 I max = std::numeric_limits<I>::max();
387 template <
typename U,
typename V>
388 void getRosInt(
const std::string& key, U &u, V default_val) {
398 template <
typename I>
399 bool getRosInt(
const std::string& key, std::vector<I> &i) {
400 std::vector<int>
param;
401 if (!nh->getParam(key, param))
return false;
404 I
min = std::numeric_limits<I>::lowest();
405 I max = std::numeric_limits<I>::max();
409 i.insert(i.begin(), param.begin(), param.end());
421 template <
typename MessageT>
422 void publish(
const MessageT& m,
const std::string& topic) {
434 return supported.count(gnss) > 0;
450 virtual void getRosParams() = 0;
456 virtual bool configureUblox() = 0;
463 virtual void initializeRosDiagnostics() = 0;
491 constexpr
static double kPollDuration = 1.0;
494 constexpr
static float kDiagnosticPeriod = 0.2;
496 constexpr
static double kFixFreqTol = 0.15;
498 constexpr
static double kFixFreqWindow = 10;
500 constexpr
static double kTimeStampStatusMin = 0;
516 bool configureUblox();
526 void initializeRosDiagnostics();
531 void printInf(
const ublox_msgs::Inf &m, uint8_t
id);
562 void processMonVer();
568 void addFirmwareInterface();
577 void addProductInterface(std::string product_category,
578 std::string ref_rov =
"");
599 float protocol_version_ = 0;
663 void initializeRosDiagnostics();
669 virtual void fixDiagnostic(
689 bool configureUblox();
711 void callbackNavPosLlh(
const ublox_msgs::NavPOSLLH& m);
719 void callbackNavVelNed(
const ublox_msgs::NavVELNED& m);
727 void callbackNavSol(
const ublox_msgs::NavSOL& m);
755 template<
typename NavPVT>
767 if(enabled[
"nav_pvt"]) {
780 sensor_msgs::NavSatFix fix;
783 uint8_t valid_time = m.VALID_DATE | m.VALID_TIME | m.VALID_FULLY_RESOLVED;
784 if (((m.valid & valid_time) == valid_time) &&
785 (m.flags2 & m.FLAGS2_CONFIRMED_AVAILABLE)) {
792 fix.header.stamp.nsec = (uint32_t)(m.nano + 1e9);
796 fix.header.stamp.nsec = (uint32_t)(m.nano);
803 fix.latitude = m.lat * 1e-7;
804 fix.longitude = m.lon * 1e-7;
805 fix.altitude = m.height * 1e-3;
807 bool fixOk = m.flags & m.FLAGS_GNSS_FIX_OK;
808 if (fixOk && m.fixType >= m.FIX_TYPE_2D) {
809 fix.status.status = fix.status.STATUS_FIX;
810 if(m.flags & m.CARRIER_PHASE_FIXED)
811 fix.status.status = fix.status.STATUS_GBAS_FIX;
814 fix.status.status = fix.status.STATUS_NO_FIX;
820 const double varH = pow(m.hAcc / 1000.0, 2);
821 const double varV = pow(m.vAcc / 1000.0, 2);
822 fix.position_covariance[0] = varH;
823 fix.position_covariance[4] = varH;
824 fix.position_covariance[8] = varV;
825 fix.position_covariance_type =
826 sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
834 nh->advertise<geometry_msgs::TwistWithCovarianceStamped>(
"fix_velocity",
836 geometry_msgs::TwistWithCovarianceStamped velocity;
837 velocity.header.stamp = fix.header.stamp;
838 velocity.header.frame_id =
frame_id;
841 velocity.twist.twist.linear.x = m.velE * 1e-3;
842 velocity.twist.twist.linear.y = m.velN * 1e-3;
843 velocity.twist.twist.linear.z = -m.velD * 1e-3;
845 const double covSpeed = pow(m.sAcc * 1e-3, 2);
847 velocity.twist.covariance[cols * 0 + 0] = covSpeed;
848 velocity.twist.covariance[cols * 1 + 1] = covSpeed;
849 velocity.twist.covariance[cols * 2 + 2] = covSpeed;
850 velocity.twist.covariance[cols * 3 + 3] = -1;
852 velocityPublisher.
publish(velocity);
858 freq_diag->diagnostic->tick(fix.header.stamp);
869 if (last_nav_pvt_.fixType ==
870 ublox_msgs::NavPVT::FIX_TYPE_DEAD_RECKONING_ONLY) {
871 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
872 stat.message =
"Dead reckoning only";
873 }
else if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_2D) {
874 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
875 stat.message =
"2D fix";
876 }
else if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_3D) {
877 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
878 stat.message =
"3D fix";
879 }
else if (last_nav_pvt_.fixType ==
880 ublox_msgs::NavPVT::FIX_TYPE_GNSS_DEAD_RECKONING_COMBINED) {
881 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
882 stat.message =
"GPS and dead reckoning combined";
883 }
else if (last_nav_pvt_.fixType ==
884 ublox_msgs::NavPVT::FIX_TYPE_TIME_ONLY) {
885 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
886 stat.message =
"Time only fix";
890 if (last_nav_pvt_.flags & ublox_msgs::NavPVT::FLAGS_DIFF_SOLN) {
891 stat.message +=
", DGNSS";
894 if (last_nav_pvt_.flags & ublox_msgs::NavPVT::CARRIER_PHASE_FLOAT) {
895 stat.message +=
", FLOAT FIX";
896 }
else if (last_nav_pvt_.flags & ublox_msgs::NavPVT::CARRIER_PHASE_FIXED) {
897 stat.message +=
", RTK FIX";
901 if (!(last_nav_pvt_.flags & ublox_msgs::NavPVT::FLAGS_GNSS_FIX_OK)) {
902 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
903 stat.message +=
", fix not ok";
906 if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_NO_FIX) {
907 stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
908 stat.message =
"No fix";
912 stat.
add(
"iTOW [ms]", last_nav_pvt_.iTOW);
913 std::ostringstream gnss_coor;
914 gnss_coor << std::fixed << std::setprecision(7);
915 gnss_coor << (last_nav_pvt_.lat * 1e-7);
916 stat.
add(
"Latitude [deg]", gnss_coor.str());
919 gnss_coor << (last_nav_pvt_.lon * 1e-7);
920 stat.
add(
"Longitude [deg]", gnss_coor.str());
921 stat.
add(
"Altitude [m]", last_nav_pvt_.height * 1e-3);
922 stat.
add(
"Height above MSL [m]", last_nav_pvt_.hMSL * 1e-3);
923 stat.
add(
"Horizontal Accuracy [m]", last_nav_pvt_.hAcc * 1e-3);
924 stat.
add(
"Vertical Accuracy [m]", last_nav_pvt_.vAcc * 1e-3);
925 stat.
add(
"# SVs used", (
int)last_nav_pvt_.numSV);
960 bool configureUblox();
1000 bool configureUblox();
1040 static constexpr
double kRtcmFreqTol = 0.15;
1041 static constexpr
int kRtcmFreqWindow = 25;
1064 void initializeRosDiagnostics();
1084 void getRosParams();
1091 bool configureUblox();
1106 ROS_WARN(
"ROS Diagnostics specific to u-blox ADR/UDR devices is %s",
1107 "unimplemented. See AdrUdrProduct class in node.h & node.cpp.");
1120 void callbackEsfMEAS(
const ublox_msgs::EsfMEAS &m);
1133 ROS_WARN(
"Functionality specific to u-blox FTS devices is %s",
1134 "unimplemented. See FtsProduct class in node.h & node.cpp.");
1171 void getRosParams();
1181 bool configureUblox();
1193 void initializeRosDiagnostics();
1203 void callbackNavSvIn(ublox_msgs::NavSVIN m);
1273 constexpr
static double kRtcmFreqMin = 1;
1275 constexpr
static double kRtcmFreqMax = 10;
1277 constexpr
static double kRtcmFreqTol = 0.1;
1279 constexpr
static int kRtcmFreqWindow = 25;
1285 void getRosParams();
1293 bool configureUblox();
1304 void initializeRosDiagnostics();
1311 void carrierPhaseDiagnostics(
1319 void callbackNavRelPosNed(
const ublox_msgs::NavRELPOSNED &m);
1347 void callbackNavRelPosNed(
const ublox_msgs::NavRELPOSNED9 &m);
1364 void getRosParams();
1370 bool configureUblox();
1383 void initializeRosDiagnostics();
1390 void callbackTimTM2(
const ublox_msgs::TimTM2 &m);
uint32_t baudrate_
UART1 baudrate.
static constexpr uint32_t kSubscribeRate
Default subscribe Rate to u-blox messages [Hz].
float fixed_pos_acc_
Fixed Position Accuracy [m].
std::map< std::string, bool > enabled
Whether or not to publish the given ublox message.
float sv_in_acc_lim_
Survey in accuracy limit [m].
RawDataStreamPa rawDataStreamPa_
raw data stream logging
boost::shared_ptr< ComponentInterface > ComponentPtr
uint8_t fmode_
Set from fix mode string.
Implements functions for Time Sync products.
Implements functions for firmware version 7.
uint8_t sbas_usage_
SBAS Usage parameter (see CfgSBAS message)
sensor_msgs::TimeReference t_ref_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
bool getRosInt(const std::string &key, I &u)
Get a integer (size 8 or 16) value from the parameter server.
uint16_t usb_out_
USB out protocol (see CfgPRT message for constants)
This abstract class represents a firmware component.
Topic diagnostics for fix / fix_velocity messages.
bool clear_bbr_
Whether to clear the flash memory during configuration.
Implements functions for raw data stream.
ublox_msgs::CfgNMEA6 cfg_nmea_
Used to configure NMEA (if set_nmea_) filled with ROS parameters.
double max_freq
Maximum allow frequency of topic.
std::vector< float > arp_position_
Antenna Reference Point Position [m] or [deg].
void publish(const boost::shared_ptr< M > &message) const
void initializeRosDiagnostics()
Adds diagnostic updaters for FTS status.
UbloxTopicDiagnostic freq_rtcm_
The RTCM topic frequency diagnostic updater.
ublox_msgs::TimTM2 timtm2
NavPVT last_nav_pvt_
The last received NavPVT message.
ROSCONSOLE_DECL void initialize()
ublox_msgs::CfgNMEA7 cfg_nmea_
Used to configure NMEA (if set_nmea_)
void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the fix diagnostics from Nav PVT message.
FixDiagnostic(std::string name, double freq_tol, int freq_window, double stamp_min)
Add a topic diagnostic to the diagnostic updater for fix topics.
bool enable_gps_
Whether or not to enable GPS.
bool enable_ppp_
Whether or not to enable PPP (advanced setting)
uint32_t sv_in_min_dur_
Measurement period used during Survey-In [s].
static constexpr uint16_t kDefaultMeasPeriod
Default measurement period for HPG devices.
ublox_msgs::CfgCFG load_
Parameters to load from non-volatile memory during configuration.
bool enable_beidou_
Whether or not to enable the BeiDuo GNSS.
Implements functions for firmware version 8.
std::string fix_mode_
Fix mode type.
std::vector< boost::shared_ptr< ComponentInterface > > components_
The u-blox node components.
Implements functions for High Precision GNSS Rover devices.
void getRosParams()
Get the FTS parameters.
double max_freq
Maximum allow frequency of topic.
Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices...
void callbackNavPvt(const NavPVT &m)
Publish a NavSatFix and TwistWithCovarianceStamped messages.
Implements functions for High Precision GNSS Reference station devices.
bool set_nmea_
Whether or not to configure the NMEA settings.
void publish(const MessageT &m, const std::string &topic)
Publish a ROS message of type MessageT.
geometry_msgs::TwistWithCovarianceStamped velocity_
The last Twist based on last_nav_vel_.
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
sensor_msgs::NavSatFix fix_
The last NavSatFix based on last_nav_pos_.
bool enable_sbas_
Whether or not to enable SBAS.
bool set_nmea_
Whether or not to configure the NMEA settings.
diagnostic_updater::HeaderlessTopicDiagnostic * diagnostic
Topic frequency diagnostic updater.
ublox_msgs::NavSVIN last_nav_svin_
The last received Nav SVIN message.
bool set_usb_
Whether to configure the USB port.
ublox_msgs::NavRELPOSNED last_rel_pos_
Last relative position (used for diagnostic updater)
uint16_t uart_in_
UART in protocol (see CfgPRT message for constants)
bool configureUblox()
Configure FTS settings.
bool svin_reset_
Whether to always reset the survey-in during configuration.
ublox_msgs::CfgDAT cfg_dat_
User-defined Datum.
uint8_t modelFromString(const std::string &model)
Determine dynamic model from human-readable string.
Implements functions for FTS products. Currently unimplemented.
bool lla_flag_
True if coordinates are in LLA, false if ECEF.
bool use_adr_
Whether or not to enable dead reckoning.
ublox_msgs::NavVELNED last_nav_vel_
The last received navigation velocity.
static constexpr uint32_t kROSQueueSize
Queue size for ROS publishers.
bool enable_galileo_
Whether or not to enable the Galileo GNSS.
bool supportsGnss(std::string gnss)
bool config_on_startup_flag_
Flag for enabling configuration on startup.
bool enable_imes_
Whether or not to enable the IMES GNSS.
uint16_t usb_tx_
USB TX Ready Pin configuration (see CfgPRT message for constants)
ublox_msgs::NavRELPOSNED9 last_rel_pos_
Last relative position (used for diagnostic updater)
bool enable_qzss_
Whether or not to enable QZSS.
std::set< std::string > supported
Which GNSS are supported by the device.
Initialization mode (before configuration)
ublox_msgs::NavPOSLLH last_nav_pos_
The last received navigation position.
void subscribe()
Subscribe to FTS messages.
uint8_t dgnss_mode_
The DGNSS mode.
ublox_gps::Gps gps
Handles communication with the U-Blox Device.
UbloxTopicDiagnostic(std::string topic, double freq_tol, int freq_window)
Add a topic diagnostic to the diagnostic updater for.
boost::shared_ptr< ros::NodeHandle > nh
Node Handle for GPS node.
void initializeRosDiagnostics()
Initialize the ROS diagnostics for the ADR/UDR device.
ublox_msgs::NavSOL last_nav_sol_
The last received num SVs used.
long toUtcSeconds(const NavPVT &msg)
Convert date/time to UTC time in seconds.
void getRosParams()
Does nothing since there are no Raw Data product specific settings.
std::vector< uint8_t > rtcm_ids
IDs of RTCM out messages to configure.
ublox_msgs::CfgCFG save_
Parameters to save to non-volatile memory after configuration.
Implements functions for firmware version 9. For now it simply re-uses the firmware version 8 class b...
void checkMin(V val, T min, std::string name)
Check that the parameter is above the minimum.
uint8_t fixModeFromString(const std::string &mode)
Determine fix mode from human-readable string.
void checkRange(V val, T min, T max, std::string name)
Check that the parameter is in the range.
uint8_t dmodel_
Set from dynamic model string.
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
bool set_nmea_
Whether or not to Configure the NMEA settings.
diagnostic_updater::TopicDiagnostic * diagnostic
Topic frequency diagnostic updater.
bool set_dat_
If true, set configure the User-Defined Datum.
std::vector< uint8_t > rtcm_rates
Rates of RTCM out messages. Size must be the same as rtcm_ids.
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.
std::vector< int8_t > arp_position_hp_
Antenna Reference Point Position High Precision [0.1 mm] or [deg * 1e-9].
uint8_t tmode3_
TMODE3 to set, such as disabled, survey-in, fixed.
sensor_msgs::TimeReference t_ref_
double rate_
The measurement rate in Hz.
boost::shared_ptr< FixDiagnostic > freq_diag
fix frequency diagnostic updater
std::string dynamic_model_
dynamic model type
ublox_msgs::CfgNMEA cfg_nmea_
Desired NMEA configuration.
This interface is used to add functionality to the main node.
std::vector< boost::shared_ptr< UbloxTopicDiagnostic > > freq_diagnostics_
Topic diagnostic updaters.
uint8_t tim_rate_
rate for TIM-TM2
Handles communication with and configuration of the u-blox device.
uint16_t uart_out_
UART out protocol (see CfgPRT message for constants)
Topic diagnostics for u-blox messages.
uint32_t qzss_sig_cfg_
The QZSS Signal configuration, see CfgGNSS message.
bool enable_glonass_
Whether or not to enable GLONASS.
std::string device_
Device port.
bool configureUblox()
Does nothing since there are no Raw Data product specific settings.
uint8_t max_sbas_
Max SBAS parameter (see CfgSBAS message)
uint16_t usb_in_
USB in protocol (see CfgPRT message for constants)
boost::shared_ptr< diagnostic_updater::Updater > updater
ROS diagnostic updater.
Implements functions for Raw Data products.
bool getRosUint(const std::string &key, U &u)
Get a unsigned integer value from the parameter server.
void add(const std::string &key, const T &val)
This class represents u-blox ROS node for all firmware and product versions.
uint8_t dr_limit_
Dead reckoning limit parameter.
bool enable_sbas_
Whether or not to enable SBAS.
double min_freq
Minimum allow frequency of topic.
double min_freq
Minimum allow frequency of topic.
static constexpr uint32_t kNavSvInfoSubscribeRate
Subscribe Rate for u-blox SV Info messages.
Implements functions for firmware version 6.
std::string frame_id
The ROS frame ID of this device.
Fixed mode (should switch to time mode almost immediately)