131 #include <boost/accumulators/accumulators.hpp> 132 #include <boost/accumulators/statistics/max.hpp> 133 #include <boost/accumulators/statistics/mean.hpp> 134 #include <boost/accumulators/statistics/min.hpp> 135 #include <boost/accumulators/statistics/rolling_mean.hpp> 136 #include <boost/accumulators/statistics/stats.hpp> 137 #include <boost/accumulators/statistics/tail.hpp> 138 #include <boost/accumulators/statistics/variance.hpp> 139 #include <boost/circular_buffer.hpp> 141 #include <diagnostic_msgs/DiagnosticStatus.h> 144 #include <gps_common/GPSFix.h> 146 #include <novatel_gps_msgs/NovatelCorrectedImuData.h> 147 #include <novatel_gps_msgs/NovatelFRESET.h> 148 #include <novatel_gps_msgs/NovatelMessageHeader.h> 149 #include <novatel_gps_msgs/NovatelPosition.h> 150 #include <novatel_gps_msgs/NovatelUtmPosition.h> 151 #include <novatel_gps_msgs/NovatelVelocity.h> 152 #include <novatel_gps_msgs/NovatelHeading2.h> 153 #include <novatel_gps_msgs/NovatelDualAntennaHeading.h> 154 #include <novatel_gps_msgs/Gpgga.h> 155 #include <novatel_gps_msgs/Gprmc.h> 156 #include <novatel_gps_msgs/Range.h> 157 #include <novatel_gps_msgs/Time.h> 160 #include <sensor_msgs/Imu.h> 161 #include <sensor_msgs/NavSatFix.h> 162 #include <std_msgs/Time.h> 168 namespace stats = boost::accumulators;
272 gps_pub_ = swri::advertise<gps_common::GPSFix>(node, gps_topic, 100);
273 fix_pub_ = swri::advertise<sensor_msgs::NavSatFix>(node,
"fix", 100);
277 clocksteering_pub_ = swri::advertise<novatel_gps_msgs::ClockSteering>(node,
"clocksteering", 100);
282 gpgga_pub_ = swri::advertise<novatel_gps_msgs::Gpgga>(node,
"gpgga", 100);
283 gprmc_pub_ = swri::advertise<novatel_gps_msgs::Gprmc>(node,
"gprmc", 100);
288 gpgsa_pub_ = swri::advertise<novatel_gps_msgs::Gpgsa>(node,
"gpgsa", 100);
293 imu_pub_ = swri::advertise<sensor_msgs::Imu>(node,
"imu", 100);
294 novatel_imu_pub_= swri::advertise<novatel_gps_msgs::NovatelCorrectedImuData>(node,
"corrimudata", 100);
295 insstdev_pub_ = swri::advertise<novatel_gps_msgs::Insstdev>(node,
"insstdev", 100);
296 inspva_pub_ = swri::advertise<novatel_gps_msgs::Inspva>(node,
"inspva", 100);
297 inscov_pub_ = swri::advertise<novatel_gps_msgs::Inscov>(node,
"inscov", 100);
302 gpgsv_pub_ = swri::advertise<novatel_gps_msgs::Gpgsv>(node,
"gpgsv", 100);
317 novatel_utm_pub_ = swri::advertise<novatel_gps_msgs::NovatelUtmPosition>(node,
"bestutm", 100);
337 range_pub_ = swri::advertise<novatel_gps_msgs::Range>(node,
"range", 100);
342 time_pub_ = swri::advertise<novatel_gps_msgs::Time>(node,
"time", 100);
347 trackstat_pub_ = swri::advertise<novatel_gps_msgs::Trackstat>(node,
"trackstat", 100);
385 boost::unique_lock<boost::mutex> lock(
mutex_);
395 std::string format_suffix;
411 opts[
"time" + format_suffix] = 1.0;
438 opts[
"clocksteering" + format_suffix] = 1.0;
443 opts[
"corrimudata" + format_suffix] = period;
444 opts[
"inscov" + format_suffix] = 1.0;
445 opts[
"inspva" + format_suffix] = period;
446 opts[
"insstdev" + format_suffix] = 1.0;
449 NODELET_WARN(
"Using the ASCII message format with CORRIMUDATA logs is not recommended. " 450 "A serial link will not be able to keep up with the data rate.");
465 opts[
"range" + format_suffix] = 1.0;
469 opts[
"trackstat" + format_suffix] = 1.0;
498 boost::this_thread::sleep(boost::posix_time::microseconds(1));
529 boost::this_thread::sleep(boost::posix_time::microseconds(1));
613 stats::accumulator_set<float, stats::stats<
619 stats::accumulator_set<float, stats::stats<stats::tag::rolling_mean> >
rolling_offset_;
643 novatel_gps_msgs::NovatelFRESET::Response& res)
651 std::string
command =
"FRESET ";
652 command += req.target.length() ?
"STANDARD" : req.target;
656 if (req.target.length() == 0)
658 ROS_WARN(
"No FRESET target specified. Doing FRESET STANDARD. This may be undesired behavior.");
673 std::vector<novatel_gps_msgs::NovatelPositionPtr> position_msgs;
674 std::vector<novatel_gps_msgs::NovatelXYZPtr> xyz_position_msgs;
675 std::vector<novatel_gps_msgs::NovatelUtmPositionPtr> utm_msgs;
676 std::vector<novatel_gps_msgs::NovatelHeading2Ptr> heading2_msgs;
677 std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr> dual_antenna_heading_msgs;
678 std::vector<gps_common::GPSFixPtr> fix_msgs;
679 std::vector<novatel_gps_msgs::GpggaPtr> gpgga_msgs;
680 std::vector<novatel_gps_msgs::GprmcPtr> gprmc_msgs;
687 connection_type_.c_str(),
700 device_interrupts_++;
705 connection_type_.c_str(),
708 gps_parse_failures_++;
712 gps_insufficient_data_warnings_++;
727 measurement_count_ += gpgga_msgs.size();
730 if (!position_msgs.empty())
732 last_novatel_position_ = position_msgs.back();
738 for (
const auto&
msg : gpgga_msgs)
740 if (
msg->utc_seconds != 0)
743 double difference = std::fabs(
msg->utc_seconds - second);
745 if (difference < 0.02)
747 msg_times_.push_back(
msg->header.stamp);
763 sync_offset =
ros::Duration(stats::rolling_mean(rolling_offset_));
767 if (publish_nmea_messages_)
769 for (
const auto&
msg : gpgga_msgs)
771 msg->header.stamp += sync_offset;
776 for (
const auto&
msg : gprmc_msgs)
778 msg->header.stamp += sync_offset;
786 std::vector<novatel_gps_msgs::GpgsaPtr> gpgsa_msgs;
788 for (
const auto&
msg : gpgsa_msgs)
798 std::vector<novatel_gps_msgs::GpgsvPtr> gpgsv_msgs;
800 for (
const auto&
msg : gpgsv_msgs)
808 if (publish_novatel_positions_)
810 for (
const auto&
msg : position_msgs)
812 msg->header.stamp += sync_offset;
818 if (publish_novatel_xyz_positions_)
820 for (
const auto&
msg : xyz_position_msgs)
822 msg->header.stamp += sync_offset;
828 if (publish_novatel_utm_positions_)
830 for (
const auto&
msg : utm_msgs)
832 msg->header.stamp += sync_offset;
838 if (publish_novatel_heading2_)
840 for (
const auto&
msg : heading2_msgs)
842 msg->header.stamp += sync_offset;
848 if (publish_novatel_dual_antenna_heading_)
850 for (
const auto&
msg : dual_antenna_heading_msgs)
852 msg->header.stamp += sync_offset;
854 novatel_dual_antenna_heading_pub_.
publish(
msg);
858 if (publish_clock_steering_)
860 std::vector<novatel_gps_msgs::ClockSteeringPtr> msgs;
862 for (
const auto&
msg : msgs)
868 if (publish_novatel_velocity_)
870 std::vector<novatel_gps_msgs::NovatelVelocityPtr> velocity_msgs;
872 for (
const auto&
msg : velocity_msgs)
874 msg->header.stamp += sync_offset;
879 if (publish_time_messages_)
881 std::vector<novatel_gps_msgs::TimePtr> time_msgs;
883 for (
const auto&
msg : time_msgs)
885 msg->header.stamp += sync_offset;
890 if (publish_range_messages_)
892 std::vector<novatel_gps_msgs::RangePtr> range_msgs;
894 for (
const auto&
msg : range_msgs)
896 msg->header.stamp += sync_offset;
901 if (publish_trackstat_)
903 std::vector<novatel_gps_msgs::TrackstatPtr> trackstat_msgs;
905 for (
const auto&
msg : trackstat_msgs)
907 msg->header.stamp += sync_offset;
912 if (publish_imu_messages_)
914 std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> novatel_imu_msgs;
916 for (
const auto&
msg : novatel_imu_msgs)
918 msg->header.stamp += sync_offset;
923 std::vector<sensor_msgs::ImuPtr> imu_msgs;
925 for (
const auto&
msg : imu_msgs)
927 msg->header.stamp += sync_offset;
932 std::vector<novatel_gps_msgs::InscovPtr> inscov_msgs;
934 for (
const auto&
msg : inscov_msgs)
936 msg->header.stamp += sync_offset;
941 std::vector<novatel_gps_msgs::InspvaPtr> inspva_msgs;
943 for (
const auto&
msg : inspva_msgs)
945 msg->header.stamp += sync_offset;
950 std::vector<novatel_gps_msgs::InsstdevPtr> insstdev_msgs;
952 for (
const auto&
msg : insstdev_msgs)
954 msg->header.stamp += sync_offset;
960 for (
const auto&
msg : fix_msgs)
962 msg->header.stamp += sync_offset;
979 publish_rate_warnings_++;
982 last_published_ =
msg->header.stamp;
988 sensor_msgs::NavSatFixPtr fix_msg = boost::make_shared<sensor_msgs::NavSatFix>();
989 fix_msg->header = msg->header;
990 fix_msg->latitude = msg->latitude;
991 fix_msg->longitude = msg->longitude;
992 fix_msg->altitude = msg->altitude;
993 fix_msg->position_covariance = msg->position_covariance;
994 switch (msg->status.status)
996 case gps_common::GPSStatus::STATUS_NO_FIX:
997 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
999 case gps_common::GPSStatus::STATUS_FIX:
1000 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
1002 case gps_common::GPSStatus::STATUS_SBAS_FIX:
1003 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_SBAS_FIX;
1005 case gps_common::GPSStatus::STATUS_GBAS_FIX:
1006 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
1008 case gps_common::GPSStatus::STATUS_DGPS_FIX:
1009 case gps_common::GPSStatus::STATUS_WAAS_FIX:
1011 ROS_WARN_ONCE(
"Unsupported fix status: %d", msg->status.status);
1012 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
1015 switch (msg->position_covariance_type)
1017 case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
1018 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
1020 case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
1021 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
1023 case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
1024 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
1026 case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
1027 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
1030 ROS_WARN_ONCE(
"Unsupported covariance type: %d", msg->position_covariance_type);
1031 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
1035 fix_msg->status.service = 0;
1046 boost::unique_lock<boost::mutex> lock(mutex_);
1047 int32_t synced_i = -1;
1048 int32_t synced_j = -1;
1050 for (int32_t i = 0; i < sync_times_.size(); i++)
1053 for (int32_t j = synced_j + 1; j < msg_times_.size(); j++)
1056 double offset = (sync_times_[i] - msg_times_[j]).toSec();
1057 if (std::fabs(offset) < 0.49)
1060 synced_i =
static_cast<int32_t
>(i);
1061 synced_j =
static_cast<int32_t
>(j);
1066 last_sync_ = sync_times_[i];
1074 for (
int i = 0; i <= synced_i && !sync_times_.empty(); i++)
1076 sync_times_.pop_front();
1080 for (
int j = 0; j <= synced_j && !msg_times_.empty(); j++)
1082 msg_times_.pop_front();
1089 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1091 if (!last_novatel_position_)
1093 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"No Status");
1098 status.
add(
"Solution Status", last_novatel_position_->solution_status);
1099 status.
add(
"Position Type", last_novatel_position_->position_type);
1100 status.
add(
"Solution Age", last_novatel_position_->solution_age);
1101 status.
add(
"Satellites Tracked", static_cast<int>(last_novatel_position_->num_satellites_tracked));
1102 status.
add(
"Satellites Used", static_cast<int>(last_novatel_position_->num_satellites_used_in_solution));
1103 status.
add(
"Software Version", last_novatel_position_->novatel_msg_header.receiver_software_version);
1105 const novatel_gps_msgs::NovatelReceiverStatus& rcvr_status = last_novatel_position_->novatel_msg_header.receiver_status;
1106 status.
add(
"Status Code", rcvr_status.original_status_code);
1108 if (last_novatel_position_->novatel_msg_header.receiver_status.original_status_code != 0)
1110 uint8_t level = diagnostic_msgs::DiagnosticStatus::WARN;
1111 std::string
msg =
"Status Warning";
1113 if (rcvr_status.antenna_is_open ||
1114 rcvr_status.antenna_is_shorted ||
1115 !rcvr_status.antenna_powered)
1117 msg +=
" Antenna Problem";
1118 level = diagnostic_msgs::DiagnosticStatus::ERROR;
1120 status.
add(
"Error Flag", rcvr_status.error_flag?
"true":
"false");
1121 status.
add(
"Temperature Flag", rcvr_status.temperature_flag?
"true":
"false");
1122 status.
add(
"Voltage Flag", rcvr_status.voltage_supply_flag?
"true":
"false");
1123 status.
add(
"Antenna Not Powered", rcvr_status.antenna_powered?
"false":
"true");
1124 status.
add(
"Antenna Open", rcvr_status.antenna_is_open?
"true":
"false");
1125 status.
add(
"Antenna Shorted", rcvr_status.antenna_is_shorted?
"true":
"false");
1126 status.
add(
"CPU Overloaded", rcvr_status.cpu_overload_flag?
"true":
"false");
1127 status.
add(
"COM1 Buffer Overrun", rcvr_status.com1_buffer_overrun?
"true":
"false");
1128 status.
add(
"COM2 Buffer Overrun", rcvr_status.com2_buffer_overrun?
"true":
"false");
1129 status.
add(
"COM3 Buffer Overrun", rcvr_status.com3_buffer_overrun?
"true":
"false");
1130 status.
add(
"USB Buffer Overrun", rcvr_status.usb_buffer_overrun?
"true":
"false");
1131 status.
add(
"RF1 AGC Flag", rcvr_status.rf1_agc_flag?
"true":
"false");
1132 status.
add(
"RF2 AGC Flag", rcvr_status.rf2_agc_flag?
"true":
"false");
1133 status.
add(
"Almanac Flag", rcvr_status.almanac_flag?
"true":
"false");
1134 status.
add(
"Position Solution Flag", rcvr_status.position_solution_flag?
"true":
"false");
1135 status.
add(
"Position Fixed Flag", rcvr_status.position_fixed_flag?
"true":
"false");
1136 status.
add(
"Clock Steering Status", rcvr_status.clock_steering_status_enabled?
"true":
"false");
1137 status.
add(
"Clock Model Flag", rcvr_status.clock_model_flag?
"true":
"false");
1138 status.
add(
"OEMV External Oscillator Flag", rcvr_status.oemv_external_oscillator_flag?
"true":
"false");
1139 status.
add(
"Software Resource Flag", rcvr_status.software_resource_flag?
"true":
"false");
1140 status.
add(
"Auxiliary1 Flag", rcvr_status.aux1_status_event_flag?
"true":
"false");
1141 status.
add(
"Auxiliary2 Flag", rcvr_status.aux2_status_event_flag?
"true":
"false");
1142 status.
add(
"Auxiliary3 Flag", rcvr_status.aux3_status_event_flag?
"true":
"false");
1143 NODELET_WARN(
"Novatel status code: %d", rcvr_status.original_status_code);
1150 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1154 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"No Sync");
1159 status.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Sync Stale");
1163 status.
add(
"Last Sync", last_sync_);
1164 status.
add(
"Mean Offset", stats::mean(offset_stats_));
1165 status.
add(
"Mean Offset (rolling)", stats::rolling_mean(rolling_offset_));
1166 status.
add(
"Offset Variance", stats::variance(offset_stats_));
1167 status.
add(
"Min Offset", stats::min(offset_stats_));
1168 status.
add(
"Max Offset", stats::max(offset_stats_));
1173 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1175 if (device_errors_ > 0)
1177 status.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Device Errors");
1179 else if (device_interrupts_ > 0)
1181 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Device Interrupts");
1185 else if (device_timeouts_)
1187 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Device Timeouts");
1192 status.
add(
"Errors", device_errors_);
1193 status.
add(
"Interrupts", device_interrupts_);
1194 status.
add(
"Timeouts", device_timeouts_);
1196 device_timeouts_ = 0;
1197 device_interrupts_ = 0;
1203 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1205 if (gps_parse_failures_ > 0)
1207 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Parse Failures");
1212 status.
add(
"Parse Failures", gps_parse_failures_);
1213 status.
add(
"Insufficient Data Warnings", gps_insufficient_data_warnings_);
1215 gps_parse_failures_ = 0;
1216 gps_insufficient_data_warnings_ = 0;
1221 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1223 double period = diagnostic_updater_.
getPeriod();
1224 double measured_rate = measurement_count_ / period;
1226 if (measured_rate < 0.5 * expected_rate_)
1228 status.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Insufficient Data Rate");
1232 else if (measured_rate < 0.95 * expected_rate_)
1234 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Insufficient Data Rate");
1239 status.
add(
"Measurement Rate (Hz)", measured_rate);
1241 measurement_count_ = 0;
1246 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal Publish Rate");
1249 bool gap_detected =
false;
1250 if (elapsed > 2.0 / expected_rate_)
1252 publish_rate_warnings_++;
1253 gap_detected =
true;
1256 if (publish_rate_warnings_ > 1 || gap_detected)
1258 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Insufficient Publish Rate");
1259 NODELET_WARN(
"publish rate failures detected <%s>: %d",
1263 status.
add(
"Warnings", publish_rate_warnings_);
1265 publish_rate_warnings_ = 0;
void GetInscovMessages(std::vector< novatel_gps_msgs::InscovPtr > &inscov_messages)
Provides any INSCOV messages that have been received since the last time this was called...
bool publish_novatel_dual_antenna_heading_
stats::accumulator_set< float, stats::stats< stats::tag::rolling_mean > > rolling_offset_
Rolling mean of time offset.
void GetNovatelPositions(std::vector< novatel_gps_msgs::NovatelPositionPtr > &positions)
Provides any BESTPOS messages that have been received since the last time this was called...
void GetFixMessages(std::vector< gps_common::GPSFixPtr > &fix_messages)
Provides any GPSFix messages that have been generated since the last time this was called...
ros::Publisher insstdev_pub_
bool span_frame_to_ros_frame_
#define NODELET_ERROR(...)
void GetClockSteeringMessages(std::vector< novatel_gps_msgs::ClockSteeringPtr > &clocksteering_msgs)
Provides any CLOCKSTEERING messages that have been received since the last time this was called...
bool publish_clock_steering_
double imu_sample_rate_
How frequently the device samples the IMU, in Hz.
void GetRangeMessages(std::vector< novatel_gps_msgs::RangePtr > &range_messages)
Provides any RANGE messages that have been received since the last time this was called.
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
int32_t measurement_count_
ros::Publisher gpgsv_pub_
int32_t gps_parse_failures_
ros::Publisher novatel_heading2_pub_
void summary(unsigned char lvl, const std::string s)
std::map< std::string, double > NovatelMessageOpts
Define NovatelMessageOpts as a map from message name to log period (seconds)
void GetNovatelUtmPositions(std::vector< novatel_gps_msgs::NovatelUtmPositionPtr > &utm_positions)
Provides any BESTUTM messages that have been received since the last time this was called...
boost::circular_buffer< ros::Time > msg_times_
Buffer of gps message time stamps.
std::string resolveName(const std::string &name, bool remap=true) const
ros::Publisher novatel_velocity_pub_
#define NODELET_ERROR_THROTTLE(rate,...)
void setHardwareID(const std::string &hwid)
ros::Publisher gpgsa_pub_
ros::Publisher gprmc_pub_
void add(const std::string &name, TaskFunction f)
void GetGpgsaMessages(std::vector< novatel_gps_msgs::GpgsaPtr > &gpgsa_messages)
Provides any GPGSA messages that have been received since the last time this was called.
void GetNovatelCorrectedImuData(std::vector< novatel_gps_msgs::NovatelCorrectedImuDataPtr > &imu_messages)
Provides any CORRIMUDATA messages that have been received since the last time this was called...
sensor_msgs::NavSatFixPtr ConvertGpsFixToNavSatFix(const gps_common::GPSFixPtr &msg)
void ApplyVehicleBodyRotation(const bool &apply_rotation)
Determines whether or not to apply a 90 degree counter-clockwise rotation about Z to the Novatel SPAN...
void GetNovatelVelocities(std::vector< novatel_gps_msgs::NovatelVelocityPtr > &velocities)
Provides any BESTVEL messages that have been received since the last time this was called...
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void GetGpgsvMessages(std::vector< novatel_gps_msgs::GpgsvPtr > &gpgsv_messages)
Provides any GPGSV messages that have been received since the last time this was called.
bool use_binary_messages_
static ConnectionType ParseConnection(const std::string &connection)
Converts the strings "udp", "tcp", or "serial" into the corresponding enum values.
ros::NodeHandle & getPrivateNodeHandle() const
void RateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
void GpsDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
ReadResult ProcessData()
Processes any data that has been received from the device since the last time this message was called...
ros::Publisher inspva_pub_
void SetImuRate(double imu_rate, bool force=true)
Sets the IMU rate; necessary for producing sensor_msgs/Imu messages.
void GetTrackstatMessages(std::vector< novatel_gps_msgs::TrackstatPtr > &trackstat_msgs)
Provides any TRACKSTAT messages that have been received since the last time this was called...
double Round(double value)
stats::accumulator_set< float, stats::stats< stats::tag::max, stats::tag::min, stats::tag::mean, stats::tag::variance > > offset_stats_
Stats on time offset.
NovatelGps::ConnectionType connection_
void GetNovatelXYZPositions(std::vector< novatel_gps_msgs::NovatelXYZPtr > &positions)
Provides any BESTXYZ messages that have been received since the last time this was called...
ROSLIB_DECL std::string command(const std::string &cmd)
static void param(const ros::NodeHandle &nh, const std::string &name, int &variable, const int default_value)
ros::Publisher novatel_position_pub_
int32_t serial_baud_
The baud rate used for serial connection.
#define ROS_WARN_ONCE(...)
ros::Publisher gpgga_pub_
bool publish_novatel_utm_positions_
void SyncDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
boost::circular_buffer< ros::Time > sync_times_
Buffer of sync message time stamps.
void CheckDeviceForData()
Reads data from the device and publishes any parsed messages.
std::string ErrorMsg() const
void GetNovatelDualAntennaHeadingMessages(std::vector< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > &headings)
Provides any DUALANTENNAHEADING messages that have been received since the last time this was called...
void GetTimeMessages(std::vector< novatel_gps_msgs::TimePtr > &time_messages)
Provides any TIME messages that have been received since the last time this was called.
bool publish_imu_messages_
ros::Publisher novatel_imu_pub_
bool publish_diagnostics_
int32_t device_interrupts_
void GetGpggaMessages(std::vector< novatel_gps_msgs::GpggaPtr > &gpgga_messages)
Provides any GPGGA messages that have been received since the last time this was called.
double gpgga_gprmc_sync_tol_
std::string device_
The device identifier e.g. /dev/ttyUSB0.
bool publish_nmea_messages_
ros::NodeHandle & getNodeHandle() const
#define NODELET_DEBUG_STREAM(...)
void GetNovatelHeading2Messages(std::vector< novatel_gps_msgs::NovatelHeading2Ptr > &headings)
Provides any HEADING2 messages that have been received since the last time this was called...
ros::Publisher range_pub_
bool publish_novatel_heading2_
double gpgga_position_sync_tol_
double reconnect_delay_s_
void GetImuMessages(std::vector< sensor_msgs::ImuPtr > &imu_messages)
Provides any Imu messages that have been generated since the last time this was called.
void SyncCallback(const std_msgs::TimeConstPtr &sync)
void GetGprmcMessages(std::vector< novatel_gps_msgs::GprmcPtr > &gprmc_messages)
Provides any GPRMC messages that have been received since the last time this was called.
void DataDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
std::string connection_type_
The connection type, ("serial", "tcp", or "udp")
ROSTIME_DECL const Time TIME_MIN
#define NODELET_INFO(...)
ros::Publisher inscov_pub_
SWRI_NODELET_EXPORT_CLASS(swri_nodelet, TestNodelet)
ros::Time last_published_
void GetInspvaMessages(std::vector< novatel_gps_msgs::InspvaPtr > &inspva_messages)
Provides any INSPVA messages that have been received since the last time this was called...
uint32_t getNumSubscribers() const
ros::Publisher clocksteering_pub_
bool resetService(novatel_gps_msgs::NovatelFRESET::Request &req, novatel_gps_msgs::NovatelFRESET::Response &res)
Service request to reset the gps through FRESET.
bool publish_range_messages_
ros::Publisher novatel_xyz_position_pub_
int32_t publish_rate_warnings_
ros::Publisher novatel_dual_antenna_heading_pub_
int32_t gps_insufficient_data_warnings_
swri::Subscriber sync_sub_
Subscriber to listen for sync times from a DIO.
novatel_gps_msgs::NovatelPositionPtr last_novatel_position_
bool publish_novatel_xyz_positions_
bool publish_novatel_positions_
void FixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
ROSCPP_DECL void shutdown()
bool publish_time_messages_
double imu_rate_
The rate at which IMU measurements will be published, in Hz.
void GetInsstdevMessages(std::vector< novatel_gps_msgs::InsstdevPtr > &insstdev_messages)
Provides any INSSTDEV messages that have been received since the last time this was called...
void add(const std::string &key, const T &val)
bool publish_sync_diagnostic_
ros::Publisher novatel_utm_pub_
bool Connect(const std::string &device, ConnectionType connection)
bool Write(const std::string &command)
Writes the given string of characters to a connected NovAtel device.
ROSCPP_DECL void spinOnce()
bool publish_novatel_velocity_
diagnostic_updater::Updater diagnostic_updater_
ros::ServiceServer reset_service_
ros::Publisher trackstat_pub_
void DeviceDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
std::string imu_frame_id_
void SetSerialBaud(int32_t serial_baud)
Sets the serial baud rate; should be called before configuring a serial connection.