00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00128 #include <exception>
00129 #include <string>
00130
00131 #include <boost/accumulators/accumulators.hpp>
00132 #include <boost/accumulators/statistics/max.hpp>
00133 #include <boost/accumulators/statistics/mean.hpp>
00134 #include <boost/accumulators/statistics/min.hpp>
00135 #include <boost/accumulators/statistics/rolling_mean.hpp>
00136 #include <boost/accumulators/statistics/stats.hpp>
00137 #include <boost/accumulators/statistics/tail.hpp>
00138 #include <boost/accumulators/statistics/variance.hpp>
00139 #include <boost/circular_buffer.hpp>
00140
00141 #include <diagnostic_msgs/DiagnosticStatus.h>
00142 #include <diagnostic_updater/diagnostic_updater.h>
00143 #include <diagnostic_updater/publisher.h>
00144 #include <gps_common/GPSFix.h>
00145 #include <nodelet/nodelet.h>
00146 #include <novatel_gps_msgs/NovatelCorrectedImuData.h>
00147 #include <novatel_gps_msgs/NovatelFRESET.h>
00148 #include <novatel_gps_msgs/NovatelMessageHeader.h>
00149 #include <novatel_gps_msgs/NovatelPosition.h>
00150 #include <novatel_gps_msgs/NovatelUtmPosition.h>
00151 #include <novatel_gps_msgs/NovatelVelocity.h>
00152 #include <novatel_gps_msgs/NovatelHeading2.h>
00153 #include <novatel_gps_msgs/NovatelDualAntennaHeading.h>
00154 #include <novatel_gps_msgs/Gpgga.h>
00155 #include <novatel_gps_msgs/Gprmc.h>
00156 #include <novatel_gps_msgs/Range.h>
00157 #include <novatel_gps_msgs/Time.h>
00158 #include <novatel_gps_driver/novatel_gps.h>
00159 #include <ros/ros.h>
00160 #include <sensor_msgs/Imu.h>
00161 #include <sensor_msgs/NavSatFix.h>
00162 #include <std_msgs/Time.h>
00163 #include <swri_math_util/math_util.h>
00164 #include <swri_roscpp/parameters.h>
00165 #include <swri_roscpp/publisher.h>
00166 #include <swri_roscpp/subscriber.h>
00167
00168 namespace stats = boost::accumulators;
00169
00170 namespace novatel_gps_driver
00171 {
00172 class NovatelGpsNodelet : public nodelet::Nodelet
00173 {
00174 public:
00175 NovatelGpsNodelet() :
00176 device_(""),
00177 connection_type_("serial"),
00178 polling_period_(0.05),
00179 publish_gpgsa_(false),
00180 publish_gpgsv_(false),
00181 imu_rate_(100.0),
00182 imu_sample_rate_(-1),
00183 publish_imu_messages_(false),
00184 publish_novatel_positions_(false),
00185 publish_novatel_xyz_positions_(false),
00186 publish_novatel_utm_positions_(false),
00187 publish_novatel_velocity_(false),
00188 publish_novatel_heading2_(false),
00189 publish_novatel_dual_antenna_heading_(false),
00190 publish_nmea_messages_(false),
00191 publish_range_messages_(false),
00192 publish_time_messages_(false),
00193 publish_trackstat_(false),
00194 publish_diagnostics_(true),
00195 publish_sync_diagnostic_(true),
00196 reconnect_delay_s_(0.5),
00197 use_binary_messages_(false),
00198 span_frame_to_ros_frame_(false),
00199 connection_(NovatelGps::SERIAL),
00200 last_sync_(ros::TIME_MIN),
00201 rolling_offset_(stats::tag::rolling_window::window_size = 10),
00202 expected_rate_(20),
00203 device_timeouts_(0),
00204 device_interrupts_(0),
00205 device_errors_(0),
00206 gps_parse_failures_(0),
00207 gps_insufficient_data_warnings_(0),
00208 publish_rate_warnings_(0),
00209 measurement_count_(0),
00210 last_published_(ros::TIME_MIN),
00211 imu_frame_id_(""),
00212 frame_id_("")
00213 {
00214 }
00215
00216 ~NovatelGpsNodelet()
00217 {
00218 gps_.Disconnect();
00219 }
00220
00225 void onInit()
00226 {
00227 ros::NodeHandle &node = getNodeHandle();
00228 ros::NodeHandle &priv = getPrivateNodeHandle();
00229
00230 swri::param(priv, "device", device_, device_);
00231 swri::param(priv, "imu_rate", imu_rate_, imu_rate_);
00232 swri::param(priv, "imu_sample_rate", imu_sample_rate_, imu_sample_rate_);
00233 swri::param(priv, "publish_clocksteering", publish_clock_steering_, false);
00234 swri::param(priv, "publish_gpgsa", publish_gpgsa_, publish_gpgsa_);
00235 swri::param(priv, "publish_gpgsv", publish_gpgsv_, publish_gpgsv_);
00236 swri::param(priv, "publish_imu_messages", publish_imu_messages_, publish_imu_messages_);
00237 swri::param(priv, "publish_novatel_positions", publish_novatel_positions_, publish_novatel_positions_);
00238 swri::param(priv, "publish_novatel_xyz_positions", publish_novatel_xyz_positions_, publish_novatel_xyz_positions_);
00239 swri::param(priv, "publish_novatel_utm_positions", publish_novatel_utm_positions_, publish_novatel_utm_positions_);
00240 swri::param(priv, "publish_novatel_velocity", publish_novatel_velocity_, publish_novatel_velocity_);
00241 swri::param(priv, "publish_novatel_heading2", publish_novatel_heading2_, publish_novatel_heading2_);
00242 swri::param(priv, "publish_novatel_dual_antenna_heading", publish_novatel_dual_antenna_heading_, publish_novatel_dual_antenna_heading_);
00243 swri::param(priv, "publish_nmea_messages", publish_nmea_messages_, publish_nmea_messages_);
00244 swri::param(priv, "publish_range_messages", publish_range_messages_, publish_range_messages_);
00245 swri::param(priv, "publish_time_messages", publish_time_messages_, publish_time_messages_);
00246 swri::param(priv, "publish_trackstat", publish_trackstat_, publish_trackstat_);
00247 swri::param(priv, "publish_diagnostics", publish_diagnostics_, publish_diagnostics_);
00248 swri::param(priv, "publish_sync_diagnostic", publish_sync_diagnostic_, publish_sync_diagnostic_);
00249 swri::param(priv, "polling_period", polling_period_, polling_period_);
00250 swri::param(priv, "reconnect_delay_s", reconnect_delay_s_, reconnect_delay_s_);
00251 swri::param(priv, "use_binary_messages", use_binary_messages_, use_binary_messages_);
00252 swri::param(priv, "span_frame_to_ros_frame", span_frame_to_ros_frame_, span_frame_to_ros_frame_);
00253
00254 swri::param(priv, "connection_type", connection_type_, connection_type_);
00255 connection_ = NovatelGps::ParseConnection(connection_type_);
00256 swri::param(priv, "serial_baud", serial_baud_, 115200);
00257
00258 swri::param(priv, "imu_frame_id", imu_frame_id_, std::string(""));
00259 swri::param(priv, "frame_id", frame_id_, std::string(""));
00260
00261
00262 swri::param(priv, "gpgga_gprmc_sync_tol", gps_.gpgga_gprmc_sync_tol_, 0.01);
00263 swri::param(priv, "gpgga_position_sync_tol", gps_.gpgga_position_sync_tol_, 0.01);
00264 swri::param(priv, "wait_for_position", gps_.wait_for_position_, false);
00265
00266
00267 reset_service_ = priv.advertiseService("freset", &NovatelGpsNodelet::resetService, this);
00268
00269 sync_sub_ = swri::Subscriber(node, "gps_sync", 100, &NovatelGpsNodelet::SyncCallback, this);
00270
00271 std::string gps_topic = node.resolveName("gps");
00272 gps_pub_ = swri::advertise<gps_common::GPSFix>(node, gps_topic, 100);
00273 fix_pub_ = swri::advertise<sensor_msgs::NavSatFix>(node, "fix", 100);
00274
00275 if (publish_clock_steering_)
00276 {
00277 clocksteering_pub_ = swri::advertise<novatel_gps_msgs::ClockSteering>(node, "clocksteering", 100);
00278 }
00279
00280 if (publish_nmea_messages_)
00281 {
00282 gpgga_pub_ = swri::advertise<novatel_gps_msgs::Gpgga>(node,"gpgga", 100);
00283 gprmc_pub_ = swri::advertise<novatel_gps_msgs::Gprmc>(node,"gprmc", 100);
00284 }
00285
00286 if (publish_gpgsa_)
00287 {
00288 gpgsa_pub_ = swri::advertise<novatel_gps_msgs::Gpgsa>(node, "gpgsa", 100);
00289 }
00290
00291 if (publish_imu_messages_)
00292 {
00293 imu_pub_ = swri::advertise<sensor_msgs::Imu>(node, "imu", 100);
00294 novatel_imu_pub_= swri::advertise<novatel_gps_msgs::NovatelCorrectedImuData>(node, "corrimudata", 100);
00295 insstdev_pub_ = swri::advertise<novatel_gps_msgs::Insstdev>(node, "insstdev", 100);
00296 inspva_pub_ = swri::advertise<novatel_gps_msgs::Inspva>(node, "inspva", 100);
00297 inscov_pub_ = swri::advertise<novatel_gps_msgs::Inscov>(node, "inscov", 100);
00298 }
00299
00300 if (publish_gpgsv_)
00301 {
00302 gpgsv_pub_ = swri::advertise<novatel_gps_msgs::Gpgsv>(node, "gpgsv", 100);
00303 }
00304
00305 if (publish_novatel_positions_)
00306 {
00307 novatel_position_pub_ = swri::advertise<novatel_gps_msgs::NovatelPosition>(node, "bestpos", 100);
00308 }
00309
00310 if (publish_novatel_xyz_positions_)
00311 {
00312 novatel_xyz_position_pub_ = swri::advertise<novatel_gps_msgs::NovatelXYZ>(node, "bestxyz", 100);
00313 }
00314
00315 if (publish_novatel_utm_positions_)
00316 {
00317 novatel_utm_pub_ = swri::advertise<novatel_gps_msgs::NovatelUtmPosition>(node, "bestutm", 100);
00318 }
00319
00320 if (publish_novatel_velocity_)
00321 {
00322 novatel_velocity_pub_ = swri::advertise<novatel_gps_msgs::NovatelVelocity>(node, "bestvel", 100);
00323 }
00324
00325 if (publish_novatel_heading2_)
00326 {
00327 novatel_heading2_pub_ = swri::advertise<novatel_gps_msgs::NovatelHeading2>(node, "heading2", 100);
00328 }
00329
00330 if (publish_novatel_dual_antenna_heading_)
00331 {
00332 novatel_dual_antenna_heading_pub_ = swri::advertise<novatel_gps_msgs::NovatelDualAntennaHeading>(node, "dual_antenna_heading", 100);
00333 }
00334
00335 if (publish_range_messages_)
00336 {
00337 range_pub_ = swri::advertise<novatel_gps_msgs::Range>(node, "range", 100);
00338 }
00339
00340 if (publish_time_messages_)
00341 {
00342 time_pub_ = swri::advertise<novatel_gps_msgs::Time>(node, "time", 100);
00343 }
00344
00345 if (publish_trackstat_)
00346 {
00347 trackstat_pub_ = swri::advertise<novatel_gps_msgs::Trackstat>(node, "trackstat", 100);
00348 }
00349
00350 hw_id_ = "Novatel GPS (" + device_ +")";
00351 if (publish_diagnostics_)
00352 {
00353 diagnostic_updater_.setHardwareID(hw_id_);
00354 diagnostic_updater_.add("Connection",
00355 this,
00356 &NovatelGpsNodelet::DeviceDiagnostic);
00357 diagnostic_updater_.add("Hardware",
00358 this,
00359 &NovatelGpsNodelet::GpsDiagnostic);
00360 diagnostic_updater_.add("Data",
00361 this,
00362 &NovatelGpsNodelet::DataDiagnostic);
00363 diagnostic_updater_.add("Rate",
00364 this,
00365 &NovatelGpsNodelet::RateDiagnostic);
00366 diagnostic_updater_.add("GPS Fix",
00367 this,
00368 &NovatelGpsNodelet::FixDiagnostic);
00369 if (publish_sync_diagnostic_)
00370 {
00371 diagnostic_updater_.add("Sync",
00372 this,
00373 &NovatelGpsNodelet::SyncDiagnostic);
00374 }
00375 }
00376
00377 gps_.ApplyVehicleBodyRotation(span_frame_to_ros_frame_);
00378
00379 thread_ = boost::thread(&NovatelGpsNodelet::Spin, this);
00380 NODELET_INFO("%s initialized", hw_id_.c_str());
00381 }
00382
00383 void SyncCallback(const std_msgs::TimeConstPtr& sync)
00384 {
00385 boost::unique_lock<boost::mutex> lock(mutex_);
00386 sync_times_.push_back(sync->data);
00387 }
00388
00393 void Spin()
00394 {
00395 std::string format_suffix;
00396 if (use_binary_messages_)
00397 {
00398
00399
00400 format_suffix = "b";
00401 }
00402 else
00403 {
00404 format_suffix = "a";
00405 }
00406
00407 NovatelMessageOpts opts;
00408 opts["gpgga"] = polling_period_;
00409 opts["gprmc"] = polling_period_;
00410 opts["bestpos" + format_suffix] = polling_period_;
00411 opts["time" + format_suffix] = 1.0;
00412 if (publish_novatel_xyz_positions_)
00413 {
00414 opts["bestxyz" + format_suffix] = polling_period_;
00415 }
00416 if (publish_novatel_utm_positions_)
00417 {
00418 opts["bestutm" + format_suffix] = polling_period_;
00419 }
00420 if (publish_novatel_heading2_)
00421 {
00422 opts["heading2" + format_suffix] = polling_period_;
00423 }
00424 if (publish_novatel_dual_antenna_heading_)
00425 {
00426 opts["dual_antenna_heading" + format_suffix] = polling_period_;
00427 }
00428 if (publish_gpgsa_)
00429 {
00430 opts["gpgsa"] = polling_period_;
00431 }
00432 if (publish_gpgsv_)
00433 {
00434 opts["gpgsv"] = 1.0;
00435 }
00436 if (publish_clock_steering_)
00437 {
00438 opts["clocksteering" + format_suffix] = 1.0;
00439 }
00440 if (publish_imu_messages_)
00441 {
00442 double period = 1.0 / imu_rate_;
00443 opts["corrimudata" + format_suffix] = period;
00444 opts["inscov" + format_suffix] = 1.0;
00445 opts["inspva" + format_suffix] = period;
00446 opts["insstdev" + format_suffix] = 1.0;
00447 if (!use_binary_messages_)
00448 {
00449 NODELET_WARN("Using the ASCII message format with CORRIMUDATA logs is not recommended. "
00450 "A serial link will not be able to keep up with the data rate.");
00451 }
00452
00453
00454 if (imu_sample_rate_ > 0)
00455 {
00456 gps_.SetImuRate(imu_sample_rate_, true);
00457 }
00458 }
00459 if (publish_novatel_velocity_)
00460 {
00461 opts["bestvel" + format_suffix] = polling_period_;
00462 }
00463 if (publish_range_messages_)
00464 {
00465 opts["range" + format_suffix] = 1.0;
00466 }
00467 if (publish_trackstat_)
00468 {
00469 opts["trackstat" + format_suffix] = 1.0;
00470 }
00471
00472 if (connection_ == NovatelGps::SERIAL)
00473 {
00474 gps_.SetSerialBaud(serial_baud_);
00475 }
00476 while (ros::ok())
00477 {
00478 if (gps_.Connect(device_, connection_, opts))
00479 {
00480
00481 NODELET_INFO("%s connected to device", hw_id_.c_str());
00482 while (gps_.IsConnected() && ros::ok())
00483 {
00484
00485 CheckDeviceForData();
00486
00487
00488
00489
00490 if (publish_diagnostics_)
00491 {
00492 diagnostic_updater_.update();
00493 }
00494
00495
00496 ros::spinOnce();
00497
00498 boost::this_thread::sleep(boost::posix_time::microseconds(1));
00499 }
00500 }
00501 else
00502 {
00503 NODELET_ERROR_THROTTLE(1, "Error connecting to device <%s:%s>: %s",
00504 connection_type_.c_str(),
00505 device_.c_str(),
00506 gps_.ErrorMsg().c_str());
00507 device_errors_++;
00508 error_msg_ = gps_.ErrorMsg();
00509 }
00510
00511 if (ros::ok())
00512 {
00513
00514
00515 ros::Duration(reconnect_delay_s_).sleep();
00516 }
00517
00518
00519
00520
00521 if (publish_diagnostics_)
00522 {
00523 diagnostic_updater_.update();
00524 }
00525
00526
00527 ros::spinOnce();
00528
00529 boost::this_thread::sleep(boost::posix_time::microseconds(1));
00530
00531 if (connection_ == NovatelGps::PCAP)
00532 {
00533
00534 ros::shutdown();
00535 }
00536 }
00537
00538 gps_.Disconnect();
00539 NODELET_INFO("%s disconnected and shut down", hw_id_.c_str());
00540 }
00541
00542 private:
00543
00545 std::string device_;
00547 std::string connection_type_;
00549 int32_t serial_baud_;
00550 double polling_period_;
00551 bool publish_gpgsa_;
00552 bool publish_gpgsv_;
00554 double imu_rate_;
00556 double imu_sample_rate_;
00557 bool span_frame_to_ros_frame_;
00558 bool publish_clock_steering_;
00559 bool publish_imu_messages_;
00560 bool publish_novatel_positions_;
00561 bool publish_novatel_xyz_positions_;
00562 bool publish_novatel_utm_positions_;
00563 bool publish_novatel_velocity_;
00564 bool publish_novatel_heading2_;
00565 bool publish_novatel_dual_antenna_heading_;
00566 bool publish_nmea_messages_;
00567 bool publish_range_messages_;
00568 bool publish_time_messages_;
00569 bool publish_trackstat_;
00570 bool publish_diagnostics_;
00571 bool publish_sync_diagnostic_;
00572 double reconnect_delay_s_;
00573 bool use_binary_messages_;
00574
00575 ros::Publisher clocksteering_pub_;
00576 ros::Publisher fix_pub_;
00577 ros::Publisher gps_pub_;
00578 ros::Publisher imu_pub_;
00579 ros::Publisher inscov_pub_;
00580 ros::Publisher inspva_pub_;
00581 ros::Publisher insstdev_pub_;
00582 ros::Publisher novatel_imu_pub_;
00583 ros::Publisher novatel_position_pub_;
00584 ros::Publisher novatel_xyz_position_pub_;
00585 ros::Publisher novatel_utm_pub_;
00586 ros::Publisher novatel_velocity_pub_;
00587 ros::Publisher novatel_heading2_pub_;
00588 ros::Publisher novatel_dual_antenna_heading_pub_;
00589 ros::Publisher gpgga_pub_;
00590 ros::Publisher gpgsv_pub_;
00591 ros::Publisher gpgsa_pub_;
00592 ros::Publisher gprmc_pub_;
00593 ros::Publisher range_pub_;
00594 ros::Publisher time_pub_;
00595 ros::Publisher trackstat_pub_;
00596
00597 ros::ServiceServer reset_service_;
00598
00599 NovatelGps::ConnectionType connection_;
00600 NovatelGps gps_;
00601
00602 boost::thread thread_;
00603 boost::mutex mutex_;
00604
00606 swri::Subscriber sync_sub_;
00607 ros::Time last_sync_;
00609 boost::circular_buffer<ros::Time> sync_times_;
00611 boost::circular_buffer<ros::Time> msg_times_;
00613 stats::accumulator_set<float, stats::stats<
00614 stats::tag::max,
00615 stats::tag::min,
00616 stats::tag::mean,
00617 stats::tag::variance> > offset_stats_;
00619 stats::accumulator_set<float, stats::stats<stats::tag::rolling_mean> > rolling_offset_;
00620
00621
00622 std::string error_msg_;
00623 diagnostic_updater::Updater diagnostic_updater_;
00624 std::string hw_id_;
00625 double expected_rate_;
00626 int32_t device_timeouts_;
00627 int32_t device_interrupts_;
00628 int32_t device_errors_;
00629 int32_t gps_parse_failures_;
00630 int32_t gps_insufficient_data_warnings_;
00631 int32_t publish_rate_warnings_;
00632 int32_t measurement_count_;
00633 ros::Time last_published_;
00634 novatel_gps_msgs::NovatelPositionPtr last_novatel_position_;
00635
00636 std::string imu_frame_id_;
00637 std::string frame_id_;
00638
00642 bool resetService(novatel_gps_msgs::NovatelFRESET::Request& req,
00643 novatel_gps_msgs::NovatelFRESET::Response& res)
00644 {
00645 if (gps_.IsConnected() == false)
00646 {
00647 res.success = false;
00648 }
00649
00650
00651 std::string command = "FRESET ";
00652 command += req.target.length() ? "STANDARD" : req.target;
00653 command += "\r\n";
00654 gps_.Write(command);
00655
00656 if (req.target.length() == 0)
00657 {
00658 ROS_WARN("No FRESET target specified. Doing FRESET STANDARD. This may be undesired behavior.");
00659 }
00660
00661 res.success = true;
00662 return true;
00663 }
00664
00671 void CheckDeviceForData()
00672 {
00673 std::vector<novatel_gps_msgs::NovatelPositionPtr> position_msgs;
00674 std::vector<novatel_gps_msgs::NovatelXYZPtr> xyz_position_msgs;
00675 std::vector<novatel_gps_msgs::NovatelUtmPositionPtr> utm_msgs;
00676 std::vector<novatel_gps_msgs::NovatelHeading2Ptr> heading2_msgs;
00677 std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr> dual_antenna_heading_msgs;
00678 std::vector<gps_common::GPSFixPtr> fix_msgs;
00679 std::vector<novatel_gps_msgs::GpggaPtr> gpgga_msgs;
00680 std::vector<novatel_gps_msgs::GprmcPtr> gprmc_msgs;
00681
00682
00683 NovatelGps::ReadResult result = gps_.ProcessData();
00684 if (result == NovatelGps::READ_ERROR)
00685 {
00686 NODELET_ERROR_THROTTLE(1, "Error reading from device <%s:%s>: %s",
00687 connection_type_.c_str(),
00688 device_.c_str(),
00689 gps_.ErrorMsg().c_str());
00690 device_errors_++;
00691 }
00692 else if (result == NovatelGps::READ_TIMEOUT)
00693 {
00694 device_timeouts_++;
00695 }
00696 else if (result == NovatelGps::READ_INTERRUPTED)
00697 {
00698
00699
00700 device_interrupts_++;
00701 }
00702 else if (result == NovatelGps::READ_PARSE_FAILED)
00703 {
00704 NODELET_ERROR("Error reading from device <%s:%s>: %s",
00705 connection_type_.c_str(),
00706 device_.c_str(),
00707 gps_.ErrorMsg().c_str());
00708 gps_parse_failures_++;
00709 }
00710 else if (result == NovatelGps::READ_INSUFFICIENT_DATA)
00711 {
00712 gps_insufficient_data_warnings_++;
00713 }
00714
00715
00716 gps_.GetGpggaMessages(gpgga_msgs);
00717 gps_.GetGprmcMessages(gprmc_msgs);
00718 gps_.GetNovatelPositions(position_msgs);
00719 gps_.GetNovatelXYZPositions(xyz_position_msgs);
00720 gps_.GetNovatelUtmPositions(utm_msgs);
00721 gps_.GetFixMessages(fix_msgs);
00722 gps_.GetNovatelHeading2Messages(heading2_msgs);
00723 gps_.GetNovatelDualAntennaHeadingMessages(dual_antenna_heading_msgs);
00724
00725
00726
00727 measurement_count_ += gpgga_msgs.size();
00728
00729
00730 if (!position_msgs.empty())
00731 {
00732 last_novatel_position_ = position_msgs.back();
00733 }
00734
00735
00736
00737
00738 for (const auto& msg : gpgga_msgs)
00739 {
00740 if (msg->utc_seconds != 0)
00741 {
00742 int64_t second = static_cast<int64_t>(swri_math_util::Round(msg->utc_seconds));
00743 double difference = std::fabs(msg->utc_seconds - second);
00744
00745 if (difference < 0.02)
00746 {
00747 msg_times_.push_back(msg->header.stamp);
00748 }
00749 }
00750 }
00751
00752
00753
00754
00755 CalculateTimeSync();
00756
00757
00758
00759
00760 ros::Duration sync_offset(0);
00761 if (last_sync_ != ros::TIME_MIN)
00762 {
00763 sync_offset = ros::Duration(stats::rolling_mean(rolling_offset_));
00764 }
00765 NODELET_DEBUG_STREAM("GPS TimeSync offset is " << sync_offset);
00766
00767 if (publish_nmea_messages_)
00768 {
00769 for (const auto& msg : gpgga_msgs)
00770 {
00771 msg->header.stamp += sync_offset;
00772 msg->header.frame_id = frame_id_;
00773 gpgga_pub_.publish(msg);
00774 }
00775
00776 for (const auto& msg : gprmc_msgs)
00777 {
00778 msg->header.stamp += sync_offset;
00779 msg->header.frame_id = frame_id_;
00780 gprmc_pub_.publish(msg);
00781 }
00782 }
00783
00784 if (publish_gpgsa_)
00785 {
00786 std::vector<novatel_gps_msgs::GpgsaPtr> gpgsa_msgs;
00787 gps_.GetGpgsaMessages(gpgsa_msgs);
00788 for (const auto& msg : gpgsa_msgs)
00789 {
00790 msg->header.stamp = ros::Time::now();
00791 msg->header.frame_id = frame_id_;
00792 gpgsa_pub_.publish(msg);
00793 }
00794 }
00795
00796 if (publish_gpgsv_)
00797 {
00798 std::vector<novatel_gps_msgs::GpgsvPtr> gpgsv_msgs;
00799 gps_.GetGpgsvMessages(gpgsv_msgs);
00800 for (const auto& msg : gpgsv_msgs)
00801 {
00802 msg->header.stamp = ros::Time::now();
00803 msg->header.frame_id = frame_id_;
00804 gpgsv_pub_.publish(msg);
00805 }
00806 }
00807
00808 if (publish_novatel_positions_)
00809 {
00810 for (const auto& msg : position_msgs)
00811 {
00812 msg->header.stamp += sync_offset;
00813 msg->header.frame_id = frame_id_;
00814 novatel_position_pub_.publish(msg);
00815 }
00816 }
00817
00818 if (publish_novatel_xyz_positions_)
00819 {
00820 for (const auto& msg : xyz_position_msgs)
00821 {
00822 msg->header.stamp += sync_offset;
00823 msg->header.frame_id = frame_id_;
00824 novatel_xyz_position_pub_.publish(msg);
00825 }
00826 }
00827
00828 if (publish_novatel_utm_positions_)
00829 {
00830 for (const auto& msg : utm_msgs)
00831 {
00832 msg->header.stamp += sync_offset;
00833 msg->header.frame_id = frame_id_;
00834 novatel_utm_pub_.publish(msg);
00835 }
00836 }
00837
00838 if (publish_novatel_heading2_)
00839 {
00840 for (const auto& msg : heading2_msgs)
00841 {
00842 msg->header.stamp += sync_offset;
00843 msg->header.frame_id = frame_id_;
00844 novatel_heading2_pub_.publish(msg);
00845 }
00846 }
00847
00848 if (publish_novatel_dual_antenna_heading_)
00849 {
00850 for (const auto& msg : dual_antenna_heading_msgs)
00851 {
00852 msg->header.stamp += sync_offset;
00853 msg->header.frame_id = frame_id_;
00854 novatel_dual_antenna_heading_pub_.publish(msg);
00855 }
00856 }
00857
00858 if (publish_clock_steering_)
00859 {
00860 std::vector<novatel_gps_msgs::ClockSteeringPtr> msgs;
00861 gps_.GetClockSteeringMessages(msgs);
00862 for (const auto& msg : msgs)
00863 {
00864 clocksteering_pub_.publish(msg);
00865 }
00866 }
00867
00868 if (publish_novatel_velocity_)
00869 {
00870 std::vector<novatel_gps_msgs::NovatelVelocityPtr> velocity_msgs;
00871 gps_.GetNovatelVelocities(velocity_msgs);
00872 for (const auto& msg : velocity_msgs)
00873 {
00874 msg->header.stamp += sync_offset;
00875 msg->header.frame_id = frame_id_;
00876 novatel_velocity_pub_.publish(msg);
00877 }
00878 }
00879 if (publish_time_messages_)
00880 {
00881 std::vector<novatel_gps_msgs::TimePtr> time_msgs;
00882 gps_.GetTimeMessages(time_msgs);
00883 for (const auto& msg : time_msgs)
00884 {
00885 msg->header.stamp += sync_offset;
00886 msg->header.frame_id = frame_id_;
00887 time_pub_.publish(msg);
00888 }
00889 }
00890 if (publish_range_messages_)
00891 {
00892 std::vector<novatel_gps_msgs::RangePtr> range_msgs;
00893 gps_.GetRangeMessages(range_msgs);
00894 for (const auto& msg : range_msgs)
00895 {
00896 msg->header.stamp += sync_offset;
00897 msg->header.frame_id = frame_id_;
00898 range_pub_.publish(msg);
00899 }
00900 }
00901 if (publish_trackstat_)
00902 {
00903 std::vector<novatel_gps_msgs::TrackstatPtr> trackstat_msgs;
00904 gps_.GetTrackstatMessages(trackstat_msgs);
00905 for (const auto& msg : trackstat_msgs)
00906 {
00907 msg->header.stamp += sync_offset;
00908 msg->header.frame_id = frame_id_;
00909 trackstat_pub_.publish(msg);
00910 }
00911 }
00912 if (publish_imu_messages_)
00913 {
00914 std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> novatel_imu_msgs;
00915 gps_.GetNovatelCorrectedImuData(novatel_imu_msgs);
00916 for (const auto& msg : novatel_imu_msgs)
00917 {
00918 msg->header.stamp += sync_offset;
00919 msg->header.frame_id = imu_frame_id_;
00920 novatel_imu_pub_.publish(msg);
00921 }
00922
00923 std::vector<sensor_msgs::ImuPtr> imu_msgs;
00924 gps_.GetImuMessages(imu_msgs);
00925 for (const auto& msg : imu_msgs)
00926 {
00927 msg->header.stamp += sync_offset;
00928 msg->header.frame_id = imu_frame_id_;
00929 imu_pub_.publish(msg);
00930 }
00931
00932 std::vector<novatel_gps_msgs::InscovPtr> inscov_msgs;
00933 gps_.GetInscovMessages(inscov_msgs);
00934 for (const auto& msg : inscov_msgs)
00935 {
00936 msg->header.stamp += sync_offset;
00937 msg->header.frame_id = imu_frame_id_;
00938 inscov_pub_.publish(msg);
00939 }
00940
00941 std::vector<novatel_gps_msgs::InspvaPtr> inspva_msgs;
00942 gps_.GetInspvaMessages(inspva_msgs);
00943 for (const auto& msg : inspva_msgs)
00944 {
00945 msg->header.stamp += sync_offset;
00946 msg->header.frame_id = imu_frame_id_;
00947 inspva_pub_.publish(msg);
00948 }
00949
00950 std::vector<novatel_gps_msgs::InsstdevPtr> insstdev_msgs;
00951 gps_.GetInsstdevMessages(insstdev_msgs);
00952 for (const auto& msg : insstdev_msgs)
00953 {
00954 msg->header.stamp += sync_offset;
00955 msg->header.frame_id = imu_frame_id_;
00956 insstdev_pub_.publish(msg);
00957 }
00958 }
00959
00960 for (const auto& msg : fix_msgs)
00961 {
00962 msg->header.stamp += sync_offset;
00963 msg->header.frame_id = frame_id_;
00964 gps_pub_.publish(msg);
00965
00966 if (fix_pub_.getNumSubscribers() > 0)
00967 {
00968 sensor_msgs::NavSatFixPtr fix_msg = ConvertGpsFixToNavSatFix(msg);
00969
00970 fix_pub_.publish(fix_msg);
00971 }
00972
00973
00974
00975
00976 if (last_published_ != ros::TIME_MIN &&
00977 (msg->header.stamp - last_published_).toSec() > 1.5 * (1.0 / expected_rate_))
00978 {
00979 publish_rate_warnings_++;
00980 }
00981
00982 last_published_ = msg->header.stamp;
00983 }
00984 }
00985
00986 sensor_msgs::NavSatFixPtr ConvertGpsFixToNavSatFix(const gps_common::GPSFixPtr& msg)
00987 {
00988 sensor_msgs::NavSatFixPtr fix_msg = boost::make_shared<sensor_msgs::NavSatFix>();
00989 fix_msg->header = msg->header;
00990 fix_msg->latitude = msg->latitude;
00991 fix_msg->longitude = msg->longitude;
00992 fix_msg->altitude = msg->altitude;
00993 fix_msg->position_covariance = msg->position_covariance;
00994 switch (msg->status.status)
00995 {
00996 case gps_common::GPSStatus::STATUS_NO_FIX:
00997 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
00998 break;
00999 case gps_common::GPSStatus::STATUS_FIX:
01000 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
01001 break;
01002 case gps_common::GPSStatus::STATUS_SBAS_FIX:
01003 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_SBAS_FIX;
01004 break;
01005 case gps_common::GPSStatus::STATUS_GBAS_FIX:
01006 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
01007 break;
01008 case gps_common::GPSStatus::STATUS_DGPS_FIX:
01009 case gps_common::GPSStatus::STATUS_WAAS_FIX:
01010 default:
01011 ROS_WARN_ONCE("Unsupported fix status: %d", msg->status.status);
01012 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
01013 break;
01014 }
01015 switch (msg->position_covariance_type)
01016 {
01017 case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
01018 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
01019 break;
01020 case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
01021 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
01022 break;
01023 case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
01024 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
01025 break;
01026 case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
01027 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
01028 break;
01029 default:
01030 ROS_WARN_ONCE("Unsupported covariance type: %d", msg->position_covariance_type);
01031 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
01032 break;
01033 }
01034
01035 fix_msg->status.service = 0;
01036
01037 return fix_msg;
01038 }
01039
01044 void CalculateTimeSync()
01045 {
01046 boost::unique_lock<boost::mutex> lock(mutex_);
01047 int32_t synced_i = -1;
01048 int32_t synced_j = -1;
01049
01050 for (int32_t i = 0; i < sync_times_.size(); i++)
01051 {
01052
01053 for (int32_t j = synced_j + 1; j < msg_times_.size(); j++)
01054 {
01055
01056 double offset = (sync_times_[i] - msg_times_[j]).toSec();
01057 if (std::fabs(offset) < 0.49)
01058 {
01059
01060 synced_i = static_cast<int32_t>(i);
01061 synced_j = static_cast<int32_t>(j);
01062
01063 offset_stats_(offset);
01064 rolling_offset_(offset);
01065
01066 last_sync_ = sync_times_[i];
01067
01068 break;
01069 }
01070 }
01071 }
01072
01073
01074 for (int i = 0; i <= synced_i && !sync_times_.empty(); i++)
01075 {
01076 sync_times_.pop_front();
01077 }
01078
01079
01080 for (int j = 0; j <= synced_j && !msg_times_.empty(); j++)
01081 {
01082 msg_times_.pop_front();
01083 }
01084 }
01085
01086 void FixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
01087 {
01088 status.clear();
01089 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
01090
01091 if (!last_novatel_position_)
01092 {
01093 status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No Status");
01094 NODELET_WARN("No GPS status data.");
01095 return;
01096 }
01097
01098 status.add("Solution Status", last_novatel_position_->solution_status);
01099 status.add("Position Type", last_novatel_position_->position_type);
01100 status.add("Solution Age", last_novatel_position_->solution_age);
01101 status.add("Satellites Tracked", static_cast<int>(last_novatel_position_->num_satellites_tracked));
01102 status.add("Satellites Used", static_cast<int>(last_novatel_position_->num_satellites_used_in_solution));
01103 status.add("Software Version", last_novatel_position_->novatel_msg_header.receiver_software_version);
01104
01105 const novatel_gps_msgs::NovatelReceiverStatus& rcvr_status = last_novatel_position_->novatel_msg_header.receiver_status;
01106 status.add("Status Code", rcvr_status.original_status_code);
01107
01108 if (last_novatel_position_->novatel_msg_header.receiver_status.original_status_code != 0)
01109 {
01110 uint8_t level = diagnostic_msgs::DiagnosticStatus::WARN;
01111 std::string msg = "Status Warning";
01112
01113 if (rcvr_status.antenna_is_open ||
01114 rcvr_status.antenna_is_shorted ||
01115 !rcvr_status.antenna_powered)
01116 {
01117 msg += " Antenna Problem";
01118 level = diagnostic_msgs::DiagnosticStatus::ERROR;
01119 }
01120 status.add("Error Flag", rcvr_status.error_flag?"true":"false");
01121 status.add("Temperature Flag", rcvr_status.temperature_flag?"true":"false");
01122 status.add("Voltage Flag", rcvr_status.voltage_supply_flag?"true":"false");
01123 status.add("Antenna Not Powered", rcvr_status.antenna_powered?"false":"true");
01124 status.add("Antenna Open", rcvr_status.antenna_is_open?"true":"false");
01125 status.add("Antenna Shorted", rcvr_status.antenna_is_shorted?"true":"false");
01126 status.add("CPU Overloaded", rcvr_status.cpu_overload_flag?"true":"false");
01127 status.add("COM1 Buffer Overrun", rcvr_status.com1_buffer_overrun?"true":"false");
01128 status.add("COM2 Buffer Overrun", rcvr_status.com2_buffer_overrun?"true":"false");
01129 status.add("COM3 Buffer Overrun", rcvr_status.com3_buffer_overrun?"true":"false");
01130 status.add("USB Buffer Overrun", rcvr_status.usb_buffer_overrun?"true":"false");
01131 status.add("RF1 AGC Flag", rcvr_status.rf1_agc_flag?"true":"false");
01132 status.add("RF2 AGC Flag", rcvr_status.rf2_agc_flag?"true":"false");
01133 status.add("Almanac Flag", rcvr_status.almanac_flag?"true":"false");
01134 status.add("Position Solution Flag", rcvr_status.position_solution_flag?"true":"false");
01135 status.add("Position Fixed Flag", rcvr_status.position_fixed_flag?"true":"false");
01136 status.add("Clock Steering Status", rcvr_status.clock_steering_status_enabled?"true":"false");
01137 status.add("Clock Model Flag", rcvr_status.clock_model_flag?"true":"false");
01138 status.add("OEMV External Oscillator Flag", rcvr_status.oemv_external_oscillator_flag?"true":"false");
01139 status.add("Software Resource Flag", rcvr_status.software_resource_flag?"true":"false");
01140 status.add("Auxiliary1 Flag", rcvr_status.aux1_status_event_flag?"true":"false");
01141 status.add("Auxiliary2 Flag", rcvr_status.aux2_status_event_flag?"true":"false");
01142 status.add("Auxiliary3 Flag", rcvr_status.aux3_status_event_flag?"true":"false");
01143 NODELET_WARN("Novatel status code: %d", rcvr_status.original_status_code);
01144 status.summary(level, msg);
01145 }
01146 }
01147
01148 void SyncDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
01149 {
01150 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
01151
01152 if (last_sync_ == ros::TIME_MIN)
01153 {
01154 status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No Sync");
01155 return;
01156 }
01157 else if (last_sync_ < ros::Time::now() - ros::Duration(10))
01158 {
01159 status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Sync Stale");
01160 NODELET_ERROR("GPS time synchronization is stale.");
01161 }
01162
01163 status.add("Last Sync", last_sync_);
01164 status.add("Mean Offset", stats::mean(offset_stats_));
01165 status.add("Mean Offset (rolling)", stats::rolling_mean(rolling_offset_));
01166 status.add("Offset Variance", stats::variance(offset_stats_));
01167 status.add("Min Offset", stats::min(offset_stats_));
01168 status.add("Max Offset", stats::max(offset_stats_));
01169 }
01170
01171 void DeviceDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
01172 {
01173 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
01174
01175 if (device_errors_ > 0)
01176 {
01177 status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Device Errors");
01178 }
01179 else if (device_interrupts_ > 0)
01180 {
01181 status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Device Interrupts");
01182 NODELET_WARN("device interrupts detected <%s:%s>: %d",
01183 connection_type_.c_str(), device_.c_str(), device_interrupts_);
01184 }
01185 else if (device_timeouts_)
01186 {
01187 status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Device Timeouts");
01188 NODELET_WARN("device timeouts detected <%s:%s>: %d",
01189 connection_type_.c_str(), device_.c_str(), device_timeouts_);
01190 }
01191
01192 status.add("Errors", device_errors_);
01193 status.add("Interrupts", device_interrupts_);
01194 status.add("Timeouts", device_timeouts_);
01195
01196 device_timeouts_ = 0;
01197 device_interrupts_ = 0;
01198 device_errors_ = 0;
01199 }
01200
01201 void GpsDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
01202 {
01203 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
01204
01205 if (gps_parse_failures_ > 0)
01206 {
01207 status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Parse Failures");
01208 NODELET_WARN("gps parse failures detected <%s>: %d",
01209 hw_id_.c_str(), gps_parse_failures_);
01210 }
01211
01212 status.add("Parse Failures", gps_parse_failures_);
01213 status.add("Insufficient Data Warnings", gps_insufficient_data_warnings_);
01214
01215 gps_parse_failures_ = 0;
01216 gps_insufficient_data_warnings_ = 0;
01217 }
01218
01219 void DataDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
01220 {
01221 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
01222
01223 double period = diagnostic_updater_.getPeriod();
01224 double measured_rate = measurement_count_ / period;
01225
01226 if (measured_rate < 0.5 * expected_rate_)
01227 {
01228 status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Insufficient Data Rate");
01229 NODELET_ERROR("insufficient data rate <%s>: %lf < %lf",
01230 hw_id_.c_str(), measured_rate, expected_rate_);
01231 }
01232 else if (measured_rate < 0.95 * expected_rate_)
01233 {
01234 status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Insufficient Data Rate");
01235 NODELET_WARN("insufficient data rate <%s>: %lf < %lf",
01236 hw_id_.c_str(), measured_rate, expected_rate_);
01237 }
01238
01239 status.add("Measurement Rate (Hz)", measured_rate);
01240
01241 measurement_count_ = 0;
01242 }
01243
01244 void RateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
01245 {
01246 status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal Publish Rate");
01247
01248 double elapsed = (ros::Time::now() - last_published_).toSec();
01249 bool gap_detected = false;
01250 if (elapsed > 2.0 / expected_rate_)
01251 {
01252 publish_rate_warnings_++;
01253 gap_detected = true;
01254 }
01255
01256 if (publish_rate_warnings_ > 1 || gap_detected)
01257 {
01258 status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Insufficient Publish Rate");
01259 NODELET_WARN("publish rate failures detected <%s>: %d",
01260 hw_id_.c_str(), publish_rate_warnings_);
01261 }
01262
01263 status.add("Warnings", publish_rate_warnings_);
01264
01265 publish_rate_warnings_ = 0;
01266 }
01267 };
01268 }
01269
01270
01271 #include <swri_nodelet/class_list_macros.h>
01272 SWRI_NODELET_EXPORT_CLASS(novatel_gps_driver, NovatelGpsNodelet)