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/variance.hpp> 138 #include <boost/circular_buffer.hpp> 140 #include <diagnostic_msgs/DiagnosticStatus.h> 143 #include <gps_common/GPSFix.h> 145 #include <novatel_gps_msgs/NovatelCorrectedImuData.h> 146 #include <novatel_gps_msgs/NovatelFRESET.h> 147 #include <novatel_gps_msgs/NovatelMessageHeader.h> 148 #include <novatel_gps_msgs/NovatelPosition.h> 149 #include <novatel_gps_msgs/NovatelPsrdop2.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> 158 #include <novatel_gps_msgs/Inspva.h> 159 #include <novatel_gps_msgs/Inspvax.h> 162 #include <sensor_msgs/Imu.h> 163 #include <sensor_msgs/NavSatFix.h> 164 #include <std_msgs/Time.h> 170 namespace stats = boost::accumulators;
282 gps_pub_ = swri::advertise<gps_common::GPSFix>(node, gps_topic, 100);
283 fix_pub_ = swri::advertise<sensor_msgs::NavSatFix>(node,
"fix", 100);
287 clocksteering_pub_ = swri::advertise<novatel_gps_msgs::ClockSteering>(node,
"clocksteering", 100);
292 gpgga_pub_ = swri::advertise<novatel_gps_msgs::Gpgga>(node,
"gpgga", 100);
293 gprmc_pub_ = swri::advertise<novatel_gps_msgs::Gprmc>(node,
"gprmc", 100);
298 gpgsa_pub_ = swri::advertise<novatel_gps_msgs::Gpgsa>(node,
"gpgsa", 100);
303 imu_pub_ = swri::advertise<sensor_msgs::Imu>(node,
"imu", 100);
304 novatel_imu_pub_= swri::advertise<novatel_gps_msgs::NovatelCorrectedImuData>(node,
"corrimudata", 100);
305 insstdev_pub_ = swri::advertise<novatel_gps_msgs::Insstdev>(node,
"insstdev", 100);
306 inspva_pub_ = swri::advertise<novatel_gps_msgs::Inspva>(node,
"inspva", 100);
307 inspvax_pub_ = swri::advertise<novatel_gps_msgs::Inspvax>(node,
"inspvax", 100);
308 inscov_pub_ = swri::advertise<novatel_gps_msgs::Inscov>(node,
"inscov", 100);
313 gpgsv_pub_ = swri::advertise<novatel_gps_msgs::Gpgsv>(node,
"gpgsv", 100);
318 gphdt_pub_ = swri::advertise<novatel_gps_msgs::Gphdt>(node,
"gphdt", 100);
333 novatel_utm_pub_ = swri::advertise<novatel_gps_msgs::NovatelUtmPosition>(node,
"bestutm", 100);
365 range_pub_ = swri::advertise<novatel_gps_msgs::Range>(node,
"range", 100);
370 time_pub_ = swri::advertise<novatel_gps_msgs::Time>(node,
"time", 100);
375 trackstat_pub_ = swri::advertise<novatel_gps_msgs::Trackstat>(node,
"trackstat", 100);
413 boost::unique_lock<boost::mutex> lock(
mutex_);
423 std::string format_suffix;
439 opts[
"time" + format_suffix] = 1.0;
462 opts[
"psrdop2" + format_suffix] = -1.0;
478 opts[
"clocksteering" + format_suffix] = 1.0;
483 opts[
"corrimudata" + format_suffix] = period;
484 opts[
"inscov" + format_suffix] = 1.0;
485 opts[
"inspva" + format_suffix] = period;
486 opts[
"inspvax" + format_suffix] = period;
487 opts[
"insstdev" + format_suffix] = 1.0;
490 NODELET_WARN(
"Using the ASCII message format with CORRIMUDATA logs is not recommended. " 491 "A serial link will not be able to keep up with the data rate.");
502 opts[
"range" + format_suffix] = 1.0;
506 opts[
"trackstat" + format_suffix] = 1.0;
657 stats::accumulator_set<float, stats::stats<
663 stats::accumulator_set<float, stats::stats<stats::tag::rolling_mean> >
rolling_offset_;
687 novatel_gps_msgs::NovatelFRESET::Response& res)
695 std::string
command =
"FRESET ";
696 command += req.target.length() ?
"STANDARD" : req.target;
700 if (req.target.length() == 0)
702 ROS_WARN(
"No FRESET target specified. Doing FRESET STANDARD. This may be undesired behavior.");
717 std::vector<gps_common::GPSFixPtr> fix_msgs;
718 std::vector<novatel_gps_msgs::NovatelPositionPtr> position_msgs;
719 std::vector<novatel_gps_msgs::GpggaPtr> gpgga_msgs;
726 connection_type_.c_str(),
739 device_interrupts_++;
744 connection_type_.c_str(),
747 gps_parse_failures_++;
751 gps_insufficient_data_warnings_++;
763 measurement_count_ += position_msgs.size();
766 if (!position_msgs.empty())
768 last_novatel_position_ = position_msgs.back();
774 for (
const auto&
msg : gpgga_msgs)
776 if (
msg->utc_seconds != 0)
779 double difference = std::fabs(
msg->utc_seconds - second);
781 if (difference < 0.02)
783 msg_times_.push_back(
msg->header.stamp);
799 sync_offset =
ros::Duration(stats::rolling_mean(rolling_offset_));
803 if (publish_nmea_messages_)
805 for (
const auto&
msg : gpgga_msgs)
807 msg->header.stamp += sync_offset;
812 std::vector<novatel_gps_msgs::GprmcPtr> gprmc_msgs;
814 for (
const auto&
msg : gprmc_msgs)
816 msg->header.stamp += sync_offset;
824 std::vector<novatel_gps_msgs::GpgsaPtr> gpgsa_msgs;
826 for (
const auto&
msg : gpgsa_msgs)
836 std::vector<novatel_gps_msgs::GpgsvPtr> gpgsv_msgs;
838 for (
const auto&
msg : gpgsv_msgs)
848 std::vector<novatel_gps_msgs::GphdtPtr> gphdt_msgs;
850 for (
const auto&
msg : gphdt_msgs)
858 if (publish_novatel_positions_)
860 for (
const auto&
msg : position_msgs)
862 msg->header.stamp += sync_offset;
868 if (publish_novatel_xyz_positions_)
870 std::vector<novatel_gps_msgs::NovatelXYZPtr> xyz_position_msgs;
872 for (
const auto&
msg : xyz_position_msgs)
874 msg->header.stamp += sync_offset;
880 if (publish_novatel_utm_positions_)
882 std::vector<novatel_gps_msgs::NovatelUtmPositionPtr> utm_msgs;
884 for (
const auto&
msg : utm_msgs)
886 msg->header.stamp += sync_offset;
892 if (publish_novatel_heading2_)
894 std::vector<novatel_gps_msgs::NovatelHeading2Ptr> heading2_msgs;
896 for (
const auto&
msg : heading2_msgs)
898 msg->header.stamp += sync_offset;
904 if (publish_novatel_dual_antenna_heading_)
906 std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr> dual_antenna_heading_msgs;
908 for (
const auto&
msg : dual_antenna_heading_msgs)
910 msg->header.stamp += sync_offset;
912 novatel_dual_antenna_heading_pub_.
publish(
msg);
916 if (publish_novatel_psrdop2_)
918 std::vector<novatel_gps_msgs::NovatelPsrdop2Ptr> psrdop2_msgs;
920 for (
const auto&
msg : psrdop2_msgs)
922 msg->header.stamp += sync_offset;
928 if (publish_clock_steering_)
930 std::vector<novatel_gps_msgs::ClockSteeringPtr> msgs;
932 for (
const auto&
msg : msgs)
938 if (publish_novatel_velocity_)
940 std::vector<novatel_gps_msgs::NovatelVelocityPtr> velocity_msgs;
942 for (
const auto&
msg : velocity_msgs)
944 msg->header.stamp += sync_offset;
949 if (publish_time_messages_)
951 std::vector<novatel_gps_msgs::TimePtr> time_msgs;
953 for (
const auto&
msg : time_msgs)
955 msg->header.stamp += sync_offset;
960 if (publish_range_messages_)
962 std::vector<novatel_gps_msgs::RangePtr> range_msgs;
964 for (
const auto&
msg : range_msgs)
966 msg->header.stamp += sync_offset;
971 if (publish_trackstat_)
973 std::vector<novatel_gps_msgs::TrackstatPtr> trackstat_msgs;
975 for (
const auto&
msg : trackstat_msgs)
977 msg->header.stamp += sync_offset;
982 if (publish_imu_messages_)
984 std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> novatel_imu_msgs;
986 for (
const auto&
msg : novatel_imu_msgs)
988 msg->header.stamp += sync_offset;
993 std::vector<sensor_msgs::ImuPtr> imu_msgs;
995 for (
const auto&
msg : imu_msgs)
997 msg->header.stamp += sync_offset;
1002 std::vector<novatel_gps_msgs::InscovPtr> inscov_msgs;
1004 for (
const auto&
msg : inscov_msgs)
1006 msg->header.stamp += sync_offset;
1011 std::vector<novatel_gps_msgs::InspvaPtr> inspva_msgs;
1013 for (
const auto&
msg : inspva_msgs)
1015 msg->header.stamp += sync_offset;
1020 std::vector<novatel_gps_msgs::InspvaxPtr> inspvax_msgs;
1022 for (
const auto&
msg : inspvax_msgs)
1024 msg->header.stamp += sync_offset;
1029 std::vector<novatel_gps_msgs::InsstdevPtr> insstdev_msgs;
1031 for (
const auto&
msg : insstdev_msgs)
1033 msg->header.stamp += sync_offset;
1039 for (
const auto&
msg : fix_msgs)
1041 msg->header.stamp += sync_offset;
1043 if (publish_invalid_gpsfix_ ||
msg->status.status != gps_common::GPSStatus::STATUS_NO_FIX)
1061 publish_rate_warnings_++;
1064 last_published_ =
msg->header.stamp;
1070 sensor_msgs::NavSatFixPtr fix_msg = boost::make_shared<sensor_msgs::NavSatFix>();
1071 fix_msg->header = msg->header;
1072 fix_msg->latitude = msg->latitude;
1073 fix_msg->longitude = msg->longitude;
1074 fix_msg->altitude = msg->altitude;
1075 fix_msg->position_covariance = msg->position_covariance;
1076 switch (msg->status.status)
1078 case gps_common::GPSStatus::STATUS_NO_FIX:
1079 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
1081 case gps_common::GPSStatus::STATUS_FIX:
1082 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
1084 case gps_common::GPSStatus::STATUS_SBAS_FIX:
1085 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_SBAS_FIX;
1087 case gps_common::GPSStatus::STATUS_GBAS_FIX:
1088 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
1090 case gps_common::GPSStatus::STATUS_DGPS_FIX:
1091 case gps_common::GPSStatus::STATUS_WAAS_FIX:
1093 ROS_WARN_ONCE(
"Unsupported fix status: %d", msg->status.status);
1094 fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
1097 switch (msg->position_covariance_type)
1099 case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
1100 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
1102 case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
1103 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
1105 case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
1106 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
1108 case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
1109 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
1112 ROS_WARN_ONCE(
"Unsupported covariance type: %d", msg->position_covariance_type);
1113 fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
1117 fix_msg->status.service = 0;
1128 boost::unique_lock<boost::mutex> lock(mutex_);
1129 int32_t synced_i = -1;
1130 int32_t synced_j = -1;
1132 for (
size_t i = 0; i < sync_times_.size(); i++)
1135 for (
size_t j = synced_j + 1; j < msg_times_.size(); j++)
1138 double offset = (sync_times_[i] - msg_times_[j]).toSec();
1139 if (std::fabs(offset) < 0.49)
1142 synced_i =
static_cast<int32_t
>(i);
1143 synced_j =
static_cast<int32_t
>(j);
1148 last_sync_ = sync_times_[i];
1156 for (
int i = 0; i <= synced_i && !sync_times_.empty(); i++)
1158 sync_times_.pop_front();
1162 for (
int j = 0; j <= synced_j && !msg_times_.empty(); j++)
1164 msg_times_.pop_front();
1171 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1173 if (!last_novatel_position_)
1175 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"No Status");
1180 status.
add(
"Solution Status", last_novatel_position_->solution_status);
1181 status.
add(
"Position Type", last_novatel_position_->position_type);
1182 status.
add(
"Solution Age", last_novatel_position_->solution_age);
1183 status.
add(
"Satellites Tracked", static_cast<int>(last_novatel_position_->num_satellites_tracked));
1184 status.
add(
"Satellites Used", static_cast<int>(last_novatel_position_->num_satellites_used_in_solution));
1185 status.
add(
"Software Version", last_novatel_position_->novatel_msg_header.receiver_software_version);
1187 const novatel_gps_msgs::NovatelReceiverStatus& rcvr_status = last_novatel_position_->novatel_msg_header.receiver_status;
1188 status.
add(
"Status Code", rcvr_status.original_status_code);
1190 if (last_novatel_position_->novatel_msg_header.receiver_status.original_status_code != 0)
1192 uint8_t level = diagnostic_msgs::DiagnosticStatus::WARN;
1193 std::string
msg =
"Status Warning";
1195 if (rcvr_status.antenna_is_open ||
1196 rcvr_status.antenna_is_shorted ||
1197 !rcvr_status.antenna_powered)
1199 msg +=
" Antenna Problem";
1200 level = diagnostic_msgs::DiagnosticStatus::ERROR;
1202 status.
add(
"Error Flag", rcvr_status.error_flag?
"true":
"false");
1203 status.
add(
"Temperature Flag", rcvr_status.temperature_flag?
"true":
"false");
1204 status.
add(
"Voltage Flag", rcvr_status.voltage_supply_flag?
"true":
"false");
1205 status.
add(
"Antenna Not Powered", rcvr_status.antenna_powered?
"false":
"true");
1206 status.
add(
"Antenna Open", rcvr_status.antenna_is_open?
"true":
"false");
1207 status.
add(
"Antenna Shorted", rcvr_status.antenna_is_shorted?
"true":
"false");
1208 status.
add(
"CPU Overloaded", rcvr_status.cpu_overload_flag?
"true":
"false");
1209 status.
add(
"COM1 Buffer Overrun", rcvr_status.com1_buffer_overrun?
"true":
"false");
1210 status.
add(
"COM2 Buffer Overrun", rcvr_status.com2_buffer_overrun?
"true":
"false");
1211 status.
add(
"COM3 Buffer Overrun", rcvr_status.com3_buffer_overrun?
"true":
"false");
1212 status.
add(
"USB Buffer Overrun", rcvr_status.usb_buffer_overrun?
"true":
"false");
1213 status.
add(
"RF1 AGC Flag", rcvr_status.rf1_agc_flag?
"true":
"false");
1214 status.
add(
"RF2 AGC Flag", rcvr_status.rf2_agc_flag?
"true":
"false");
1215 status.
add(
"Almanac Flag", rcvr_status.almanac_flag?
"true":
"false");
1216 status.
add(
"Position Solution Flag", rcvr_status.position_solution_flag?
"true":
"false");
1217 status.
add(
"Position Fixed Flag", rcvr_status.position_fixed_flag?
"true":
"false");
1218 status.
add(
"Clock Steering Status", rcvr_status.clock_steering_status_enabled?
"true":
"false");
1219 status.
add(
"Clock Model Flag", rcvr_status.clock_model_flag?
"true":
"false");
1220 status.
add(
"OEMV External Oscillator Flag", rcvr_status.oemv_external_oscillator_flag?
"true":
"false");
1221 status.
add(
"Software Resource Flag", rcvr_status.software_resource_flag?
"true":
"false");
1222 status.
add(
"Auxiliary1 Flag", rcvr_status.aux1_status_event_flag?
"true":
"false");
1223 status.
add(
"Auxiliary2 Flag", rcvr_status.aux2_status_event_flag?
"true":
"false");
1224 status.
add(
"Auxiliary3 Flag", rcvr_status.aux3_status_event_flag?
"true":
"false");
1225 NODELET_WARN(
"Novatel status code: %d", rcvr_status.original_status_code);
1232 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1236 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"No Sync");
1241 status.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Sync Stale");
1245 status.
add(
"Last Sync", last_sync_);
1246 status.
add(
"Mean Offset", stats::mean(offset_stats_));
1247 status.
add(
"Mean Offset (rolling)", stats::rolling_mean(rolling_offset_));
1248 status.
add(
"Offset Variance", stats::variance(offset_stats_));
1249 status.
add(
"Min Offset", stats::min(offset_stats_));
1250 status.
add(
"Max Offset", stats::max(offset_stats_));
1255 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1257 if (device_errors_ > 0)
1259 status.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Device Errors");
1261 else if (device_interrupts_ > 0)
1263 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Device Interrupts");
1267 else if (device_timeouts_)
1269 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Device Timeouts");
1274 status.
add(
"Errors", device_errors_);
1275 status.
add(
"Interrupts", device_interrupts_);
1276 status.
add(
"Timeouts", device_timeouts_);
1278 device_timeouts_ = 0;
1279 device_interrupts_ = 0;
1285 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1287 if (gps_parse_failures_ > 0)
1289 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Parse Failures");
1294 status.
add(
"Parse Failures", gps_parse_failures_);
1295 status.
add(
"Insufficient Data Warnings", gps_insufficient_data_warnings_);
1297 gps_parse_failures_ = 0;
1298 gps_insufficient_data_warnings_ = 0;
1303 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal");
1305 double period = diagnostic_updater_.
getPeriod();
1306 double measured_rate = measurement_count_ / period;
1308 if (measured_rate < 0.5 * expected_rate_)
1310 status.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Insufficient Data Rate");
1314 else if (measured_rate < 0.95 * expected_rate_)
1316 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Insufficient Data Rate");
1321 status.
add(
"Measurement Rate (Hz)", measured_rate);
1323 measurement_count_ = 0;
1328 status.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Nominal Publish Rate");
1331 bool gap_detected =
false;
1332 if (elapsed > 2.0 / expected_rate_)
1334 publish_rate_warnings_++;
1335 gap_detected =
true;
1338 if (publish_rate_warnings_ > 1 || gap_detected)
1340 status.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Insufficient Publish Rate");
1341 NODELET_WARN(
"publish rate failures detected <%s>: %d",
1345 status.
add(
"Warnings", publish_rate_warnings_);
1347 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_
ros::Publisher gphdt_pub_
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(...)
~NovatelGpsNodelet() override
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
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_
void GetInspvaxMessages(std::vector< novatel_gps_msgs::InspvaxPtr > &inspvax_messages)
Provides any INSPVAX messages that have been received since the last time this was called...
#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 GetGphdtMessages(std::vector< novatel_gps_msgs::GphdtPtr > &gphdt_messages)
Provides any GPHDT messages that have been received since the last time this was called.
void RateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
void GetNovatelPsrdop2Messages(std::vector< novatel_gps_msgs::NovatelPsrdop2Ptr > &psrdop2_messages)
Provides any PSRDOP2 messages that have been received since the last time this was called...
void GpsDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
ros::Publisher inspvax_pub_
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.
bool publish_novatel_psrdop2_
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 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)
ros::Publisher novatel_psrdop2_pub_
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 publish_invalid_gpsfix_
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.