44 std::string
lower = model;
45 std::transform(lower.begin(), lower.end(), lower.begin(), ::tolower);
46 if(lower ==
"portable") {
47 return ublox_msgs::CfgNAV5::DYN_MODEL_PORTABLE;
48 }
else if(lower ==
"stationary") {
49 return ublox_msgs::CfgNAV5::DYN_MODEL_STATIONARY;
50 }
else if(lower ==
"pedestrian") {
51 return ublox_msgs::CfgNAV5::DYN_MODEL_PEDESTRIAN;
52 }
else if(lower ==
"automotive") {
53 return ublox_msgs::CfgNAV5::DYN_MODEL_AUTOMOTIVE;
54 }
else if(lower ==
"sea") {
55 return ublox_msgs::CfgNAV5::DYN_MODEL_SEA;
56 }
else if(lower ==
"airborne1") {
57 return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_1G;
58 }
else if(lower ==
"airborne2") {
59 return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_2G;
60 }
else if(lower ==
"airborne4") {
61 return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_4G;
62 }
else if(lower ==
"wristwatch") {
63 return ublox_msgs::CfgNAV5::DYN_MODEL_WRIST_WATCH;
64 }
else if(lower ==
"bike") {
65 return ublox_msgs::CfgNAV5::DYN_MODEL_BIKE;
68 throw std::runtime_error(
"Invalid settings: " + lower +
69 " is not a valid dynamic model.");
73 std::string
lower = mode;
74 std::transform(lower.begin(), lower.end(), lower.begin(), ::tolower);
76 return ublox_msgs::CfgNAV5::FIX_MODE_2D_ONLY;
77 }
else if (lower ==
"3d") {
78 return ublox_msgs::CfgNAV5::FIX_MODE_3D_ONLY;
79 }
else if (lower ==
"auto") {
80 return ublox_msgs::CfgNAV5::FIX_MODE_AUTO;
83 throw std::runtime_error(
"Invalid settings: " + mode +
84 " is not a valid fix mode.");
110 ROS_INFO(
"U-Blox Firmware Version: %d", ublox_version);
115 std::string ref_rov) {
116 if (product_category.compare(
"HPG") == 0 && ref_rov.compare(
"REF") == 0)
118 else if (product_category.compare(
"HPG") == 0 && ref_rov.compare(
"ROV") == 0)
120 else if (product_category.compare(
"HPG") == 0)
122 else if (product_category.compare(
"TIM") == 0)
124 else if (product_category.compare(
"ADR") == 0 ||
125 product_category.compare(
"UDR") == 0)
127 else if (product_category.compare(
"FTS") == 0)
129 else if(product_category.compare(
"SPG") != 0)
130 ROS_WARN(
"Product category %s %s from MonVER message not recognized %s",
131 product_category.c_str(), ref_rov.c_str(),
132 "options are HPG REF, HPG ROV, HPG #.#, TIM, ADR, UDR, FTS, SPG");
136 nh->param(
"device",
device_, std::string(
"/dev/ttyACM0"));
137 nh->param(
"frame_id",
frame_id, std::string(
"gps"));
148 | ublox_msgs::CfgPRT::PROTO_NMEA
149 | ublox_msgs::CfgPRT::PROTO_RTCM);
153 if (
nh->hasParam(
"usb/in") ||
nh->hasParam(
"usb/out")) {
156 throw std::runtime_error(std::string(
"usb/out is set, therefore ") +
157 "usb/in must be set");
160 throw std::runtime_error(std::string(
"usb/in is set, therefore ") +
161 "usb/out must be set");
178 nh->param(
"fix_mode",
fix_mode_, std::string(
"auto"));
182 ROS_WARN(
"Warning: PPP is enabled - this is an expert setting.");
187 throw std::runtime_error(std::string(
"Invalid settings: size of rtcm_ids") +
188 " must match size of rtcm_rates");
195 std::vector<float> shift, rot;
198 ||
nh->getParam(
"dat/shift", shift)
199 ||
nh->getParam(
"dat/rot", rot)
201 throw std::runtime_error(std::string(
"dat/set is true, therefore ") +
202 "dat/majA, dat/flat, dat/shift, dat/rot, & dat/scale must be set");
203 if(shift.size() != 3 || rot.size() != 3)
204 throw std::runtime_error(std::string(
"size of dat/shift & dat/rot ") +
233 static std::vector<uint8_t> payload(1, 1);
242 if (payload[0] > 32) {
259 ROS_DEBUG(
"Subscribing to U-Blox messages");
261 nh->param(
"publish/all",
enabled[
"all"],
false);
262 nh->param(
"inf/all",
enabled[
"inf"],
true);
272 publish<ublox_msgs::NavSTATUS>, _1,
"navstatus"),
kSubscribeRate);
277 publish<ublox_msgs::NavPOSECEF>, _1,
"navposecef"),
kSubscribeRate);
285 nh->param(
"inf/debug",
enabled[
"inf_debug"],
false);
341 if (!
nh->hasParam(
"diagnostic_period"))
345 updater->setHardwareID(
"ublox");
356 ublox_msgs::MonVER monVer;
358 throw std::runtime_error(
"Failed to poll MonVER & set relevant settings");
360 ROS_DEBUG(
"%s, HW VER: %s", monVer.swVersion.c_array(),
361 monVer.hwVersion.c_array());
363 std::vector<std::string> extension;
364 extension.reserve(monVer.extension.size());
365 for(std::size_t i = 0; i < monVer.extension.size(); ++i) {
366 ROS_DEBUG(
"%s", monVer.extension[i].field.c_array());
368 unsigned char* end = std::find(monVer.extension[i].field.begin(),
369 monVer.extension[i].field.end(),
'\0');
370 extension.push_back(std::string(monVer.extension[i].field.begin(), end));
374 for(std::size_t i = 0; i < extension.size(); ++i) {
375 std::size_t found = extension[i].find(
"PROTVER");
376 if (found != std::string::npos) {
378 extension[i].substr(8, extension[i].size()-8).c_str());
383 ROS_WARN(
"Failed to parse MonVER and determine protocol version. %s",
384 "Defaulting to firmware version 6.");
389 std::vector<std::string> strs;
390 if(extension.size() > 0)
391 boost::split(strs, extension[extension.size()-1], boost::is_any_of(
";"));
392 for(
size_t i = 0; i < strs.size(); i++)
395 for(std::size_t i = 0; i < extension.size(); ++i) {
396 std::vector<std::string> strs;
398 if(i <= extension.size() - 2) {
399 boost::split(strs, extension[i], boost::is_any_of(
"="));
400 if(strs.size() > 1) {
401 if (strs[0].compare(std::string(
"FWVER")) == 0) {
411 if(i >= extension.size() - 2) {
412 boost::split(strs, extension[i], boost::is_any_of(
";"));
413 for(
size_t i = 0; i < strs.size(); i++)
423 throw std::runtime_error(
"Failed to initialize.");
424 if (
load_.loadMask != 0) {
425 ROS_DEBUG(
"Loading u-blox configuration from memory. %u",
load_.loadMask);
427 throw std::runtime_error(std::string(
"Failed to load configuration ") +
430 ROS_DEBUG(
"Loaded I/O configuration from memory, resetting serial %s",
435 throw std::runtime_error(std::string(
"Failed to reset serial I/O") +
436 "after loading I/O configurations from device memory.");
445 std::stringstream ss;
446 ss <<
"Failed to set measurement rate to " <<
meas_rate 447 <<
"ms and navigation rate to " <<
nav_rate;
448 throw std::runtime_error(ss.str());
453 throw std::runtime_error(std::string(
"Failed to ") +
459 throw std::runtime_error(std::string(
"Failed to ") +
463 throw std::runtime_error(
"Failed to set model: " +
dynamic_model_ +
".");
465 throw std::runtime_error(
"Failed to set fix mode: " +
fix_mode_ +
".");
467 std::stringstream ss;
468 ss <<
"Failed to set dead reckoning limit: " <<
dr_limit_ <<
".";
469 throw std::runtime_error(ss.str());
472 throw std::runtime_error(
"Failed to set user-defined datum.");
479 if (
save_.saveMask != 0) {
480 ROS_DEBUG(
"Saving the u-blox configuration, mask %u, device %u",
483 ROS_ERROR(
"u-blox unable to save configuration to non-volatile memory");
485 }
catch (std::exception& e) {
486 ROS_FATAL(
"Error configuring u-blox: %s", e.what());
493 ublox_msgs::CfgINF
msg;
495 ublox_msgs::CfgINF_Block block;
496 block.protocolID = block.PROTOCOL_ID_UBX;
498 uint8_t mask = (
enabled[
"inf_error"] ? block.INF_MSG_ERROR : 0) |
499 (
enabled[
"inf_warning"] ? block.INF_MSG_WARNING : 0) |
500 (
enabled[
"inf_notice"] ? block.INF_MSG_NOTICE : 0) |
501 (
enabled[
"inf_test"] ? block.INF_MSG_TEST : 0) |
502 (
enabled[
"inf_debug"] ? block.INF_MSG_DEBUG : 0);
503 for (
int i = 0; i < block.infMsgMask.size(); i++)
504 block.infMsgMask[i] = mask;
506 msg.blocks.push_back(block);
509 if (
uart_in_ & ublox_msgs::CfgPRT::PROTO_NMEA) {
510 ublox_msgs::CfgINF_Block block;
511 block.protocolID = block.PROTOCOL_ID_NMEA;
513 for (
int i = 0; i < block.infMsgMask.size(); i++)
514 block.infMsgMask[i] = mask;
515 msg.blocks.push_back(block);
520 ROS_WARN(
"Failed to configure INF messages");
527 if (boost::regex_match(
device_, match,
528 boost::regex(
"(tcp|udp)://(.+):(\\d+)"))) {
529 std::string proto(match[1]);
530 if (proto ==
"tcp") {
531 std::string host(match[2]);
532 std::string port(match[3]);
533 ROS_INFO(
"Connecting to %s://%s:%s ...", proto.c_str(), host.c_str(),
537 throw std::runtime_error(
"Protocol '" + proto +
"' is unsupported");
558 if(
nh->param(
"raw_data",
false))
568 ROS_INFO(
"U-Blox configured successfully.");
608 nh->param(
"nmea/set", set_nmea_,
false);
610 bool compat, consider;
612 if (!
getRosUint(
"nmea/version", cfg_nmea_.version))
613 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
614 "true, therefore nmea/version must be set");
615 if (!
getRosUint(
"nmea/num_sv", cfg_nmea_.numSV))
616 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
617 "true, therefore nmea/num_sv must be set");
618 if (!
nh->getParam(
"nmea/compat", compat))
619 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
620 "true, therefore nmea/compat must be set");
621 if (!
nh->getParam(
"nmea/consider", consider))
622 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
623 "true, therefore nmea/consider must be set");
626 cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
627 cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
631 nh->param(
"nmea/filter/pos", temp,
false);
632 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
633 nh->param(
"nmea/filter/msk_pos", temp,
false);
634 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
635 nh->param(
"nmea/filter/time", temp,
false);
636 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
637 nh->param(
"nmea/filter/date", temp,
false);
638 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
639 nh->param(
"nmea/filter/sbas", temp,
false);
640 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_SBAS_FILT : 0;
641 nh->param(
"nmea/filter/track", temp,
false);
642 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
647 ROS_WARN(
"ublox_version < 7, ignoring GNSS settings");
650 throw std::runtime_error(
"Failed to configure NMEA");
676 publish<ublox_msgs::NavSVINFO>, _1,
"navsvinfo"),
689 if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_DEAD_RECKONING_ONLY) {
690 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
691 stat.message =
"Dead reckoning only";
692 }
else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_2D_FIX) {
693 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
694 stat.message =
"2D fix";
695 }
else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_3D_FIX) {
696 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
697 stat.message =
"3D fix";
698 }
else if (last_nav_sol_.gpsFix ==
699 ublox_msgs::NavSOL::GPS_GPS_DEAD_RECKONING_COMBINED) {
700 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
701 stat.message =
"GPS and dead reckoning combined";
702 }
else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_TIME_ONLY_FIX) {
703 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
704 stat.message =
"Time fix only";
707 if (!(last_nav_sol_.flags & ublox_msgs::NavSOL::FLAGS_GPS_FIX_OK)) {
708 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
709 stat.message +=
", fix not ok";
712 if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_NO_FIX) {
713 stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
714 stat.message =
"No fix";
718 stat.
add(
"iTOW [ms]", last_nav_pos_.iTOW);
719 stat.
add(
"Latitude [deg]", last_nav_pos_.lat * 1e-7);
720 stat.
add(
"Longitude [deg]", last_nav_pos_.lon * 1e-7);
721 stat.
add(
"Altitude [m]", last_nav_pos_.height * 1e-3);
722 stat.
add(
"Height above MSL [m]", last_nav_pos_.hMSL * 1e-3);
723 stat.
add(
"Horizontal Accuracy [m]", last_nav_pos_.hAcc * 1e-3);
724 stat.
add(
"Vertical Accuracy [m]", last_nav_pos_.vAcc * 1e-3);
725 stat.
add(
"# SVs used", (
int)last_nav_sol_.numSV);
738 if (m.iTOW == last_nav_vel_.iTOW)
739 fix_.header.stamp = velocity_.header.stamp;
744 fix_.latitude = m.lat * 1e-7;
745 fix_.longitude = m.lon * 1e-7;
746 fix_.altitude = m.height * 1e-3;
748 if (last_nav_sol_.gpsFix >= last_nav_sol_.GPS_2D_FIX)
749 fix_.status.status = fix_.status.STATUS_FIX;
751 fix_.status.status = fix_.status.STATUS_NO_FIX;
754 const double varH = pow(m.hAcc / 1000.0, 2);
755 const double varV = pow(m.vAcc / 1000.0, 2);
757 fix_.position_covariance[0] = varH;
758 fix_.position_covariance[4] = varH;
759 fix_.position_covariance[8] = varV;
760 fix_.position_covariance_type =
761 sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
763 fix_.status.service = fix_.status.SERVICE_GPS;
767 freq_diag->diagnostic->tick(fix_.header.stamp);
780 nh->advertise<geometry_msgs::TwistWithCovarianceStamped>(
"fix_velocity",
782 if (m.iTOW == last_nav_pos_.iTOW)
783 velocity_.header.stamp = fix_.header.stamp;
786 velocity_.header.frame_id =
frame_id;
789 velocity_.twist.twist.linear.x = m.velE / 100.0;
790 velocity_.twist.twist.linear.y = m.velN / 100.0;
791 velocity_.twist.twist.linear.z = -m.velD / 100.0;
793 const double varSpeed = pow(m.sAcc / 100.0, 2);
796 velocity_.twist.covariance[cols * 0 + 0] = varSpeed;
797 velocity_.twist.covariance[cols * 1 + 1] = varSpeed;
798 velocity_.twist.covariance[cols * 2 + 2] = varSpeed;
799 velocity_.twist.covariance[cols * 3 + 3] = -1;
801 velocityPublisher.
publish(velocity_);
824 nh->param(
"gnss/gps", enable_gps_,
true);
825 nh->param(
"gnss/glonass", enable_glonass_,
false);
826 nh->param(
"gnss/qzss", enable_qzss_,
false);
827 getRosUint(
"gnss/qzss_sig_cfg", qzss_sig_cfg_,
828 ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
832 ROS_WARN(
"gnss/gps is true, but GPS GNSS is not supported by this device");
834 ROS_WARN(
"gnss/glonass is true, but GLONASS is not %s",
835 "supported by this device");
837 ROS_WARN(
"gnss/qzss is true, but QZSS is not supported by this device");
839 ROS_WARN(
"gnss/sbas is true, but SBAS is not supported by this device");
841 if(
nh->hasParam(
"gnss/galileo"))
842 ROS_WARN(
"ublox_version < 8, ignoring Galileo GNSS Settings");
843 if(
nh->hasParam(
"gnss/beidou"))
844 ROS_WARN(
"ublox_version < 8, ignoring BeiDou Settings");
845 if(
nh->hasParam(
"gnss/imes"))
846 ROS_WARN(
"ublox_version < 8, ignoring IMES GNSS Settings");
850 + (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS;
855 nh->param(
"nmea/set", set_nmea_,
false);
857 bool compat, consider;
859 if (!
getRosUint(
"nmea/version", cfg_nmea_.nmeaVersion))
860 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
861 "true, therefore nmea/version must be set");
862 if (!
getRosUint(
"nmea/num_sv", cfg_nmea_.numSV))
863 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
864 "true, therefore nmea/num_sv must be set");
865 if (!
getRosUint(
"nmea/sv_numbering", cfg_nmea_.svNumbering))
866 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
867 "true, therefore nmea/sv_numbering must be set");
868 if (!
nh->getParam(
"nmea/compat", compat))
869 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
870 "true, therefore nmea/compat must be set");
871 if (!
nh->getParam(
"nmea/consider", consider))
872 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
873 "true, therefore nmea/consider must be set");
876 cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
877 cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
880 nh->param(
"nmea/filter/pos", temp,
false);
881 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
882 nh->param(
"nmea/filter/msk_pos", temp,
false);
883 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
884 nh->param(
"nmea/filter/time", temp,
false);
885 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
886 nh->param(
"nmea/filter/date", temp,
false);
887 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
888 nh->param(
"nmea/filter/gps_only", temp,
false);
889 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
890 nh->param(
"nmea/filter/track", temp,
false);
891 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
893 nh->param(
"nmea/gnssToFilter/gps", temp,
false);
894 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
895 nh->param(
"nmea/gnssToFilter/sbas", temp,
false);
896 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
897 nh->param(
"nmea/gnssToFilter/qzss", temp,
false);
898 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
899 nh->param(
"nmea/gnssToFilter/glonass", temp,
false);
900 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
902 getRosUint(
"nmea/main_talker_id", cfg_nmea_.mainTalkerId);
903 getRosUint(
"nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
909 ublox_msgs::CfgGNSS cfgGNSSRead;
912 ROS_DEBUG(
"Num. tracking channels in hardware: %i", cfgGNSSRead.numTrkChHw);
913 ROS_DEBUG(
"Num. tracking channels to use: %i", cfgGNSSRead.numTrkChUse);
915 throw std::runtime_error(
"Failed to read the GNSS config.");
918 ublox_msgs::CfgGNSS cfgGNSSWrite;
919 cfgGNSSWrite.numConfigBlocks = 1;
920 cfgGNSSWrite.numTrkChHw = cfgGNSSRead.numTrkChHw;
921 cfgGNSSWrite.numTrkChUse = cfgGNSSRead.numTrkChUse;
922 cfgGNSSWrite.msgVer = 0;
926 ublox_msgs::CfgGNSS_Block block;
927 block.gnssId = block.GNSS_ID_GLONASS;
928 block.resTrkCh = block.RES_TRK_CH_GLONASS;
929 block.maxTrkCh = block.MAX_TRK_CH_GLONASS;
930 block.flags = enable_glonass_ ? block.SIG_CFG_GLONASS_L1OF : 0;
931 cfgGNSSWrite.blocks.push_back(block);
933 throw std::runtime_error(std::string(
"Failed to ") +
934 ((enable_glonass_) ?
"enable" :
"disable") +
941 ublox_msgs::CfgGNSS_Block block;
942 block.gnssId = block.GNSS_ID_QZSS;
943 block.resTrkCh = block.RES_TRK_CH_QZSS;
944 block.maxTrkCh = block.MAX_TRK_CH_QZSS;
945 block.flags = enable_qzss_ ? qzss_sig_cfg_ : 0;
946 cfgGNSSWrite.blocks[0] = block;
948 throw std::runtime_error(std::string(
"Failed to ") +
949 ((enable_glonass_) ?
"enable" :
"disable") +
956 ublox_msgs::CfgGNSS_Block block;
957 block.gnssId = block.GNSS_ID_SBAS;
958 block.resTrkCh = block.RES_TRK_CH_SBAS;
959 block.maxTrkCh = block.MAX_TRK_CH_SBAS;
960 block.flags =
enable_sbas_ ? block.SIG_CFG_SBAS_L1CA : 0;
961 cfgGNSSWrite.blocks[0] = block;
963 throw std::runtime_error(std::string(
"Failed to ") +
970 throw std::runtime_error(
"Failed to configure NMEA");
988 publish<ublox_msgs::NavSVINFO>, _1,
"navsvinfo"),
1005 nh->param(
"clear_bbr", clear_bbr_,
false);
1009 nh->param(
"gnss/gps", enable_gps_,
true);
1010 nh->param(
"gnss/galileo", enable_galileo_,
false);
1011 nh->param(
"gnss/beidou", enable_beidou_,
false);
1012 nh->param(
"gnss/imes", enable_imes_,
false);
1013 nh->param(
"gnss/glonass", enable_glonass_,
false);
1014 nh->param(
"gnss/qzss", enable_qzss_,
false);
1017 getRosUint(
"gnss/qzss_sig_cfg", qzss_sig_cfg_,
1018 ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
1021 ROS_WARN(
"gnss/gps is true, but GPS GNSS is not supported by %s",
1024 ROS_WARN(
"gnss/glonass is true, but GLONASS is not supported by %s",
1027 ROS_WARN(
"gnss/galileo is true, but Galileo GNSS is not supported %s",
1030 ROS_WARN(
"gnss/beidou is true, but Beidou GNSS is not supported %s",
1033 ROS_WARN(
"gnss/imes is true, but IMES GNSS is not supported by %s",
1036 ROS_WARN(
"gnss/qzss is true, but QZSS is not supported by this device");
1038 ROS_WARN(
"gnss/sbas is true, but SBAS is not supported by this device");
1042 + (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS
1043 + (enable_beidou_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_COMPASS
1044 + (enable_galileo_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GALILEO;
1049 nh->param(
"nmea/set", set_nmea_,
false);
1051 bool compat, consider;
1052 cfg_nmea_.version = cfg_nmea_.VERSION;
1055 if (!
getRosUint(
"nmea/version", cfg_nmea_.nmeaVersion))
1056 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1057 "true, therefore nmea/version must be set");
1058 if (!
getRosUint(
"nmea/num_sv", cfg_nmea_.numSV))
1059 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1060 "true, therefore nmea/num_sv must be set");
1061 if (!
getRosUint(
"nmea/sv_numbering", cfg_nmea_.svNumbering))
1062 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1063 "true, therefore nmea/sv_numbering must be set");
1064 if (!
nh->getParam(
"nmea/compat", compat))
1065 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1066 "true, therefore nmea/compat must be set");
1067 if (!
nh->getParam(
"nmea/consider", consider))
1068 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1069 "true, therefore nmea/consider must be set");
1072 cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
1073 cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
1075 nh->param(
"nmea/limit82", temp,
false);
1076 cfg_nmea_.flags |= temp ? cfg_nmea_.FLAGS_LIMIT82 : 0;
1077 nh->param(
"nmea/high_prec", temp,
false);
1078 cfg_nmea_.flags |= temp ? cfg_nmea_.FLAGS_HIGH_PREC : 0;
1080 nh->param(
"nmea/filter/pos", temp,
false);
1081 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
1082 nh->param(
"nmea/filter/msk_pos", temp,
false);
1083 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
1084 nh->param(
"nmea/filter/time", temp,
false);
1085 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
1086 nh->param(
"nmea/filter/date", temp,
false);
1087 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
1088 nh->param(
"nmea/filter/gps_only", temp,
false);
1089 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
1090 nh->param(
"nmea/filter/track", temp,
false);
1091 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
1093 nh->param(
"nmea/gnssToFilter/gps", temp,
false);
1094 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
1095 nh->param(
"nmea/gnssToFilter/sbas", temp,
false);
1096 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
1097 nh->param(
"nmea/gnssToFilter/qzss", temp,
false);
1098 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
1099 nh->param(
"nmea/gnssToFilter/glonass", temp,
false);
1100 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
1101 nh->param(
"nmea/gnssToFilter/beidou", temp,
false);
1102 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_BEIDOU : 0;
1104 getRosUint(
"nmea/main_talker_id", cfg_nmea_.mainTalkerId);
1105 getRosUint(
"nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
1107 std::vector<uint8_t> bdsTalkerId;
1108 getRosUint(
"nmea/bds_talker_id", bdsTalkerId);
1109 cfg_nmea_.bdsTalkerId[0] = bdsTalkerId[0];
1110 cfg_nmea_.bdsTalkerId[1] = bdsTalkerId[1];
1119 ROS_ERROR(
"u-blox failed to clear flash memory");
1125 ublox_msgs::CfgGNSS cfg_gnss;
1128 ROS_DEBUG(
"Num. tracking channels in hardware: %i", cfg_gnss.numTrkChHw);
1129 ROS_DEBUG(
"Num. tracking channels to use: %i", cfg_gnss.numTrkChUse);
1131 throw std::runtime_error(
"Failed to read the GNSS config.");
1135 bool correct =
true;
1136 for (
int i = 0; i < cfg_gnss.blocks.size(); i++) {
1137 ublox_msgs::CfgGNSS_Block block = cfg_gnss.blocks[i];
1138 if (block.gnssId == block.GNSS_ID_GPS
1139 && enable_gps_ != (block.flags & block.FLAGS_ENABLE)) {
1141 cfg_gnss.blocks[i].flags =
1142 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_gps_;
1143 ROS_DEBUG(
"GPS Configuration is different");
1144 }
else if (block.gnssId == block.GNSS_ID_SBAS
1145 &&
enable_sbas_ != (block.flags & block.FLAGS_ENABLE)) {
1147 cfg_gnss.blocks[i].flags =
1148 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) |
enable_sbas_;
1149 ROS_DEBUG(
"SBAS Configuration is different");
1150 }
else if (block.gnssId == block.GNSS_ID_GALILEO
1151 && enable_galileo_ != (block.flags & block.FLAGS_ENABLE)) {
1153 cfg_gnss.blocks[i].flags =
1154 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_galileo_;
1155 ROS_DEBUG(
"Galileo GNSS Configuration is different");
1156 }
else if (block.gnssId == block.GNSS_ID_BEIDOU
1157 && enable_beidou_ != (block.flags & block.FLAGS_ENABLE)) {
1159 cfg_gnss.blocks[i].flags =
1160 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_beidou_;
1161 ROS_DEBUG(
"BeiDou Configuration is different");
1162 }
else if (block.gnssId == block.GNSS_ID_IMES
1163 && enable_imes_ != (block.flags & block.FLAGS_ENABLE)) {
1165 cfg_gnss.blocks[i].flags =
1166 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_imes_;
1167 }
else if (block.gnssId == block.GNSS_ID_QZSS
1168 && (enable_qzss_ != (block.flags & block.FLAGS_ENABLE)
1170 && qzss_sig_cfg_ != (block.flags & block.FLAGS_SIG_CFG_MASK)))) {
1171 ROS_DEBUG(
"QZSS Configuration is different %u, %u",
1172 block.flags & block.FLAGS_ENABLE,
1175 ROS_DEBUG(
"QZSS Configuration: %u", block.flags);
1176 cfg_gnss.blocks[i].flags =
1177 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_qzss_;
1178 ROS_DEBUG(
"QZSS Configuration: %u", cfg_gnss.blocks[i].flags);
1181 cfg_gnss.blocks[i].flags |= qzss_sig_cfg_;
1182 }
else if (block.gnssId == block.GNSS_ID_GLONASS
1183 && enable_glonass_ != (block.flags & block.FLAGS_ENABLE)) {
1185 cfg_gnss.blocks[i].flags =
1186 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_glonass_;
1187 ROS_DEBUG(
"GLONASS Configuration is different");
1194 ROS_DEBUG(
"U-Blox GNSS configuration is correct. GNSS not re-configured.");
1195 else if (!
gps.
configGnss(cfg_gnss, boost::posix_time::seconds(15)))
1196 throw std::runtime_error(std::string(
"Failed to cold reset device ") +
1197 "after configuring GNSS");
1203 throw std::runtime_error(
"Failed to configure NMEA");
1239 nh->param(
"publish/rxm/all",
enabled[
"rxm"],
true);
1292 if(nav_rate_hz != 1)
1293 ROS_WARN(
"Nav Rate recommended to be 1 Hz");
1298 throw std::runtime_error(std::string(
"Failed to ")
1299 + (
use_adr_ ?
"enable" :
"disable") +
"use_adr");
1304 nh->param(
"publish/esf/all",
enabled[
"esf"],
true);
1337 publish<ublox_msgs::EsfSTATUS>, _1,
"esfstatus"),
kSubscribeRate);
1340 nh->param(
"publish/hnr/pvt",
enabled[
"hnr_pvt"],
true);
1351 nh->advertise<sensor_msgs::TimeReference>(
"interrupt_time",
kROSQueueSize);
1356 static const float deg_per_sec = pow(2, -12);
1357 static const float m_per_sec_sq = pow(2, -10);
1358 static const float deg_c = 1e-2;
1360 std::vector<uint32_t> imu_data = m.data;
1361 for (
int i=0; i < imu_data.size(); i++){
1362 unsigned int data_type = imu_data[i] >> 24;
1363 int32_t data_value =
static_cast<int32_t
>(imu_data[i] << 8);
1366 imu_.orientation_covariance[0] = -1;
1367 imu_.linear_acceleration_covariance[0] = -1;
1368 imu_.angular_velocity_covariance[0] = -1;
1370 if (data_type == 14) {
1371 imu_.angular_velocity.x = data_value * deg_per_sec;
1372 }
else if (data_type == 16) {
1373 imu_.linear_acceleration.x = data_value * m_per_sec_sq;
1374 }
else if (data_type == 13) {
1375 imu_.angular_velocity.y = data_value * deg_per_sec;
1376 }
else if (data_type == 17) {
1377 imu_.linear_acceleration.y = data_value * m_per_sec_sq;
1378 }
else if (data_type == 5) {
1379 imu_.angular_velocity.z = data_value * deg_per_sec;
1380 }
else if (data_type == 18) {
1381 imu_.linear_acceleration.z = data_value * m_per_sec_sq;
1382 }
else if (data_type == 12) {
1385 ROS_INFO(
"data_type: %u", data_type);
1386 ROS_INFO(
"data_value: %u", data_value);
1403 time_ref_pub.publish(
t_ref_);
1416 ROS_WARN(
"For HPG Ref devices, nav_rate should be exactly 1 Hz.");
1419 throw std::runtime_error(
"Invalid settings: TMODE3 must be set");
1421 if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_FIXED) {
1422 if(!
nh->getParam(
"arp/position", arp_position_))
1423 throw std::runtime_error(std::string(
"Invalid settings: arp/position ")
1424 +
"must be set if TMODE3 is fixed");
1425 if(!
getRosInt(
"arp/position_hp", arp_position_hp_))
1426 throw std::runtime_error(std::string(
"Invalid settings: arp/position_hp ")
1427 +
"must be set if TMODE3 is fixed");
1428 if(!
nh->getParam(
"arp/acc", fixed_pos_acc_))
1429 throw std::runtime_error(std::string(
"Invalid settings: arp/acc ")
1430 +
"must be set if TMODE3 is fixed");
1431 if(!
nh->getParam(
"arp/lla_flag", lla_flag_)) {
1432 ROS_WARN(
"arp/lla_flag param not set, assuming ARP coordinates are %s",
1436 }
else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_SURVEY_IN) {
1437 nh->param(
"sv_in/reset", svin_reset_,
true);
1438 if(!
getRosUint(
"sv_in/min_dur", sv_in_min_dur_))
1439 throw std::runtime_error(std::string(
"Invalid settings: sv_in/min_dur ")
1440 +
"must be set if TMODE3 is survey-in");
1441 if(!
nh->getParam(
"sv_in/acc_lim", sv_in_acc_lim_))
1442 throw std::runtime_error(std::string(
"Invalid settings: sv_in/acc_lim ")
1443 +
"must be set if TMODE3 is survey-in");
1444 }
else if(tmode3_ != ublox_msgs::CfgTMODE3::FLAGS_MODE_DISABLED) {
1445 throw std::runtime_error(std::string(
"tmode3 param invalid. See CfgTMODE3")
1446 +
" flag constants for possible values.");
1453 if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_DISABLED) {
1455 throw std::runtime_error(
"Failed to disable TMODE3.");
1457 }
else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_FIXED) {
1460 throw std::runtime_error(
"Failed to set TMODE3 to fixed.");
1462 throw std::runtime_error(
"Failed to set RTCM rates");
1464 }
else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_SURVEY_IN) {
1466 ublox_msgs::NavSVIN nav_svin;
1468 throw std::runtime_error(std::string(
"Failed to poll NavSVIN while") +
1469 " configuring survey-in");
1471 if(nav_svin.active) {
1476 if(nav_svin.valid) {
1480 ublox_msgs::NavPVT nav_pvt;
1482 throw std::runtime_error(std::string(
"Failed to poll NavPVT while") +
1483 " configuring survey-in");
1485 if (nav_pvt.fixType == nav_pvt.FIX_TYPE_TIME_ONLY
1486 && nav_pvt.flags & nav_pvt.FLAGS_GNSS_FIX_OK) {
1495 if(1000 % meas_rate_temp != 0)
1498 if(!
gps.
configRate(meas_rate_temp, (
int) 1000 / meas_rate_temp))
1499 throw std::runtime_error(std::string(
"Failed to set nav rate to 1 Hz") +
1500 "before setting TMODE3 to survey-in.");
1503 ROS_ERROR(
"Failed to disable TMODE3 before setting to survey-in.");
1508 throw std::runtime_error(
"Failed to set TMODE3 to survey-in.");
1531 if(!m.active && m.valid && mode_ == SURVEY_IN) {
1539 ROS_INFO(
"Setting mode (internal state) to Time Mode");
1549 ROS_ERROR(
"Failed to configure RTCM IDs");
1562 if (mode_ == INIT) {
1563 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1564 stat.message =
"Not configured";
1565 }
else if (mode_ == DISABLED){
1566 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1567 stat.message =
"Disabled";
1568 }
else if (mode_ == SURVEY_IN) {
1569 if (!last_nav_svin_.active && !last_nav_svin_.valid) {
1570 stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
1571 stat.message =
"Survey-In inactive and invalid";
1572 }
else if (last_nav_svin_.active && !last_nav_svin_.valid) {
1573 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1574 stat.message =
"Survey-In active but invalid";
1575 }
else if (!last_nav_svin_.active && last_nav_svin_.valid) {
1576 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1577 stat.message =
"Survey-In complete";
1578 }
else if (last_nav_svin_.active && last_nav_svin_.valid) {
1579 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1580 stat.message =
"Survey-In active and valid";
1583 stat.
add(
"iTOW [ms]", last_nav_svin_.iTOW);
1584 stat.
add(
"Duration [s]", last_nav_svin_.dur);
1585 stat.
add(
"# observations", last_nav_svin_.obs);
1586 stat.
add(
"Mean X [m]", last_nav_svin_.meanX * 1e-2);
1587 stat.
add(
"Mean Y [m]", last_nav_svin_.meanY * 1e-2);
1588 stat.
add(
"Mean Z [m]", last_nav_svin_.meanZ * 1e-2);
1589 stat.
add(
"Mean X HP [m]", last_nav_svin_.meanXHP * 1e-4);
1590 stat.
add(
"Mean Y HP [m]", last_nav_svin_.meanYHP * 1e-4);
1591 stat.
add(
"Mean Z HP [m]", last_nav_svin_.meanZHP * 1e-4);
1592 stat.
add(
"Mean Accuracy [m]", last_nav_svin_.meanAcc * 1e-4);
1593 }
else if(mode_ == FIXED) {
1594 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1595 stat.message =
"Fixed Position";
1596 }
else if(mode_ == TIME) {
1597 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1598 stat.message =
"Time";
1608 ublox_msgs::CfgDGNSS::DGNSS_MODE_RTK_FIXED);
1614 throw std::runtime_error(std::string(
"Failed to Configure DGNSS"));
1620 nh->param(
"publish/nav/relposned",
enabled[
"nav_relposned"],
enabled[
"nav"]);
1628 kRtcmFreqMin, kRtcmFreqMax,
1629 kRtcmFreqTol, kRtcmFreqWindow);
1630 updater->add(
"Carrier Phase Solution",
this,
1637 uint32_t carr_soln = last_rel_pos_.flags & last_rel_pos_.FLAGS_CARR_SOLN_MASK;
1638 stat.
add(
"iTow", last_rel_pos_.iTow);
1639 if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_NONE ||
1640 !(last_rel_pos_.flags & last_rel_pos_.FLAGS_DIFF_SOLN &&
1641 last_rel_pos_.flags & last_rel_pos_.FLAGS_REL_POS_VALID)) {
1642 stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
1643 stat.message =
"None";
1645 if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_FLOAT) {
1646 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1647 stat.message =
"Float";
1648 }
else if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_FIXED) {
1649 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1650 stat.message =
"Fixed";
1652 stat.
add(
"Ref Station ID", last_rel_pos_.refStationId);
1654 double rel_pos_n = (last_rel_pos_.relPosN
1655 + (last_rel_pos_.relPosHPN * 1e-2)) * 1e-2;
1656 double rel_pos_e = (last_rel_pos_.relPosE
1657 + (last_rel_pos_.relPosHPE * 1e-2)) * 1e-2;
1658 double rel_pos_d = (last_rel_pos_.relPosD
1659 + (last_rel_pos_.relPosHPD * 1e-2)) * 1e-2;
1660 stat.
add(
"Relative Position N [m]", rel_pos_n);
1661 stat.
add(
"Relative Accuracy N [m]", last_rel_pos_.accN * 1e-4);
1662 stat.
add(
"Relative Position E [m]", rel_pos_e);
1663 stat.
add(
"Relative Accuracy E [m]", last_rel_pos_.accE * 1e-4);
1664 stat.
add(
"Relative Position D [m]", rel_pos_d);
1665 stat.
add(
"Relative Accuracy D [m]", last_rel_pos_.accD * 1e-4);
1670 if (
enabled[
"nav_relposned"]) {
1672 nh->advertise<ublox_msgs::NavRELPOSNED>(
"navrelposned",
kROSQueueSize);
1686 nh->param(
"publish/nav/relposned",
enabled[
"nav_relposned"],
enabled[
"nav"]);
1696 if (
enabled[
"nav_relposned"]) {
1698 nh->advertise<ublox_msgs::NavRELPOSNED9>(
"navrelposned",
kROSQueueSize);
1709 imu_.linear_acceleration_covariance[0] = -1;
1710 imu_.angular_velocity_covariance[0] = -1;
1714 double heading = - (
static_cast<double>(m.relPosHeading) * 1e-5 / 180.0 * M_PI) - M_PI_2;
1716 orientation.
setRPY(0, 0, heading);
1717 imu_.orientation.x = orientation[0];
1718 imu_.orientation.y = orientation[1];
1719 imu_.orientation.z = orientation[2];
1720 imu_.orientation.w = orientation[3];
1721 imu_.orientation_covariance[0] = 1000.0;
1722 imu_.orientation_covariance[4] = 1000.0;
1723 imu_.orientation_covariance[8] = 1000.0;
1725 if (m.flags & ublox_msgs::NavRELPOSNED9::FLAGS_REL_POS_HEAD_VALID)
1727 imu_.orientation_covariance[8] = pow(m.accHeading * 1e-5 / 180.0 * M_PI, 2);
1747 throw std::runtime_error(std::string(
"Failed to Configure TIM Product to UTC Time"));
1750 throw std::runtime_error(std::string(
"Failed to Configure TIM Product"));
1764 ROS_INFO(
"Subscribed to TIM-TM2 messages on topic tim/tm2");
1785 nh->advertise<sensor_msgs::TimeReference>(
"interrupt_time",
kROSQueueSize);
1788 t_ref_.header.seq = m.risingEdgeCount;
1792 t_ref_.time_ref =
ros::Time((m.wnR * 604800 + m.towMsR / 1000), (m.towMsR % 1000) * 1000000 + m.towSubMsR);
1794 std::ostringstream src;
1795 src <<
"TIM" << int(m.ch);
1796 t_ref_.source = src.str();
1802 time_ref_pub.publish(
t_ref_);
uint32_t baudrate_
UART1 baudrate.
int debug
Used to determine which debug messages to display.
bool isConfigured() const
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.
static constexpr uint32_t kSubscribeRate
Default subscribe Rate to u-blox messages [Hz].
void subscribe()
Subscribe to Raw Data Product messages and set up ROS publishers.
std::map< std::string, bool > enabled
Whether or not to publish the given ublox message.
void close()
Closes the I/O port, and initiates save on shutdown procedure if enabled.
RawDataStreamPa rawDataStreamPa_
raw data stream logging
boost::shared_ptr< ComponentInterface > ComponentPtr
uint8_t fmode_
Set from fix mode string.
static constexpr float kDiagnosticPeriod
[s] 5Hz diagnostic period
bool configureUblox()
Configure rover settings.
bool poll(ConfigT &message, const std::vector< uint8_t > &payload=std::vector< uint8_t >(), const boost::posix_time::time_duration &timeout=default_timeout_)
void processMonVer()
Process the MonVer message and add firmware and product components.
void subscribe()
Subscribe to all requested u-blox messages.
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 getRosInt(const std::string &key, I &u)
Get a integer (size 8 or 16) value from the parameter server.
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.
uint16_t usb_out_
USB out protocol (see CfgPRT message for constants)
bool configureUblox()
Configure GNSS individually. Only configures GLONASS.
Topic diagnostics for fix / fix_velocity messages.
static constexpr double kPollDuration
how often (in seconds) to call poll messages
static constexpr double kFixFreqTol
Tolerance for Fix topic frequency as percentage of target frequency.
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
void initializeRosDiagnostics()
Adds diagnostic updaters for Time Sync status.
void publish(const boost::shared_ptr< M > &message) const
void subscribe()
Subscribe to Rover messages, such as NavRELPOSNED.
void subscribe()
Subscribe to ADR/UDR messages.
void ubloxCallback(const unsigned char *data, const std::size_t size)
Callback function which handles raw data.
void initializeRosDiagnostics()
Add diagnostic updaters for the TMODE3 status.
void subscribe()
Subscribe to messages which are not generic to all firmware.
virtual void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)=0
Handle to send fix status to ROS diagnostics.
bool setTimeMode()
Set the device mode to time mode (internal state variable).
void pollMessages(const ros::TimerEvent &event)
Poll messages from the U-Blox device.
void subscribe()
Subscribe to Time Sync messages.
bool setUseAdr(bool enable, float protocol_version)
Enable or disable ADR (automotive dead reckoning).
bool enable_ppp_
Whether or not to enable PPP (advanced setting)
bool setFixMode(uint8_t mode)
Set the device fix mode.
void getRosParams()
Get the node parameters from the ROS Parameter Server.
static constexpr uint16_t kDefaultMeasPeriod
Default measurement period for HPG devices.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ublox_msgs::CfgCFG load_
Parameters to load from non-volatile memory during configuration.
bool configureUblox()
Configure Time Sync settings.
static const uint8_t DEBUG
bool configureUblox()
Prints a warning, GNSS configuration not available in this version.
bool configRate(uint16_t meas_rate, uint16_t nav_rate)
Configure the device navigation and measurement rate settings.
void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED &m)
Set the last received message and call rover diagnostic updater.
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.
bool configureUblox()
Configure the u-blox Reference Station settings.
bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas)
Configure the SBAS settings.
Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices...
void callbackNavPvt(const NavPVT &m)
Publish a NavSatFix and TwistWithCovarianceStamped messages.
bool setTimtm2(uint8_t rate)
Enable or disable TIM-TM2 (time mark message).
Implements functions for High Precision GNSS Reference station devices.
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
UbloxNode()
Initialize and run the u-blox node.
bool disableTmode3()
Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices...
bool set_usb_
Whether to configure the USB port.
static const uint8_t TEST
void addFirmwareInterface()
Add the interface for firmware specific configuration, subscribers, & diagnostics. This assumes the protocol_version_ has been set.
uint16_t uart_in_
UART in protocol (see CfgPRT message for constants)
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 configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit)
Set the TMODE3 settings to survey-in.
bool use_adr_
Whether or not to enable dead reckoning.
ROSCPP_DECL void spin(Spinner &spinner)
void reset(const boost::posix_time::time_duration &wait)
Reset I/O communications.
void initializeSerial(std::string port, unsigned int baudrate, uint16_t uart_in, uint16_t uart_out)
Initialize the Serial I/O port.
static constexpr uint32_t kROSQueueSize
Queue size for ROS publishers.
void initialize(void)
Initializes raw data streams If storing to file is enabled, the filename is created and the correspon...
static const uint8_t NOTICE
bool supportsGnss(std::string gnss)
bool config_on_startup_flag_
Flag for enabling configuration on startup.
uint16_t usb_tx_
USB TX Ready Pin configuration (see CfgPRT message for constants)
void callbackNavSol(const ublox_msgs::NavSOL &m)
Update the number of SVs used for the fix.
void getRosParams()
Get the ROS parameters specific to the Rover configuration.
void subscribe()
Subscribe to u-blox Reference Station messages.
void callbackEsfMEAS(const ublox_msgs::EsfMEAS &m)
void getRosParams()
Get the Time Sync parameters.
std::set< std::string > supported
Which GNSS are supported by the device.
void subscribe()
Subscribe to Rover messages, such as NavRELPOSNED.
void subscribe()
Subscribe to u-blox messages which are not generic to all firmware versions.
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
void setRawDataCallback(const Worker::Callback &callback)
Set the callback function which handles raw data.
ublox_gps::Gps gps
Handles communication with the U-Blox Device.
bool setDgnss(uint8_t mode)
Set the DGNSS mode (see CfgDGNSS message for details).
void setConfigOnStartup(const bool config_on_startup)
Set the internal flag for enabling or disabling the initial configurations.
void initializeRosDiagnostics()
Add the fix diagnostics to the updater.
void initializeRosDiagnostics()
Initialize the diagnostic updater and add the fix diagnostic.
boost::shared_ptr< ros::NodeHandle > nh
Node Handle for GPS node.
bool setPpp(bool enable, float protocol_version)
Enable or disable PPP (precise-point-positioning).
bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the USB Port.
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.
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.
void callbackNavVelNed(const ublox_msgs::NavVELNED &m)
Update the last known velocity.
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.
#define ROS_WARN_STREAM(args)
void getRosParams()
Sets the fix status service type to GPS.
bool set_dat_
If true, set configure the User-Defined Datum.
#define ROS_DEBUG_STREAM(args)
std::vector< uint8_t > rtcm_rates
Rates of RTCM out messages. Size must be the same as rtcm_ids.
bool setDeadReckonLimit(uint8_t limit)
Set the dead reckoning time limit.
static constexpr double kTimeStampStatusMin
Minimum Time Stamp Status for fix frequency diagnostic.
float protocol_version_
Determined From Mon VER.
AdrUdrProduct(float protocol_version)
void callbackTimTM2(const ublox_msgs::TimTM2 &m)
void callbackNavPosLlh(const ublox_msgs::NavPOSLLH &m)
Publish the fix and call the fix diagnostic updater.
double rate_
The measurement rate in Hz.
boost::shared_ptr< FixDiagnostic > freq_diag
fix frequency diagnostic updater
std::string dynamic_model_
dynamic model type
void setSaveOnShutdown(bool save_on_shutdown)
If called, when the node shuts down, it will send a command to save the flash memory.
static const uint8_t WARNING
void subscribe(typename CallbackHandler_< T >::Callback callback, unsigned int rate)
Configure the U-Blox send rate of the message & subscribe to the given message.
bool isInitialized() const
#define ROS_INFO_STREAM(args)
void initialize()
Initialize the U-Blox node. Configure the U-Blox and subscribe to messages.
uint16_t uart_out_
UART out protocol (see CfgPRT message for constants)
void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED9 &m)
Set the last received message and call rover diagnostic updater.
void tmode3Diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the TMODE3 diagnostics.
Topic diagnostics for u-blox messages.
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 ...
bool configureUblox()
Configure settings specific to firmware 8 based on ROS parameters.
int main(int argc, char **argv)
bool isEnabled(void)
Returns the if raw data streaming is enabled.
void shutdown()
Shutdown the node. Closes the serial port.
std::string device_
Device port.
uint8_t max_sbas_
Max SBAS parameter (see CfgSBAS message)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
uint16_t usb_in_
USB in protocol (see CfgPRT message for constants)
void getRosParams()
Get the ADR/UDR parameters.
boost::shared_ptr< diagnostic_updater::Updater > updater
ROS diagnostic updater.
void configureInf()
Configure INF messages, call after subscribe.
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.
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
void initializeRosDiagnostics()
Adds frequency diagnostics for RTCM topics.
uint8_t dr_limit_
Dead reckoning limit parameter.
#define ROS_ERROR_STREAM(args)
void initializeRosDiagnostics()
Add diagnostic updaters for rover GNSS status, including status of RTCM messages. ...
bool enable_sbas_
Whether or not to enable SBAS.
static constexpr double kFixFreqWindow
Window [num messages] for Fix Frequency Diagnostic.
void getRosParams(void)
Get the raw data stream parameters.
bool configureUblox()
Configure the device based on ROS parameters.
void carrierPhaseDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the rover diagnostics, including the carrier phase solution status (float or fixed)...
void getRosParams()
Get the ROS parameters specific to firmware version 8.
void getRosParams()
Get the parameters specific to firmware version 7.
static const uint8_t ERROR
void subscribe()
Subscribe to NavPVT, RxmRAW, and RxmSFRB messages.
void callbackNavSvIn(ublox_msgs::NavSVIN m)
Update the last received NavSVIN message and call diagnostic updater.
static constexpr uint32_t kNavSvInfoSubscribeRate
Subscribe Rate for u-blox SV Info messages.
#define ROSCONSOLE_DEFAULT_NAME
void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Updates fix diagnostic from NavPOSLLH, NavVELNED, and NavSOL messages.
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 configureUblox()
Configure ADR/UDR settings.
bool configure(const ConfigT &message, bool wait=true)
Send the given configuration message.
Implements functions for firmware version 6.
static constexpr int kResetWait
How long to wait during I/O reset [s].
bool setDynamicModel(uint8_t model)
Set the device dynamic model.
bool clearBbr()
Send a message to the receiver to delete the BBR data stored in flash.
void addProductInterface(std::string product_category, std::string ref_rov="")
Add the interface which is used for product category configuration, subscribers, & diagnostics...
void initializeTcp(std::string host, std::string port)
Initialize TCP I/O.
void getRosParams()
Get the ROS parameters specific to the Reference Station configuration.
std::string frame_id
The ROS frame ID of this device.
bool setUTCtime()
Configure the U-Blox to UTC time.