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(
"HDG") == 0)
124 else if (product_category.compare(
"TIM") == 0)
126 else if (product_category.compare(
"ADR") == 0 ||
127 product_category.compare(
"UDR") == 0 ||
128 product_category.compare(
"LAP") == 0)
130 else if (product_category.compare(
"FTS") == 0)
132 else if(product_category.compare(
"SPG") != 0)
133 ROS_WARN(
"Product category %s %s from MonVER message not recognized %s",
134 product_category.c_str(), ref_rov.c_str(),
135 "options are HPG REF, HPG ROV, HPG #.#, HDG #.#, TIM, ADR, UDR, LAP, FTS, SPG");
139 nh->param(
"device",
device_, std::string(
"/dev/ttyACM0"));
140 nh->param(
"frame_id",
frame_id, std::string(
"gps"));
151 | ublox_msgs::CfgPRT::PROTO_NMEA
152 | ublox_msgs::CfgPRT::PROTO_RTCM);
156 if (
nh->hasParam(
"usb/in") ||
nh->hasParam(
"usb/out")) {
159 throw std::runtime_error(std::string(
"usb/out is set, therefore ") +
160 "usb/in must be set");
163 throw std::runtime_error(std::string(
"usb/in is set, therefore ") +
164 "usb/out must be set");
181 nh->param(
"fix_mode",
fix_mode_, std::string(
"auto"));
185 ROS_WARN(
"Warning: PPP is enabled - this is an expert setting.");
190 throw std::runtime_error(std::string(
"Invalid settings: size of rtcm_ids") +
191 " must match size of rtcm_rates");
198 std::vector<float> shift, rot;
201 ||
nh->getParam(
"dat/shift", shift)
202 ||
nh->getParam(
"dat/rot", rot)
204 throw std::runtime_error(std::string(
"dat/set is true, therefore ") +
205 "dat/majA, dat/flat, dat/shift, dat/rot, & dat/scale must be set");
206 if(shift.size() != 3 || rot.size() != 3)
207 throw std::runtime_error(std::string(
"size of dat/shift & dat/rot ") +
237 gps.
poll(ublox_msgs::MonVER::CLASS_ID, ublox_msgs::MonVER::MESSAGE_ID);
241 static std::vector<uint8_t> payload(1, 1);
250 if (payload[0] > 32) {
267 ROS_DEBUG(
"Subscribing to U-Blox messages");
269 nh->param(
"publish/all",
enabled[
"all"],
false);
270 nh->param(
"inf/all",
enabled[
"inf"],
true);
280 publish<ublox_msgs::NavSTATUS>, _1,
"navstatus"),
kSubscribeRate);
285 publish<ublox_msgs::NavPOSECEF>, _1,
"navposecef"),
kSubscribeRate);
292 nh->param(
"publish/nmea",
enabled[
"nmea"],
false);
297 nh->param(
"inf/debug",
enabled[
"inf_debug"],
false);
353 if (!
nh->hasParam(
"diagnostic_period"))
357 updater->setHardwareID(
"ublox");
368 ublox_msgs::MonVER monVer;
370 throw std::runtime_error(
"Failed to poll MonVER & set relevant settings");
372 ROS_DEBUG(
"%s, HW VER: %s", monVer.swVersion.c_array(),
373 monVer.hwVersion.c_array());
375 std::vector<std::string> extension;
376 extension.reserve(monVer.extension.size());
377 for(std::size_t i = 0; i < monVer.extension.size(); ++i) {
378 ROS_DEBUG(
"%s", monVer.extension[i].field.c_array());
380 unsigned char* end = std::find(monVer.extension[i].field.begin(),
381 monVer.extension[i].field.end(),
'\0');
382 extension.push_back(std::string(monVer.extension[i].field.begin(), end));
386 for(std::size_t i = 0; i < extension.size(); ++i) {
387 std::size_t found = extension[i].find(
"PROTVER");
388 if (found != std::string::npos) {
390 extension[i].substr(8, extension[i].size()-8).c_str());
395 ROS_WARN(
"Failed to parse MonVER and determine protocol version. %s",
396 "Defaulting to firmware version 6.");
401 std::vector<std::string> strs;
402 if(extension.size() > 0)
403 boost::split(strs, extension[extension.size()-1], boost::is_any_of(
";"));
404 for(
size_t i = 0; i < strs.size(); i++)
407 for(std::size_t i = 0; i < extension.size(); ++i) {
408 std::vector<std::string> strs;
410 if(i <= extension.size() - 2) {
411 boost::split(strs, extension[i], boost::is_any_of(
"="));
412 if(strs.size() > 1) {
413 if (strs[0].compare(std::string(
"FWVER")) == 0) {
423 if(i >= extension.size() - 2) {
424 boost::split(strs, extension[i], boost::is_any_of(
";"));
425 for(
size_t i = 0; i < strs.size(); i++)
435 throw std::runtime_error(
"Failed to initialize.");
436 if (
load_.loadMask != 0) {
437 ROS_DEBUG(
"Loading u-blox configuration from memory. %u",
load_.loadMask);
439 throw std::runtime_error(std::string(
"Failed to load configuration ") +
442 ROS_DEBUG(
"Loaded I/O configuration from memory, resetting serial %s",
447 throw std::runtime_error(std::string(
"Failed to reset serial I/O") +
448 "after loading I/O configurations from device memory.");
457 std::stringstream ss;
458 ss <<
"Failed to set measurement rate to " <<
meas_rate 459 <<
"ms and navigation rate to " <<
nav_rate;
460 throw std::runtime_error(ss.str());
465 throw std::runtime_error(std::string(
"Failed to ") +
471 throw std::runtime_error(std::string(
"Failed to ") +
475 throw std::runtime_error(
"Failed to set model: " +
dynamic_model_ +
".");
477 throw std::runtime_error(
"Failed to set fix mode: " +
fix_mode_ +
".");
479 std::stringstream ss;
480 ss <<
"Failed to set dead reckoning limit: " <<
dr_limit_ <<
".";
481 throw std::runtime_error(ss.str());
484 throw std::runtime_error(
"Failed to set user-defined datum.");
491 if (
save_.saveMask != 0) {
492 ROS_DEBUG(
"Saving the u-blox configuration, mask %u, device %u",
495 ROS_ERROR(
"u-blox unable to save configuration to non-volatile memory");
497 }
catch (std::exception& e) {
498 ROS_FATAL(
"Error configuring u-blox: %s", e.what());
505 ublox_msgs::CfgINF
msg;
507 ublox_msgs::CfgINF_Block block;
508 block.protocolID = block.PROTOCOL_ID_UBX;
510 uint8_t mask = (
enabled[
"inf_error"] ? block.INF_MSG_ERROR : 0) |
511 (
enabled[
"inf_warning"] ? block.INF_MSG_WARNING : 0) |
512 (
enabled[
"inf_notice"] ? block.INF_MSG_NOTICE : 0) |
513 (
enabled[
"inf_test"] ? block.INF_MSG_TEST : 0) |
514 (
enabled[
"inf_debug"] ? block.INF_MSG_DEBUG : 0);
515 for (
int i = 0; i < block.infMsgMask.size(); i++)
516 block.infMsgMask[i] = mask;
518 msg.blocks.push_back(block);
521 if (
uart_in_ & ublox_msgs::CfgPRT::PROTO_NMEA) {
522 ublox_msgs::CfgINF_Block block;
523 block.protocolID = block.PROTOCOL_ID_NMEA;
525 for (
int i = 0; i < block.infMsgMask.size(); i++)
526 block.infMsgMask[i] = mask;
527 msg.blocks.push_back(block);
532 ROS_WARN(
"Failed to configure INF messages");
539 if (boost::regex_match(
device_, match,
540 boost::regex(
"(tcp|udp)://(.+):(\\d+)"))) {
541 std::string proto(match[1]);
542 if (proto ==
"tcp") {
543 std::string host(match[2]);
544 std::string port(match[3]);
545 ROS_INFO(
"Connecting to %s://%s:%s ...", proto.c_str(), host.c_str(),
548 }
else if (proto ==
"udp") {
549 std::string host(match[2]);
550 std::string port(match[3]);
551 ROS_INFO(
"Connecting to %s://%s:%s ...", proto.c_str(), host.c_str(),
555 throw std::runtime_error(
"Protocol '" + proto +
"' is unsupported");
576 if(
nh->param(
"raw_data",
false))
586 ROS_INFO(
"U-Blox configured successfully.");
593 if (
device_.substr(0, 6) ==
"udp://") {
634 nh->param(
"nmea/set", set_nmea_,
false);
636 bool compat, consider;
638 if (!
getRosUint(
"nmea/version", cfg_nmea_.version))
639 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
640 "true, therefore nmea/version must be set");
641 if (!
getRosUint(
"nmea/num_sv", cfg_nmea_.numSV))
642 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
643 "true, therefore nmea/num_sv must be set");
644 if (!
nh->getParam(
"nmea/compat", compat))
645 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
646 "true, therefore nmea/compat must be set");
647 if (!
nh->getParam(
"nmea/consider", consider))
648 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
649 "true, therefore nmea/consider must be set");
652 cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
653 cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
657 nh->param(
"nmea/filter/pos", temp,
false);
658 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
659 nh->param(
"nmea/filter/msk_pos", temp,
false);
660 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
661 nh->param(
"nmea/filter/time", temp,
false);
662 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
663 nh->param(
"nmea/filter/date", temp,
false);
664 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
665 nh->param(
"nmea/filter/sbas", temp,
false);
666 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_SBAS_FILT : 0;
667 nh->param(
"nmea/filter/track", temp,
false);
668 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
673 ROS_WARN(
"ublox_version < 7, ignoring GNSS settings");
676 throw std::runtime_error(
"Failed to configure NMEA");
702 publish<ublox_msgs::NavSVINFO>, _1,
"navsvinfo"),
715 if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_DEAD_RECKONING_ONLY) {
716 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
717 stat.message =
"Dead reckoning only";
718 }
else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_2D_FIX) {
719 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
720 stat.message =
"2D fix";
721 }
else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_3D_FIX) {
722 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
723 stat.message =
"3D fix";
724 }
else if (last_nav_sol_.gpsFix ==
725 ublox_msgs::NavSOL::GPS_GPS_DEAD_RECKONING_COMBINED) {
726 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
727 stat.message =
"GPS and dead reckoning combined";
728 }
else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_TIME_ONLY_FIX) {
729 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
730 stat.message =
"Time fix only";
733 if (!(last_nav_sol_.flags & ublox_msgs::NavSOL::FLAGS_GPS_FIX_OK)) {
734 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
735 stat.message +=
", fix not ok";
738 if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_NO_FIX) {
739 stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
740 stat.message =
"No fix";
744 stat.
add(
"iTOW [ms]", last_nav_pos_.iTOW);
745 stat.
add(
"Latitude [deg]", last_nav_pos_.lat * 1e-7);
746 stat.
add(
"Longitude [deg]", last_nav_pos_.lon * 1e-7);
747 stat.
add(
"Altitude [m]", last_nav_pos_.height * 1e-3);
748 stat.
add(
"Height above MSL [m]", last_nav_pos_.hMSL * 1e-3);
749 stat.
add(
"Horizontal Accuracy [m]", last_nav_pos_.hAcc * 1e-3);
750 stat.
add(
"Vertical Accuracy [m]", last_nav_pos_.vAcc * 1e-3);
751 stat.
add(
"# SVs used", (
int)last_nav_sol_.numSV);
764 if (m.iTOW == last_nav_vel_.iTOW)
765 fix_.header.stamp = velocity_.header.stamp;
770 fix_.latitude = m.lat * 1e-7;
771 fix_.longitude = m.lon * 1e-7;
772 fix_.altitude = m.height * 1e-3;
774 if (last_nav_sol_.gpsFix >= last_nav_sol_.GPS_2D_FIX)
775 fix_.status.status = fix_.status.STATUS_FIX;
777 fix_.status.status = fix_.status.STATUS_NO_FIX;
780 const double varH = pow(m.hAcc / 1000.0, 2);
781 const double varV = pow(m.vAcc / 1000.0, 2);
783 fix_.position_covariance[0] = varH;
784 fix_.position_covariance[4] = varH;
785 fix_.position_covariance[8] = varV;
786 fix_.position_covariance_type =
787 sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
789 fix_.status.service = fix_.status.SERVICE_GPS;
793 freq_diag->diagnostic->tick(fix_.header.stamp);
806 nh->advertise<geometry_msgs::TwistWithCovarianceStamped>(
"fix_velocity",
808 if (m.iTOW == last_nav_pos_.iTOW)
809 velocity_.header.stamp = fix_.header.stamp;
812 velocity_.header.frame_id =
frame_id;
815 velocity_.twist.twist.linear.x = m.velE / 100.0;
816 velocity_.twist.twist.linear.y = m.velN / 100.0;
817 velocity_.twist.twist.linear.z = -m.velD / 100.0;
819 const double varSpeed = pow(m.sAcc / 100.0, 2);
822 velocity_.twist.covariance[cols * 0 + 0] = varSpeed;
823 velocity_.twist.covariance[cols * 1 + 1] = varSpeed;
824 velocity_.twist.covariance[cols * 2 + 2] = varSpeed;
825 velocity_.twist.covariance[cols * 3 + 3] = -1;
827 velocityPublisher.
publish(velocity_);
850 nh->param(
"gnss/gps", enable_gps_,
true);
851 nh->param(
"gnss/glonass", enable_glonass_,
false);
852 nh->param(
"gnss/qzss", enable_qzss_,
false);
853 getRosUint(
"gnss/qzss_sig_cfg", qzss_sig_cfg_,
854 ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
858 ROS_WARN(
"gnss/gps is true, but GPS GNSS is not supported by this device");
860 ROS_WARN(
"gnss/glonass is true, but GLONASS is not %s",
861 "supported by this device");
863 ROS_WARN(
"gnss/qzss is true, but QZSS is not supported by this device");
865 ROS_WARN(
"gnss/sbas is true, but SBAS is not supported by this device");
867 if(
nh->hasParam(
"gnss/galileo"))
868 ROS_WARN(
"ublox_version < 8, ignoring Galileo GNSS Settings");
869 if(
nh->hasParam(
"gnss/beidou"))
870 ROS_WARN(
"ublox_version < 8, ignoring BeiDou Settings");
871 if(
nh->hasParam(
"gnss/imes"))
872 ROS_WARN(
"ublox_version < 8, ignoring IMES GNSS Settings");
876 + (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS;
881 nh->param(
"nmea/set", set_nmea_,
false);
883 bool compat, consider;
885 if (!
getRosUint(
"nmea/version", cfg_nmea_.nmeaVersion))
886 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
887 "true, therefore nmea/version must be set");
888 if (!
getRosUint(
"nmea/num_sv", cfg_nmea_.numSV))
889 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
890 "true, therefore nmea/num_sv must be set");
891 if (!
getRosUint(
"nmea/sv_numbering", cfg_nmea_.svNumbering))
892 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
893 "true, therefore nmea/sv_numbering must be set");
894 if (!
nh->getParam(
"nmea/compat", compat))
895 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
896 "true, therefore nmea/compat must be set");
897 if (!
nh->getParam(
"nmea/consider", consider))
898 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
899 "true, therefore nmea/consider must be set");
902 cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
903 cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
906 nh->param(
"nmea/filter/pos", temp,
false);
907 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
908 nh->param(
"nmea/filter/msk_pos", temp,
false);
909 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
910 nh->param(
"nmea/filter/time", temp,
false);
911 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
912 nh->param(
"nmea/filter/date", temp,
false);
913 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
914 nh->param(
"nmea/filter/gps_only", temp,
false);
915 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
916 nh->param(
"nmea/filter/track", temp,
false);
917 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
919 nh->param(
"nmea/gnssToFilter/gps", temp,
false);
920 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
921 nh->param(
"nmea/gnssToFilter/sbas", temp,
false);
922 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
923 nh->param(
"nmea/gnssToFilter/qzss", temp,
false);
924 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
925 nh->param(
"nmea/gnssToFilter/glonass", temp,
false);
926 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
928 getRosUint(
"nmea/main_talker_id", cfg_nmea_.mainTalkerId);
929 getRosUint(
"nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
935 ublox_msgs::CfgGNSS cfgGNSSRead;
938 ROS_DEBUG(
"Num. tracking channels in hardware: %i", cfgGNSSRead.numTrkChHw);
939 ROS_DEBUG(
"Num. tracking channels to use: %i", cfgGNSSRead.numTrkChUse);
941 throw std::runtime_error(
"Failed to read the GNSS config.");
944 ublox_msgs::CfgGNSS cfgGNSSWrite;
945 cfgGNSSWrite.numConfigBlocks = 1;
946 cfgGNSSWrite.numTrkChHw = cfgGNSSRead.numTrkChHw;
947 cfgGNSSWrite.numTrkChUse = cfgGNSSRead.numTrkChUse;
948 cfgGNSSWrite.msgVer = 0;
952 ublox_msgs::CfgGNSS_Block block;
953 block.gnssId = block.GNSS_ID_GLONASS;
954 block.resTrkCh = block.RES_TRK_CH_GLONASS;
955 block.maxTrkCh = block.MAX_TRK_CH_GLONASS;
956 block.flags = enable_glonass_ ? block.SIG_CFG_GLONASS_L1OF : 0;
957 cfgGNSSWrite.blocks.push_back(block);
959 throw std::runtime_error(std::string(
"Failed to ") +
960 ((enable_glonass_) ?
"enable" :
"disable") +
967 ublox_msgs::CfgGNSS_Block block;
968 block.gnssId = block.GNSS_ID_QZSS;
969 block.resTrkCh = block.RES_TRK_CH_QZSS;
970 block.maxTrkCh = block.MAX_TRK_CH_QZSS;
971 block.flags = enable_qzss_ ? qzss_sig_cfg_ : 0;
972 cfgGNSSWrite.blocks[0] = block;
974 throw std::runtime_error(std::string(
"Failed to ") +
975 ((enable_glonass_) ?
"enable" :
"disable") +
982 ublox_msgs::CfgGNSS_Block block;
983 block.gnssId = block.GNSS_ID_SBAS;
984 block.resTrkCh = block.RES_TRK_CH_SBAS;
985 block.maxTrkCh = block.MAX_TRK_CH_SBAS;
986 block.flags =
enable_sbas_ ? block.SIG_CFG_SBAS_L1CA : 0;
987 cfgGNSSWrite.blocks[0] = block;
989 throw std::runtime_error(std::string(
"Failed to ") +
996 throw std::runtime_error(
"Failed to configure NMEA");
1014 publish<ublox_msgs::NavSVINFO>, _1,
"navsvinfo"),
1031 nh->param(
"clear_bbr", clear_bbr_,
false);
1035 nh->param(
"gnss/gps", enable_gps_,
true);
1036 nh->param(
"gnss/galileo", enable_galileo_,
false);
1037 nh->param(
"gnss/beidou", enable_beidou_,
false);
1038 nh->param(
"gnss/imes", enable_imes_,
false);
1039 nh->param(
"gnss/glonass", enable_glonass_,
false);
1040 nh->param(
"gnss/qzss", enable_qzss_,
false);
1043 getRosUint(
"gnss/qzss_sig_cfg", qzss_sig_cfg_,
1044 ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
1047 ROS_WARN(
"gnss/gps is true, but GPS GNSS is not supported by %s",
1050 ROS_WARN(
"gnss/glonass is true, but GLONASS is not supported by %s",
1053 ROS_WARN(
"gnss/galileo is true, but Galileo GNSS is not supported %s",
1056 ROS_WARN(
"gnss/beidou is true, but Beidou GNSS is not supported %s",
1059 ROS_WARN(
"gnss/imes is true, but IMES GNSS is not supported by %s",
1062 ROS_WARN(
"gnss/qzss is true, but QZSS is not supported by this device");
1064 ROS_WARN(
"gnss/sbas is true, but SBAS is not supported by this device");
1068 + (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS
1069 + (enable_beidou_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_COMPASS
1070 + (enable_galileo_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GALILEO;
1075 nh->param(
"nmea/set", set_nmea_,
false);
1077 bool compat, consider;
1078 cfg_nmea_.version = cfg_nmea_.VERSION;
1081 if (!
getRosUint(
"nmea/version", cfg_nmea_.nmeaVersion))
1082 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1083 "true, therefore nmea/version must be set");
1084 if (!
getRosUint(
"nmea/num_sv", cfg_nmea_.numSV))
1085 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1086 "true, therefore nmea/num_sv must be set");
1087 if (!
getRosUint(
"nmea/sv_numbering", cfg_nmea_.svNumbering))
1088 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1089 "true, therefore nmea/sv_numbering must be set");
1090 if (!
nh->getParam(
"nmea/compat", compat))
1091 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1092 "true, therefore nmea/compat must be set");
1093 if (!
nh->getParam(
"nmea/consider", consider))
1094 throw std::runtime_error(std::string(
"Invalid settings: nmea/set is ") +
1095 "true, therefore nmea/consider must be set");
1098 cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
1099 cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
1101 nh->param(
"nmea/limit82", temp,
false);
1102 cfg_nmea_.flags |= temp ? cfg_nmea_.FLAGS_LIMIT82 : 0;
1103 nh->param(
"nmea/high_prec", temp,
false);
1104 cfg_nmea_.flags |= temp ? cfg_nmea_.FLAGS_HIGH_PREC : 0;
1106 nh->param(
"nmea/filter/pos", temp,
false);
1107 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
1108 nh->param(
"nmea/filter/msk_pos", temp,
false);
1109 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
1110 nh->param(
"nmea/filter/time", temp,
false);
1111 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
1112 nh->param(
"nmea/filter/date", temp,
false);
1113 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
1114 nh->param(
"nmea/filter/gps_only", temp,
false);
1115 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
1116 nh->param(
"nmea/filter/track", temp,
false);
1117 cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
1119 nh->param(
"nmea/gnssToFilter/gps", temp,
false);
1120 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
1121 nh->param(
"nmea/gnssToFilter/sbas", temp,
false);
1122 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
1123 nh->param(
"nmea/gnssToFilter/qzss", temp,
false);
1124 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
1125 nh->param(
"nmea/gnssToFilter/glonass", temp,
false);
1126 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
1127 nh->param(
"nmea/gnssToFilter/beidou", temp,
false);
1128 cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_BEIDOU : 0;
1130 getRosUint(
"nmea/main_talker_id", cfg_nmea_.mainTalkerId);
1131 getRosUint(
"nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
1133 std::vector<uint8_t> bdsTalkerId;
1134 getRosUint(
"nmea/bds_talker_id", bdsTalkerId);
1135 if(bdsTalkerId.size() >= 2) {
1136 cfg_nmea_.bdsTalkerId[0] = bdsTalkerId[0];
1137 cfg_nmea_.bdsTalkerId[1] = bdsTalkerId[1];
1148 ROS_ERROR(
"u-blox failed to clear flash memory");
1154 ublox_msgs::CfgGNSS cfg_gnss;
1157 ROS_DEBUG(
"Num. tracking channels in hardware: %i", cfg_gnss.numTrkChHw);
1158 ROS_DEBUG(
"Num. tracking channels to use: %i", cfg_gnss.numTrkChUse);
1160 throw std::runtime_error(
"Failed to read the GNSS config.");
1164 bool correct =
true;
1165 for (
int i = 0; i < cfg_gnss.blocks.size(); i++) {
1166 ublox_msgs::CfgGNSS_Block block = cfg_gnss.blocks[i];
1167 if (block.gnssId == block.GNSS_ID_GPS
1168 && enable_gps_ != (block.flags & block.FLAGS_ENABLE)) {
1170 cfg_gnss.blocks[i].flags =
1171 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_gps_;
1172 ROS_DEBUG(
"GPS Configuration is different");
1173 }
else if (block.gnssId == block.GNSS_ID_SBAS
1174 &&
enable_sbas_ != (block.flags & block.FLAGS_ENABLE)) {
1176 cfg_gnss.blocks[i].flags =
1177 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) |
enable_sbas_;
1178 ROS_DEBUG(
"SBAS Configuration is different");
1179 }
else if (block.gnssId == block.GNSS_ID_GALILEO
1180 && enable_galileo_ != (block.flags & block.FLAGS_ENABLE)) {
1182 cfg_gnss.blocks[i].flags =
1183 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_galileo_;
1184 ROS_DEBUG(
"Galileo GNSS Configuration is different");
1185 }
else if (block.gnssId == block.GNSS_ID_BEIDOU
1186 && enable_beidou_ != (block.flags & block.FLAGS_ENABLE)) {
1188 cfg_gnss.blocks[i].flags =
1189 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_beidou_;
1190 ROS_DEBUG(
"BeiDou Configuration is different");
1191 }
else if (block.gnssId == block.GNSS_ID_IMES
1192 && enable_imes_ != (block.flags & block.FLAGS_ENABLE)) {
1194 cfg_gnss.blocks[i].flags =
1195 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_imes_;
1196 }
else if (block.gnssId == block.GNSS_ID_QZSS
1197 && (enable_qzss_ != (block.flags & block.FLAGS_ENABLE)
1199 && qzss_sig_cfg_ != (block.flags & block.FLAGS_SIG_CFG_MASK)))) {
1200 ROS_DEBUG(
"QZSS Configuration is different %u, %u",
1201 block.flags & block.FLAGS_ENABLE,
1204 ROS_DEBUG(
"QZSS Configuration: %u", block.flags);
1205 cfg_gnss.blocks[i].flags =
1206 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_qzss_;
1207 ROS_DEBUG(
"QZSS Configuration: %u", cfg_gnss.blocks[i].flags);
1210 cfg_gnss.blocks[i].flags |= qzss_sig_cfg_;
1211 }
else if (block.gnssId == block.GNSS_ID_GLONASS
1212 && enable_glonass_ != (block.flags & block.FLAGS_ENABLE)) {
1214 cfg_gnss.blocks[i].flags =
1215 (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_glonass_;
1216 ROS_DEBUG(
"GLONASS Configuration is different");
1223 ROS_DEBUG(
"U-Blox GNSS configuration is correct. GNSS not re-configured.");
1224 else if (!
gps.
configGnss(cfg_gnss, boost::posix_time::seconds(15)))
1225 throw std::runtime_error(std::string(
"Failed to cold reset device ") +
1226 "after configuring GNSS");
1232 throw std::runtime_error(
"Failed to configure NMEA");
1268 nh->param(
"publish/rxm/all",
enabled[
"rxm"],
true);
1321 if(nav_rate_hz != 1)
1322 ROS_WARN(
"Nav Rate recommended to be 1 Hz");
1327 throw std::runtime_error(std::string(
"Failed to ")
1328 + (
use_adr_ ?
"enable" :
"disable") +
"use_adr");
1333 nh->param(
"publish/esf/all",
enabled[
"esf"],
true);
1372 publish<ublox_msgs::EsfSTATUS>, _1,
"esfstatus"),
kSubscribeRate);
1375 nh->param(
"publish/hnr/pvt",
enabled[
"hnr_pvt"],
true);
1386 nh->advertise<sensor_msgs::TimeReference>(
"interrupt_time",
kROSQueueSize);
1391 static const float rad_per_sec = pow(2, -12) * M_PI / 180.0F;
1392 static const float m_per_sec_sq = pow(2, -10);
1393 static const float deg_c = 1e-2;
1395 std::vector<uint32_t> imu_data = m.data;
1396 for (
int i=0; i < imu_data.size(); i++){
1397 unsigned int data_type = imu_data[i] >> 24;
1398 int32_t data_value =
static_cast<int32_t
>(imu_data[i] << 8);
1401 imu_.orientation_covariance[0] = -1;
1402 imu_.linear_acceleration_covariance[0] = -1;
1403 imu_.angular_velocity_covariance[0] = -1;
1405 if (data_type == 14) {
1406 imu_.angular_velocity.x = data_value * rad_per_sec;
1407 }
else if (data_type == 16) {
1408 imu_.linear_acceleration.x = data_value * m_per_sec_sq;
1409 }
else if (data_type == 13) {
1410 imu_.angular_velocity.y = data_value * rad_per_sec;
1411 }
else if (data_type == 17) {
1412 imu_.linear_acceleration.y = data_value * m_per_sec_sq;
1413 }
else if (data_type == 5) {
1414 imu_.angular_velocity.z = data_value * rad_per_sec;
1415 }
else if (data_type == 18) {
1416 imu_.linear_acceleration.z = data_value * m_per_sec_sq;
1417 }
else if (data_type == 12) {
1438 time_ref_pub.publish(
t_ref_);
1451 ROS_WARN(
"For HPG Ref devices, nav_rate should be exactly 1 Hz.");
1454 throw std::runtime_error(
"Invalid settings: TMODE3 must be set");
1456 if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_FIXED) {
1457 if(!
nh->getParam(
"arp/position", arp_position_))
1458 throw std::runtime_error(std::string(
"Invalid settings: arp/position ")
1459 +
"must be set if TMODE3 is fixed");
1460 if(!
getRosInt(
"arp/position_hp", arp_position_hp_))
1461 throw std::runtime_error(std::string(
"Invalid settings: arp/position_hp ")
1462 +
"must be set if TMODE3 is fixed");
1463 if(!
nh->getParam(
"arp/acc", fixed_pos_acc_))
1464 throw std::runtime_error(std::string(
"Invalid settings: arp/acc ")
1465 +
"must be set if TMODE3 is fixed");
1466 if(!
nh->getParam(
"arp/lla_flag", lla_flag_)) {
1467 ROS_WARN(
"arp/lla_flag param not set, assuming ARP coordinates are %s",
1471 }
else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_SURVEY_IN) {
1472 nh->param(
"sv_in/reset", svin_reset_,
true);
1473 if(!
getRosUint(
"sv_in/min_dur", sv_in_min_dur_))
1474 throw std::runtime_error(std::string(
"Invalid settings: sv_in/min_dur ")
1475 +
"must be set if TMODE3 is survey-in");
1476 if(!
nh->getParam(
"sv_in/acc_lim", sv_in_acc_lim_))
1477 throw std::runtime_error(std::string(
"Invalid settings: sv_in/acc_lim ")
1478 +
"must be set if TMODE3 is survey-in");
1479 }
else if(tmode3_ != ublox_msgs::CfgTMODE3::FLAGS_MODE_DISABLED) {
1480 throw std::runtime_error(std::string(
"tmode3 param invalid. See CfgTMODE3")
1481 +
" flag constants for possible values.");
1488 if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_DISABLED) {
1490 throw std::runtime_error(
"Failed to disable TMODE3.");
1492 }
else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_FIXED) {
1495 throw std::runtime_error(
"Failed to set TMODE3 to fixed.");
1497 throw std::runtime_error(
"Failed to set RTCM rates");
1499 }
else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_SURVEY_IN) {
1501 ublox_msgs::NavSVIN nav_svin;
1503 throw std::runtime_error(std::string(
"Failed to poll NavSVIN while") +
1504 " configuring survey-in");
1506 if(nav_svin.active) {
1511 if(nav_svin.valid) {
1515 ublox_msgs::NavPVT nav_pvt;
1517 throw std::runtime_error(std::string(
"Failed to poll NavPVT while") +
1518 " configuring survey-in");
1520 if (nav_pvt.fixType == nav_pvt.FIX_TYPE_TIME_ONLY
1521 && nav_pvt.flags & nav_pvt.FLAGS_GNSS_FIX_OK) {
1530 if(1000 % meas_rate_temp != 0)
1533 if(!
gps.
configRate(meas_rate_temp, (
int) 1000 / meas_rate_temp))
1534 throw std::runtime_error(std::string(
"Failed to set nav rate to 1 Hz") +
1535 "before setting TMODE3 to survey-in.");
1538 ROS_ERROR(
"Failed to disable TMODE3 before setting to survey-in.");
1543 throw std::runtime_error(
"Failed to set TMODE3 to survey-in.");
1566 if(!m.active && m.valid && mode_ == SURVEY_IN) {
1574 ROS_INFO(
"Setting mode (internal state) to Time Mode");
1584 ROS_ERROR(
"Failed to configure RTCM IDs");
1597 if (mode_ == INIT) {
1598 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1599 stat.message =
"Not configured";
1600 }
else if (mode_ == DISABLED){
1601 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1602 stat.message =
"Disabled";
1603 }
else if (mode_ == SURVEY_IN) {
1604 if (!last_nav_svin_.active && !last_nav_svin_.valid) {
1605 stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
1606 stat.message =
"Survey-In inactive and invalid";
1607 }
else if (last_nav_svin_.active && !last_nav_svin_.valid) {
1608 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1609 stat.message =
"Survey-In active but invalid";
1610 }
else if (!last_nav_svin_.active && last_nav_svin_.valid) {
1611 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1612 stat.message =
"Survey-In complete";
1613 }
else if (last_nav_svin_.active && last_nav_svin_.valid) {
1614 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1615 stat.message =
"Survey-In active and valid";
1618 stat.
add(
"iTOW [ms]", last_nav_svin_.iTOW);
1619 stat.
add(
"Duration [s]", last_nav_svin_.dur);
1620 stat.
add(
"# observations", last_nav_svin_.obs);
1621 stat.
add(
"Mean X [m]", last_nav_svin_.meanX * 1e-2);
1622 stat.
add(
"Mean Y [m]", last_nav_svin_.meanY * 1e-2);
1623 stat.
add(
"Mean Z [m]", last_nav_svin_.meanZ * 1e-2);
1624 stat.
add(
"Mean X HP [m]", last_nav_svin_.meanXHP * 1e-4);
1625 stat.
add(
"Mean Y HP [m]", last_nav_svin_.meanYHP * 1e-4);
1626 stat.
add(
"Mean Z HP [m]", last_nav_svin_.meanZHP * 1e-4);
1627 stat.
add(
"Mean Accuracy [m]", last_nav_svin_.meanAcc * 1e-4);
1628 }
else if(mode_ == FIXED) {
1629 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1630 stat.message =
"Fixed Position";
1631 }
else if(mode_ == TIME) {
1632 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1633 stat.message =
"Time";
1643 ublox_msgs::CfgDGNSS::DGNSS_MODE_RTK_FIXED);
1649 throw std::runtime_error(std::string(
"Failed to Configure DGNSS"));
1655 nh->param(
"publish/nav/relposned",
enabled[
"nav_relposned"],
enabled[
"nav"]);
1663 kRtcmFreqMin, kRtcmFreqMax,
1664 kRtcmFreqTol, kRtcmFreqWindow);
1665 updater->add(
"Carrier Phase Solution",
this,
1672 uint32_t carr_soln = last_rel_pos_.flags & last_rel_pos_.FLAGS_CARR_SOLN_MASK;
1673 stat.
add(
"iTOW", last_rel_pos_.iTOW);
1674 if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_NONE ||
1675 !(last_rel_pos_.flags & last_rel_pos_.FLAGS_DIFF_SOLN &&
1676 last_rel_pos_.flags & last_rel_pos_.FLAGS_REL_POS_VALID)) {
1677 stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
1678 stat.message =
"None";
1680 if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_FLOAT) {
1681 stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1682 stat.message =
"Float";
1683 }
else if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_FIXED) {
1684 stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1685 stat.message =
"Fixed";
1687 stat.
add(
"Ref Station ID", last_rel_pos_.refStationId);
1689 double rel_pos_n = (last_rel_pos_.relPosN
1690 + (last_rel_pos_.relPosHPN * 1e-2)) * 1e-2;
1691 double rel_pos_e = (last_rel_pos_.relPosE
1692 + (last_rel_pos_.relPosHPE * 1e-2)) * 1e-2;
1693 double rel_pos_d = (last_rel_pos_.relPosD
1694 + (last_rel_pos_.relPosHPD * 1e-2)) * 1e-2;
1695 stat.
add(
"Relative Position N [m]", rel_pos_n);
1696 stat.
add(
"Relative Accuracy N [m]", last_rel_pos_.accN * 1e-4);
1697 stat.
add(
"Relative Position E [m]", rel_pos_e);
1698 stat.
add(
"Relative Accuracy E [m]", last_rel_pos_.accE * 1e-4);
1699 stat.
add(
"Relative Position D [m]", rel_pos_d);
1700 stat.
add(
"Relative Accuracy D [m]", last_rel_pos_.accD * 1e-4);
1705 if (
enabled[
"nav_relposned"]) {
1707 nh->advertise<ublox_msgs::NavRELPOSNED>(
"navrelposned",
kROSQueueSize);
1720 nh->param(
"publish/nav/hpposecef",
enabled[
"nav_hpposecef"],
enabled[
"nav"]);
1723 publish<ublox_msgs::NavHPPOSECEF>, _1,
"navhpposecef"),
kSubscribeRate);
1729 nh->param(
"publish/nav/hpposllh",
enabled[
"nav_hpposllh"],
enabled[
"nav"]);
1737 nh->param(
"publish/nav/relposned",
enabled[
"nav_relposned"],
enabled[
"nav"]);
1747 if (
enabled[
"nav_hpposllh"]) {
1754 sensor_msgs::NavSatFix fix_msg;
1759 fix_msg.header.frame_id =
frame_id;
1760 fix_msg.latitude = m.lat * 1e-7 + m.latHp * 1e-9;
1761 fix_msg.longitude = m.lon * 1e-7 + m.lonHp * 1e-9;
1762 fix_msg.altitude = m.height * 1e-3 + m.heightHp * 1e-4;
1764 if (m.invalid_llh) {
1765 fix_msg.status.status = fix_msg.status.STATUS_NO_FIX;
1767 fix_msg.status.status = fix_msg.status.STATUS_FIX;
1771 const double varH = pow(m.hAcc / 10000.0, 2);
1772 const double varV = pow(m.vAcc / 10000.0, 2);
1774 fix_msg.position_covariance[0] = varH;
1775 fix_msg.position_covariance[4] = varH;
1776 fix_msg.position_covariance[8] = varV;
1777 fix_msg.position_covariance_type =
1778 sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
1780 fix_msg.status.service = fix_msg.status.SERVICE_GPS;
1781 fixPublisher.
publish(fix_msg);
1786 if (
enabled[
"nav_relposned"]) {
1788 nh->advertise<ublox_msgs::NavRELPOSNED9>(
"navrelposned",
kROSQueueSize);
1799 imu_.linear_acceleration_covariance[0] = -1;
1800 imu_.angular_velocity_covariance[0] = -1;
1803 double heading = M_PI_2 - (
static_cast<double>(m.relPosHeading) * 1e-5 / 180.0 * M_PI);
1805 orientation.
setRPY(0, 0, heading);
1806 imu_.orientation.x = orientation[0];
1807 imu_.orientation.y = orientation[1];
1808 imu_.orientation.z = orientation[2];
1809 imu_.orientation.w = orientation[3];
1810 imu_.orientation_covariance[0] = 1000.0;
1811 imu_.orientation_covariance[4] = 1000.0;
1812 imu_.orientation_covariance[8] = 1000.0;
1814 if (m.flags & ublox_msgs::NavRELPOSNED9::FLAGS_REL_POS_HEAD_VALID)
1816 imu_.orientation_covariance[8] = pow(m.accHeading * 1e-5 / 180.0 * M_PI, 2);
1836 throw std::runtime_error(std::string(
"Failed to Configure TIM Product to UTC Time"));
1839 throw std::runtime_error(std::string(
"Failed to Configure TIM Product"));
1853 ROS_INFO(
"Subscribed to TIM-TM2 messages on topic tim/tm2");
1874 nh->advertise<sensor_msgs::TimeReference>(
"interrupt_time",
kROSQueueSize);
1877 t_ref_.header.seq = m.risingEdgeCount;
1881 t_ref_.time_ref =
ros::Time((m.wnR * 604800 + m.towMsR / 1000), (m.towMsR % 1000) * 1000000 + m.towSubMsR);
1883 std::ostringstream src;
1884 src <<
"TIM" << int(m.ch);
1885 t_ref_.source = src.str();
1891 time_ref_pub.publish(
t_ref_);
uint32_t baudrate_
UART1 baudrate.
int debug
Used to determine which debug messages to display.
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 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.
void reset(const boost::posix_time::time_duration &wait)
Reset I/O communications.
static constexpr double kKeepAlivePeriod
How often (in seconds) to send keep-alive message.
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 publish(const boost::shared_ptr< M > &message) const
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.
bool sendRtcm(const std::vector< uint8_t > &message)
Send rtcm correction message.
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.
bool isInitialized() const
bool isConfigured() const
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 rtcmCallback(const rtcm_msgs::Message::ConstPtr &msg)
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.
#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 ...
void subscribe_nmea(boost::function< void(const std::string &)> callback)
Subscribe to the given Ublox message.
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 callbackNavHpPosLlh(const ublox_msgs::NavHPPOSLLH &m)
Publish a sensor_msgs/NavSatFix message upon receiving a HPPOSLLH UBX message.
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 keepAlive(const ros::TimerEvent &event)
Poll version message from the U-Blox device to keep socket active.
void publish_nmea(const std::string &sentence, const std::string &topic)
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.
void initializeUdp(std::string host, std::string port)
Initialize UDP I/O.
std::string frame_id
The ROS frame ID of this device.
bool setUTCtime()
Configure the U-Blox to UTC time.