31 #include <net/ethernet.h> 32 #include <netinet/udp.h> 33 #include <netinet/tcp.h> 34 #include <netinet/ip.h> 37 #include <boost/algorithm/string/join.hpp> 38 #include <boost/make_shared.hpp> 46 gpgga_gprmc_sync_tol_(0.01),
47 gpgga_position_sync_tol_(0.01),
48 wait_for_position_(false),
53 tcp_socket_(io_service_),
55 clocksteering_msgs_(MAX_BUFFER_SIZE),
56 corrimudata_msgs_(MAX_BUFFER_SIZE),
57 gpgga_msgs_(MAX_BUFFER_SIZE),
58 gpgga_sync_buffer_(SYNC_BUFFER_SIZE),
59 gpgsa_msgs_(MAX_BUFFER_SIZE),
60 gpgsv_msgs_(MAX_BUFFER_SIZE),
61 gprmc_msgs_(MAX_BUFFER_SIZE),
62 gprmc_sync_buffer_(SYNC_BUFFER_SIZE),
63 imu_msgs_(MAX_BUFFER_SIZE),
64 inscov_msgs_(MAX_BUFFER_SIZE),
65 inspva_msgs_(MAX_BUFFER_SIZE),
66 insstdev_msgs_(MAX_BUFFER_SIZE),
67 heading2_msgs_(MAX_BUFFER_SIZE),
68 dual_antenna_heading_msgs_(MAX_BUFFER_SIZE),
69 novatel_positions_(MAX_BUFFER_SIZE),
70 novatel_xyz_positions_(MAX_BUFFER_SIZE),
71 novatel_utm_positions_(MAX_BUFFER_SIZE),
72 novatel_velocities_(MAX_BUFFER_SIZE),
73 position_sync_buffer_(SYNC_BUFFER_SIZE),
74 range_msgs_(MAX_BUFFER_SIZE),
75 time_msgs_(MAX_BUFFER_SIZE),
76 trackstat_msgs_(MAX_BUFFER_SIZE),
78 imu_rate_forced_(false),
79 apply_vehicle_body_rotation_(false)
89 const std::string& device,
95 opts[
"bestposa"] = 0.05;
98 return Connect(device, connection, opts);
102 const std::string& device,
131 if (connection ==
"serial")
135 else if (connection ==
"udp")
139 else if (connection ==
"tcp")
143 else if (connection ==
"pcap")
199 std::vector<NmeaSentence> nmea_sentences;
200 std::vector<NovatelSentence> novatel_sentences;
201 std::vector<BinaryMessage> binary_messages;
211 std::string remaining_buffer;
221 error_msg_ =
"Parse failure extracting sentences.";
226 ROS_DEBUG(
"Parsed: %lu NMEA / %lu NovAtel / %lu Binary messages",
227 nmea_sentences.size(), novatel_sentences.size(), binary_messages.size());
236 for(
const auto& sentence : nmea_sentences)
243 read_result = result;
250 ROS_WARN(
"For sentence: [%s]", boost::algorithm::join(sentence.body,
",").c_str());
255 for(
const auto& sentence : novatel_sentences)
262 read_result = result;
273 for(
const auto&
msg : binary_messages)
280 read_result = result;
310 utm_positions.clear();
325 fix_messages.clear();
334 double dt = gpgga_time - gprmc_time;
360 bool has_position =
false;
361 bool pop_position =
false;
373 gps_seconds = gps_seconds + 604800;
375 int32_t days =
static_cast<int32_t
>(gps_seconds / 86400.0);
376 double position_time = gps_seconds - days * 86400.0;
379 double pos_dt = gpgga_time - position_time;
381 if (pos_dt > 43200.0)
385 if (pos_dt < -43200.0)
393 ROS_DEBUG(
"Discarding a position message that is too old (%f < %f)", position_time, gpgga_time);
400 ROS_DEBUG(
"Waiting because the most recent GPGGA message is too old (%f > %f)", position_time, gpgga_time);
416 gps_common::GPSFixPtr gps_fix = boost::make_shared<gps_common::GPSFix>();
433 gps_fix->position_covariance[0] = sigma_x * sigma_x;
436 gps_fix->position_covariance[4] = sigma_y * sigma_y;
439 gps_fix->position_covariance[8] = sigma_z * sigma_z;
441 gps_fix->position_covariance_type =
442 gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
451 fix_messages.push_back(gps_fix);
476 imu_messages.clear();
483 gpgga_messages.clear();
504 gprmc_messages.clear();
511 inscov_messages.clear();
518 inspva_messages.clear();
525 insstdev_messages.clear();
560 ROS_INFO(
"Opening pcap file: %s", device.c_str());
594 ROS_ERROR(
"Failed to configure GPS. This port may be read only, or the " 595 "device may not be functioning as expected; however, the " 596 "driver may still function correctly if the port has already " 597 "been pre-configured.");
613 size_t sep_pos = endpoint.find(
':');
614 if (sep_pos == std::string::npos || sep_pos == endpoint.size() - 1)
617 std::stringstream ss;
631 port = endpoint.substr(sep_pos + 1);
636 ip = endpoint.substr(0, sep_pos);
645 boost::asio::ip::tcp::resolver resolver(
io_service_);
646 boost::asio::ip::tcp::resolver::query query(ip, port);
647 boost::asio::ip::tcp::resolver::iterator iter = resolver.resolve(query);
650 ROS_INFO(
"Connecting via TCP to %s:%s", ip.c_str(), port.c_str());
654 boost::asio::ip::udp::resolver resolver(
io_service_);
655 boost::asio::ip::udp::resolver::query query(ip, port);
656 udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>(*resolver.resolve(query));
659 ROS_INFO(
"Connecting via UDP to %s:%s", ip.c_str(), port.c_str());
664 uint16_t port_num =
static_cast<uint16_t
>(strtoll(port.c_str(),
NULL, 10));
667 boost::asio::ip::tcp::acceptor acceptor(
io_service_,
668 boost::asio::ip::tcp::endpoint(
669 boost::asio::ip::tcp::v4(), port_num));
670 ROS_INFO(
"Listening on TCP port %s", port.c_str());
672 ROS_INFO(
"Accepted TCP connection from client: %s",
673 tcp_socket_.remote_endpoint().address().to_string().c_str());
677 udp_socket_.reset(
new boost::asio::ip::udp::socket(
679 boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(),
681 boost::array<char, 1> recv_buf;
682 udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>();
683 boost::system::error_code error;
685 ROS_INFO(
"Listening on UDP port %s", port.c_str());
687 if (error && error != boost::asio::error::message_size)
689 throw boost::system::system_error(error);
692 ROS_INFO(
"Accepted UDP connection from client: %s",
697 catch (std::exception& e)
700 ROS_ERROR(
"Unable to connect: %s", e.what());
714 ROS_ERROR(
"Failed to configure GPS. This port may be read only, or the " 715 "device may not be functioning as expected; however, the " 716 "driver may still function correctly if the port has already " 717 "been pre-configured.");
737 error_msg_ =
"Timed out waiting for serial device.";
742 error_msg_ =
"Interrupted during read from serial device.";
752 boost::system::error_code error;
761 boost::asio::ip::udp::endpoint remote_endpoint;
773 catch (std::exception& e)
775 ROS_WARN(
"TCP connection error: %s", e.what());
780 struct pcap_pkthdr*
header;
781 const u_char *pkt_data;
784 result = pcap_next_ex(
pcap_, &header, &pkt_data);
787 struct iphdr* iph = (
struct iphdr*)(pkt_data +
sizeof(
struct ethhdr));
788 uint32_t iphdrlen = iph->ihl * 4;
790 switch (iph->protocol)
794 if (header->len == 54)
810 bool store_packet =
true;
813 struct tcphdr* tcph = (
struct tcphdr*) (pkt_data + iphdrlen +
sizeof(
struct ethhdr));
815 uint32_t last_iphdrlen = last_iph->ihl * 4;
816 struct tcphdr* last_tcph = (
struct tcphdr*) (&(
last_tcp_packet_[0]) + last_iphdrlen);
817 uint16_t last_len = ntohs(static_cast<uint16_t>(last_iph->tot_len));
818 uint16_t new_len = ntohs(static_cast<uint16_t>(iph->tot_len));
819 uint32_t last_seq = ntohl(last_tcph->seq);
820 uint32_t new_seq = ntohl(tcph->seq);
822 if (new_seq != last_seq)
826 uint32_t data_offset = last_tcph->doff * 4;
831 else if (new_len <= last_len)
835 store_packet =
false;
846 pkt_data +
sizeof(
struct ethhdr),
847 pkt_data + header->len);
854 uint16_t frag_off = ntohs(static_cast<uint16_t>(iph->frag_off));
855 uint16_t fragment_offset = frag_off &
static_cast<uint16_t
>(0x1FFF);
859 if (fragment_offset == 0)
861 header_size =
sizeof(
struct ethhdr) + iphdrlen + sizeof(struct udphdr);
865 header_size =
sizeof(
struct ethhdr) + iphdrlen;
873 ROS_WARN(
"Unexpected protocol: %u", iph->protocol);
883 else if (result == -2)
885 ROS_INFO(
"Done reading pcap file.");
890 uint32_t iphdrlen = last_iph->ihl * 4;
891 struct tcphdr* last_tcph = (
struct tcphdr*) (&(
last_tcp_packet_[0]) + iphdrlen);
892 uint32_t data_offset = last_tcph->doff * 4;
915 imu_messages.clear();
924 ROS_WARN_ONCE(
"IMU rate has not been configured; cannot produce sensor_msgs/Imu messages.");
931 ROS_WARN_THROTTLE(1.0,
"No INSSTDEV or INSCOV data yet; orientation covariance will be unavailable.");
938 novatel_gps_msgs::NovatelCorrectedImuDataPtr corrimudata =
corrimudata_queue_.front();
941 double corrimudata_time = corrimudata->gps_week_num *
SECONDS_PER_WEEK + corrimudata->gps_seconds;
942 double inspva_time = inspva->novatel_msg_header.gps_week_num *
948 ROS_DEBUG(
"INSPVA and CORRIMUDATA were unacceptably far apart.");
949 if (corrimudata_time < inspva_time)
951 ROS_DEBUG(
"Discarding oldest CORRIMUDATA.");
967 sensor_msgs::ImuPtr imu = boost::make_shared<sensor_msgs::Imu>();
969 imu->header.stamp = corrimudata->header.stamp;
976 imu->orientation_covariance =
latest_inscov_->attitude_covariance;
982 imu->orientation_covariance[8] = std::pow(2,
latest_insstdev_->azimuth_dev);
986 imu->orientation_covariance[0] =
987 imu->orientation_covariance[4] =
988 imu->orientation_covariance[8] = 1e-3;
991 imu->angular_velocity.x = corrimudata->pitch_rate *
imu_rate_;
992 imu->angular_velocity.y = corrimudata->roll_rate *
imu_rate_;
993 imu->angular_velocity.z = corrimudata->yaw_rate *
imu_rate_;
994 imu->angular_velocity_covariance[0] =
995 imu->angular_velocity_covariance[4] =
996 imu->angular_velocity_covariance[8] = 1e-3;
998 imu->linear_acceleration.x = corrimudata->lateral_acceleration *
imu_rate_;
999 imu->linear_acceleration.y = corrimudata->longitudinal_acceleration *
imu_rate_;
1000 imu->linear_acceleration.z = corrimudata->vertical_acceleration *
imu_rate_;
1001 imu->linear_acceleration_covariance[0] =
1002 imu->linear_acceleration_covariance[4] =
1003 imu->linear_acceleration_covariance[8] = 1e-3;
1008 size_t new_size =
imu_msgs_.size() - previous_size;
1009 ROS_DEBUG(
"Created %lu new sensor_msgs/Imu messages.", new_size);
1014 ROS_INFO(
"IMU sample rate: %f", imu_rate);
1016 if (imu_rate_forced)
1024 ROS_INFO(
"Serial baud rate : %d", serial_baud);
1031 switch (
msg.header_.message_id_)
1036 position->header.stamp = stamp;
1044 xyz_position->header.stamp = stamp;
1051 utm_position->header.stamp = stamp;
1058 velocity->header.stamp = stamp;
1065 heading->header.stamp = stamp;
1072 heading->header.stamp = stamp;
1079 imu->header.stamp = stamp;
1093 inscov->header.stamp = stamp;
1101 inspva->header.stamp = stamp;
1115 insstdev->header.stamp = stamp;
1123 range->header.stamp = stamp;
1132 time->header.stamp = stamp;
1139 trackstat->header.stamp = stamp;
1144 ROS_WARN(
"Unexpected binary message id: %u",
msg.header_.message_id_);
1159 if (most_recent_utc_time < gpgga->utc_seconds)
1161 most_recent_utc_time = gpgga->utc_seconds;
1164 gpgga->header.stamp = stamp -
ros::Duration(most_recent_utc_time - gpgga->utc_seconds);
1183 if (most_recent_utc_time < gprmc->utc_seconds)
1185 most_recent_utc_time = gprmc->utc_seconds;
1188 gprmc->header.stamp = stamp -
ros::Duration(most_recent_utc_time - gprmc->utc_seconds);
1224 if (sentence.id ==
"BESTPOSA")
1227 position->header.stamp = stamp;
1231 else if (sentence.id ==
"BESTXYZ")
1234 position->header.stamp = stamp;
1237 else if (sentence.id ==
"BESTUTMA")
1240 utm_position->header.stamp = stamp;
1243 else if (sentence.id ==
"BESTVELA")
1246 velocity->header.stamp = stamp;
1249 else if (sentence.id ==
"HEADING2")
1252 heading->header.stamp = stamp;
1255 else if (sentence.id ==
"DUALANTENNAHEADING")
1258 heading->header.stamp = stamp;
1261 else if (sentence.id ==
"CORRIMUDATAA")
1264 imu->header.stamp = stamp;
1274 else if (sentence.id ==
"INSCOVA")
1277 inscov->header.stamp = stamp;
1281 else if (sentence.id ==
"INSPVAA")
1284 inspva->header.stamp = stamp;
1294 else if (sentence.id ==
"INSSTDEVA")
1297 insstdev->header.stamp = stamp;
1301 else if (sentence.id ==
"TIMEA")
1306 time->header.stamp = stamp;
1309 else if (sentence.id ==
"RANGEA")
1312 range->header.stamp = stamp;
1315 else if (sentence.id ==
"TRACKSTATA")
1318 trackstat->header.stamp = stamp;
1321 else if (sentence.id ==
"RAWIMUXA")
1323 static std::map<std::string, std::pair<double, std::string>> rates = {
1324 {
"0", std::pair<double, std::string>(100,
"Unknown") },
1325 {
"1", std::pair<double, std::string>(100,
"Honeywell HG1700 AG11") },
1326 {
"4", std::pair<double, std::string>(100,
"Honeywell HG1700 AG17") },
1327 {
"5", std::pair<double, std::string>(100,
"Honeywell HG1700 CA29") },
1328 {
"8", std::pair<double, std::string>(200,
"Litton LN-200 (200hz model)") },
1329 {
"11", std::pair<double, std::string>(100,
"Honeywell HG1700 AG58") },
1330 {
"12", std::pair<double, std::string>(100,
"Honeywell HG1700 AG62") },
1331 {
"13", std::pair<double, std::string>(200,
"iMAR ilMU-FSAS") },
1332 {
"16", std::pair<double, std::string>(200,
"KVH 1750 IMU") },
1333 {
"19", std::pair<double, std::string>(200,
"Northrop Grumman Litef LCI-1") },
1334 {
"20", std::pair<double, std::string>(100,
"Honeywell HG1930 AA99") },
1335 {
"26", std::pair<double, std::string>(100,
"Northrop Grumman Litef ISA-100C") },
1336 {
"27", std::pair<double, std::string>(100,
"Honeywell HG1900 CA50") },
1337 {
"28", std::pair<double, std::string>(100,
"Honeywell HG1930 CA50") },
1338 {
"31", std::pair<double, std::string>(200,
"Analog Devices ADIS16488") },
1339 {
"32", std::pair<double, std::string>(125,
"Sensonor STIM300") },
1340 {
"33", std::pair<double, std::string>(200,
"KVH1750 IMU") },
1341 {
"34", std::pair<double, std::string>(200,
"Northrop Grumman Litef ISA-100") },
1342 {
"38", std::pair<double, std::string>(400,
"Northrop Grumman Litef ISA-100 400Hz") },
1343 {
"39", std::pair<double, std::string>(400,
"Northrop Grumman Litef ISA-100C 400Hz") },
1344 {
"41", std::pair<double, std::string>(125,
"Epson G320N") },
1345 {
"45", std::pair<double, std::string>(200,
"KVH 1725 IMU?") },
1347 {
"52", std::pair<double, std::string>(200,
"Litef microIMU") },
1348 {
"56", std::pair<double, std::string>(125,
"Sensonor STIM300, Direct Connection") },
1349 {
"58", std::pair<double, std::string>(200,
"Honeywell HG4930 AN01") },
1353 std::string
id = sentence.body.size() > 1 ? sentence.body[1] :
"";
1354 if (rates.find(
id) != rates.end())
1356 double rate = rates[id].first;
1358 ROS_INFO(
"IMU Type %s Found, Rate: %f Hz", rates[
id].second.c_str(), (float)rate);
1369 ROS_ERROR(
"Unknown IMU Type Received: %s",
id.c_str());
1372 else if (sentence.id ==
"CLOCKSTEERINGA")
1383 std::vector<uint8_t> bytes(command.begin(), command.end());
1388 if (written != (int32_t)command.length())
1390 ROS_ERROR(
"Failed to send command: %s", command.c_str());
1392 return written == (int32_t)command.length();
1396 boost::system::error_code error;
1402 written = boost::asio::write(
tcp_socket_, boost::asio::buffer(bytes), error);
1410 ROS_ERROR(
"Error writing TCP data: %s", error.message().c_str());
1414 return written == (int32_t) command.length();
1416 catch (std::exception& e)
1419 ROS_ERROR(
"Exception writing TCP data: %s", e.what());
1433 bool configured =
true;
1434 configured = configured &&
Write(
"unlogall THISPORT_ALL\r\n");
1438 configured = configured &&
Write(
"vehiclebodyrotation 0 0 90\r\n");
1439 configured = configured &&
Write(
"applyvehiclebodyrotation\r\n");
1442 for(NovatelMessageOpts::const_iterator option = opts.begin(); option != opts.end(); ++option)
1445 command << std::setprecision(3);
1446 command <<
"log " << option->first <<
" ontime " << option->second <<
"\r\n";
1447 configured = configured &&
Write(command.str());
1451 configured = configured &&
Write(
"log rawimuxa\r\n");
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...
novatel_gps_msgs::InsstdevPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
novatel_gps_msgs::InscovPtr latest_inscov_
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...
boost::array< uint8_t, 10000 > socket_buffer_
Fixed-size buffer for reading directly from sockets.
GpggaParser gpgga_parser_
DualAntennaHeadingParser dual_antenna_heading_parser_
boost::circular_buffer< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_msgs_
NovatelGps::ReadResult ParseNovatelSentence(const NovatelSentence &sentence, const ros::Time &stamp)
Converts a NovatelSentence object into a ROS message of the appropriate type and places it in the app...
boost::circular_buffer< novatel_gps_msgs::GprmcPtr > gprmc_msgs_
TrackstatParser trackstat_parser_
boost::shared_ptr< boost::asio::ip::udp::socket > udp_socket_
static constexpr uint16_t MESSAGE_ID
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...
static const std::string MESSAGE_NAME
CorrImuDataParser corrimudata_parser_
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.
bool WasLastGpsValid() const
novatel_gps_msgs::NovatelVelocityPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
bool WasLastGpsValid() const
static constexpr double IMU_TOLERANCE_S
novatel_gps_msgs::NovatelPositionPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
novatel_gps_msgs::RangePtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
novatel_gps_msgs::NovatelHeading2Ptr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
static constexpr uint16_t MESSAGE_ID
bool CreateIpConnection(const std::string &endpoint, NovatelMessageOpts const &opts)
Establishes an IP connection with a NovAtel device.
static constexpr uint32_t SECONDS_PER_WEEK
static const std::string MESSAGE_NAME
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...
novatel_gps_msgs::InsstdevPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
swri_serial_util::SerialPort serial_
bpf_program pcap_packet_filter_
std::vector< uint8_t > data_buffer_
static constexpr uint16_t MESSAGE_ID
InsstdevParser insstdev_parser_
novatel_gps_msgs::NovatelDualAntennaHeadingPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
static constexpr uint16_t MESSAGE_ID
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...
pcap_t * pcap_
pcap device for testing
static constexpr uint32_t MESSAGE_ID
static constexpr uint16_t DEFAULT_UDP_PORT
novatel_gps_msgs::TrackstatPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
BestvelParser bestvel_parser_
void ApplyVehicleBodyRotation(const bool &apply_rotation)
Determines whether or not to apply a 90 degree counter-clockwise rotation about Z to the Novatel SPAN...
InspvaParser inspva_parser_
void GetNovatelVelocities(std::vector< novatel_gps_msgs::NovatelVelocityPtr > &velocities)
Provides any BESTVEL messages that have been received since the last time this was called...
bool apply_vehicle_body_rotation_
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.
boost::circular_buffer< novatel_gps_msgs::ClockSteeringPtr > clocksteering_msgs_
BestposParser bestpos_parser_
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > novatel_positions_
novatel_gps_msgs::GpggaPtr ParseAscii(const NmeaSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
novatel_gps_msgs::InspvaPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
boost::circular_buffer< novatel_gps_msgs::GpgsvPtr > gpgsv_msgs_
novatel_gps_msgs::NovatelVelocityPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
novatel_gps_msgs::NovatelDualAntennaHeadingPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
NovatelMessageExtractor extractor_
Used to extract messages from the incoming data stream.
static ConnectionType ParseConnection(const std::string &connection)
Converts the strings "udp", "tcp", or "serial" into the corresponding enum values.
novatel_gps_msgs::GprmcPtr ParseAscii(const NmeaSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
boost::circular_buffer< novatel_gps_msgs::GpgsaPtr > gpgsa_msgs_
boost::shared_ptr< boost::asio::ip::udp::endpoint > udp_endpoint_
bool Open(const std::string &device, SerialConfig config=SerialConfig())
GprmcParser gprmc_parser_
static constexpr uint16_t MESSAGE_ID
BestutmParser bestutm_parser_
ReadResult ProcessData()
Processes any data that has been received from the device since the last time this message was called...
void SetImuRate(double imu_rate, bool force=true)
Sets the IMU rate; necessary for producing sensor_msgs/Imu messages.
boost::circular_buffer< novatel_gps_msgs::InscovPtr > inscov_msgs_
novatel_gps_msgs::NovatelPositionPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
BestxyzParser bestxyz_parser_
novatel_gps_msgs::TrackstatPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
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...
bool Configure(NovatelMessageOpts const &opts)
(Re)configure the driver with a set of message options
InscovParser inscov_parser_
novatel_gps_msgs::InscovPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
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)
novatel_gps_msgs::ClockSteeringPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
#define ROS_WARN_THROTTLE(period,...)
#define ROS_WARN_ONCE(...)
novatel_gps_msgs::TimePtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
static constexpr uint32_t MESSAGE_ID
novatel_gps_msgs::InsstdevPtr latest_insstdev_
static constexpr size_t MAX_BUFFER_SIZE
bool CreatePcapConnection(const std::string &device, NovatelMessageOpts const &opts)
Creates a pcap device for playing back recorded data.
boost::asio::ip::tcp::socket tcp_socket_
void GetNovatelDualAntennaHeadingMessages(std::vector< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > &headings)
Provides any DUALANTENNAHEADING messages that have been received since the last time this was called...
boost::circular_buffer< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > dual_antenna_heading_msgs_
static constexpr double DEGREES_TO_RADIANS
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.
RangeParser range_parser_
std::queue< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_queue_
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.
novatel_gps_msgs::NovatelCorrectedImuDataPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
int32_t Write(const std::vector< uint8_t > &input)
double gpgga_gprmc_sync_tol_
novatel_gps_msgs::RangePtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
boost::circular_buffer< novatel_gps_msgs::Gprmc > gprmc_sync_buffer_
ConnectionType connection_
Heading2Parser heading2_parser_
boost::circular_buffer< sensor_msgs::ImuPtr > imu_msgs_
#define ROS_DEBUG_STREAM(args)
novatel_gps_msgs::NovatelXYZPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
void GetNovatelHeading2Messages(std::vector< novatel_gps_msgs::NovatelHeading2Ptr > &headings)
Provides any HEADING2 messages that have been received since the last time this was called...
void GenerateImuMessages()
Processes any messages in our corrimudata & inspva queues in order to generate Imu messages from them...
Result ReadBytes(std::vector< uint8_t > &output, size_t max_bytes, int32_t timeout)
static const std::string MESSAGE_NAME
boost::circular_buffer< novatel_gps_msgs::NovatelHeading2Ptr > heading2_msgs_
boost::circular_buffer< novatel_gps_msgs::GpggaPtr > gpgga_msgs_
double gpgga_position_sync_tol_
NovatelGps::ReadResult ParseBinaryMessage(const BinaryMessage &msg, const ros::Time &stamp)
Converts a BinaryMessage object into a ROS message of the appropriate type and places it in the appro...
void GetImuMessages(std::vector< sensor_msgs::ImuPtr > &imu_messages)
Provides any Imu messages that have been generated since the last time this was called.
static constexpr uint16_t MESSAGE_ID
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.
GpgsaParser gpgsa_parser_
boost::asio::io_service io_service_
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > position_sync_buffer_
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...
novatel_gps_msgs::NovatelHeading2Ptr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
GpgsvParser gpgsv_parser_
novatel_gps_msgs::GpgsvPtr ParseAscii(const NmeaSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
boost::circular_buffer< novatel_gps_msgs::InsstdevPtr > insstdev_msgs_
boost::circular_buffer< novatel_gps_msgs::RangePtr > range_msgs_
boost::circular_buffer< novatel_gps_msgs::TimePtr > time_msgs_
static constexpr uint16_t MESSAGE_ID
boost::circular_buffer< novatel_gps_msgs::Gpgga > gpgga_sync_buffer_
ClockSteeringParser clocksteering_parser_
bool CreateSerialConnection(const std::string &device, NovatelMessageOpts const &opts)
Establishes a serial port connection with a NovAtel device.
boost::circular_buffer< novatel_gps_msgs::NovatelUtmPositionPtr > novatel_utm_positions_
static constexpr uint16_t MESSAGE_ID
novatel_gps_msgs::NovatelUtmPositionPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
static const std::string MESSAGE_NAME
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
novatel_gps_msgs::InspvaPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
novatel_gps_msgs::NovatelCorrectedImuDataPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
novatel_gps_msgs::GpgsaPtr ParseAscii(const NmeaSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
std::string nmea_buffer_
Buffer containing incomplete data from message parsing.
ReadResult ReadData()
Reads data from a connected NovAtel device. Any read data will be appended to data_buffer_.
static constexpr uint16_t DEFAULT_TCP_PORT
boost::circular_buffer< novatel_gps_msgs::TrackstatPtr > trackstat_msgs_
boost::circular_buffer< novatel_gps_msgs::NovatelXYZPtr > novatel_xyz_positions_
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...
boost::circular_buffer< novatel_gps_msgs::NovatelVelocityPtr > novatel_velocities_
novatel_gps_msgs::NovatelXYZPtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
std::string ErrorMsg() const
bool Connect(const std::string &device, ConnectionType connection)
boost::circular_buffer< novatel_gps_msgs::InspvaPtr > inspva_msgs_
bool Write(const std::string &command)
Writes the given string of characters to a connected NovAtel device.
static constexpr uint32_t MESSAGE_ID
novatel_gps_msgs::InscovPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
NovatelGps::ReadResult ParseNmeaSentence(const NmeaSentence &sentence, const ros::Time &stamp, double most_recent_utc_time)
Converts an NMEA sentence into a ROS message of the appropriate type and places it in the appropriate...
std::queue< novatel_gps_msgs::InspvaPtr > inspva_queue_
static constexpr uint16_t MESSAGE_ID
static constexpr uint16_t MESSAGE_ID
novatel_gps_msgs::NovatelUtmPositionPtr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
std::vector< uint8_t > last_tcp_packet_
novatel_gps_msgs::TimePtr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
char pcap_errbuf_[MAX_BUFFER_SIZE]
void SetSerialBaud(int32_t serial_baud)
Sets the serial baud rate; should be called before configuring a serial connection.