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 gpsfix_sync_tol_(0.01),
50 imu_rate_forced_(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 gpgsa_msgs_(MAX_BUFFER_SIZE),
59 gpgsv_msgs_(MAX_BUFFER_SIZE),
60 gphdt_msgs_(MAX_BUFFER_SIZE),
61 gprmc_msgs_(MAX_BUFFER_SIZE),
62 imu_msgs_(MAX_BUFFER_SIZE),
63 inscov_msgs_(MAX_BUFFER_SIZE),
64 inspva_msgs_(MAX_BUFFER_SIZE),
65 inspvax_msgs_(MAX_BUFFER_SIZE),
66 insstdev_msgs_(MAX_BUFFER_SIZE),
67 novatel_positions_(MAX_BUFFER_SIZE),
68 novatel_xyz_positions_(MAX_BUFFER_SIZE),
69 novatel_utm_positions_(MAX_BUFFER_SIZE),
70 novatel_velocities_(MAX_BUFFER_SIZE),
71 bestpos_sync_buffer_(SYNC_BUFFER_SIZE),
72 bestvel_sync_buffer_(SYNC_BUFFER_SIZE),
73 heading2_msgs_(MAX_BUFFER_SIZE),
74 dual_antenna_heading_msgs_(MAX_BUFFER_SIZE),
75 psrdop2_msgs_(MAX_BUFFER_SIZE),
76 range_msgs_(MAX_BUFFER_SIZE),
77 time_msgs_(MAX_BUFFER_SIZE),
78 trackstat_msgs_(MAX_BUFFER_SIZE),
80 apply_vehicle_body_rotation_(false)
90 const std::string& device,
96 opts[
"bestposa"] = 0.05;
99 return Connect(device, connection, opts);
103 const std::string& device,
132 if (connection ==
"serial")
136 else if (connection ==
"udp")
140 else if (connection ==
"tcp")
144 else if (connection ==
"pcap")
176 if (
pcap_ !=
nullptr)
200 std::vector<NmeaSentence> nmea_sentences;
201 std::vector<NovatelSentence> novatel_sentences;
202 std::vector<BinaryMessage> binary_messages;
212 std::string remaining_buffer;
222 error_msg_ =
"Parse failure extracting sentences.";
227 ROS_DEBUG(
"Parsed: %lu NMEA / %lu NovAtel / %lu Binary messages",
228 nmea_sentences.size(), novatel_sentences.size(), binary_messages.size());
237 for(
const auto& sentence : nmea_sentences)
244 read_result = result;
251 ROS_WARN(
"For sentence: [%s]", boost::algorithm::join(sentence.body,
",").c_str());
256 for(
const auto& sentence : novatel_sentences)
263 read_result = result;
274 for(
const auto&
msg : binary_messages)
281 read_result = result;
311 utm_positions.clear();
326 fix_messages.clear();
334 auto gpsFix = boost::make_shared<gps_common::GPSFix>();
342 double time_diff = std::fabs(bestvel->novatel_msg_header.gps_seconds -
343 bestpos->novatel_msg_header.gps_seconds);
347 gpsFix->track = bestvel->track_ground;
348 gpsFix->speed = std::sqrt(std::pow(bestvel->horizontal_speed, 2) + std::pow(bestvel->vertical_speed, 2));
352 else if (bestvel->novatel_msg_header.gps_seconds < bestpos->novatel_msg_header.gps_seconds)
374 gpsFix->altitude = bestpos->height;
375 gpsFix->latitude = bestpos->lat;
376 gpsFix->longitude = bestpos->lon;
378 if (bestpos->solution_status ==
"SOL_COMPUTED")
380 gpsFix->status.status = gps_common::GPSStatus::STATUS_FIX;
384 gpsFix->status.status = gps_common::GPSStatus::STATUS_NO_FIX;
387 gpsFix->time = bestpos->novatel_msg_header.gps_seconds;
389 gpsFix->status.header.stamp = gpsFix->header.stamp;
390 gpsFix->status.satellites_visible = bestpos->num_satellites_tracked;
391 gpsFix->status.satellites_used = bestpos->num_satellites_used_in_solution;
393 double sigma_x = bestpos->lon_sigma;
394 double sigma_x_squared = sigma_x * sigma_x;
395 gpsFix->position_covariance[0] = sigma_x_squared;
397 double sigma_y = bestpos->lat_sigma;
398 double sigma_y_squared = sigma_y * sigma_y;
399 gpsFix->position_covariance[4] = sigma_y_squared;
401 double sigma_z = bestpos->height_sigma;
402 gpsFix->position_covariance[8] = sigma_z * sigma_z;
406 gpsFix->err_horz = 2.0 * std::sqrt(sigma_x_squared + sigma_y_squared);
409 gpsFix->err = 0.833 * (sigma_x + sigma_y + sigma_z);
412 gpsFix->err_vert = 2.0 * sigma_z;
414 gpsFix->position_covariance_type =
415 gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
434 fix_messages.push_back(gpsFix);
453 imu_messages.clear();
460 psrdop2_messages.clear();
467 gpgga_messages.clear();
495 gprmc_messages.clear();
502 inscov_messages.clear();
509 inspva_messages.clear();
516 inspvax_messages.clear();
523 insstdev_messages.clear();
558 ROS_INFO(
"Opening pcap file: %s", device.c_str());
592 ROS_ERROR(
"Failed to configure GPS. This port may be read only, or the " 593 "device may not be functioning as expected; however, the " 594 "driver may still function correctly if the port has already " 595 "been pre-configured.");
611 size_t sep_pos = endpoint.find(
':');
612 if (sep_pos == std::string::npos || sep_pos == endpoint.size() - 1)
615 std::stringstream ss;
629 port = endpoint.substr(sep_pos + 1);
634 ip = endpoint.substr(0, sep_pos);
643 boost::asio::ip::tcp::resolver resolver(
io_service_);
644 boost::asio::ip::tcp::resolver::query query(ip, port);
645 boost::asio::ip::tcp::resolver::iterator iter = resolver.resolve(query);
648 ROS_INFO(
"Connecting via TCP to %s:%s", ip.c_str(), port.c_str());
652 boost::asio::ip::udp::resolver resolver(
io_service_);
653 boost::asio::ip::udp::resolver::query query(ip, port);
654 udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>(*resolver.resolve(query));
657 ROS_INFO(
"Connecting via UDP to %s:%s", ip.c_str(), port.c_str());
662 auto port_num =
static_cast<uint16_t
>(strtoll(port.c_str(),
nullptr, 10));
665 boost::asio::ip::tcp::acceptor acceptor(
io_service_,
666 boost::asio::ip::tcp::endpoint(
667 boost::asio::ip::tcp::v4(), port_num));
668 ROS_INFO(
"Listening on TCP port %s", port.c_str());
670 ROS_INFO(
"Accepted TCP connection from client: %s",
671 tcp_socket_.remote_endpoint().address().to_string().c_str());
675 udp_socket_.reset(
new boost::asio::ip::udp::socket(
677 boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(),
679 boost::array<char, 1> recv_buf;
680 udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>();
681 boost::system::error_code error;
683 ROS_INFO(
"Listening on UDP port %s", port.c_str());
685 if (error && error != boost::asio::error::message_size)
687 throw boost::system::system_error(error);
690 ROS_INFO(
"Accepted UDP connection from client: %s",
695 catch (std::exception& e)
698 ROS_ERROR(
"Unable to connect: %s", e.what());
712 ROS_ERROR(
"Failed to configure GPS. This port may be read only, or the " 713 "device may not be functioning as expected; however, the " 714 "driver may still function correctly if the port has already " 715 "been pre-configured.");
735 error_msg_ =
"Timed out waiting for serial device.";
740 error_msg_ =
"Interrupted during read from serial device.";
750 boost::system::error_code error;
759 boost::asio::ip::udp::endpoint remote_endpoint;
771 catch (std::exception& e)
773 ROS_WARN(
"TCP connection error: %s", e.what());
778 struct pcap_pkthdr* header;
779 const u_char *pkt_data;
782 result = pcap_next_ex(
pcap_, &header, &pkt_data);
785 auto iph =
reinterpret_cast<const iphdr*
>(pkt_data +
sizeof(
struct ethhdr));
786 uint32_t iphdrlen = iph->ihl * 4u;
788 switch (iph->protocol)
792 if (header->len == 54)
808 bool store_packet =
true;
811 auto tcph =
reinterpret_cast<const tcphdr*
>(pkt_data + iphdrlen +
sizeof(
struct ethhdr));
813 uint32_t last_iphdrlen = last_iph->ihl * 4u;
814 auto last_tcph =
reinterpret_cast<const tcphdr*
>(&(
last_tcp_packet_[0]) + last_iphdrlen);
815 uint16_t last_len = ntohs(static_cast<uint16_t>(last_iph->tot_len));
816 uint16_t new_len = ntohs(static_cast<uint16_t>(iph->tot_len));
817 uint32_t last_seq = ntohl(last_tcph->seq);
818 uint32_t new_seq = ntohl(tcph->seq);
820 if (new_seq != last_seq)
824 uint32_t data_offset = last_tcph->doff * 4;
829 else if (new_len <= last_len)
833 store_packet =
false;
844 pkt_data +
sizeof(
struct ethhdr),
845 pkt_data + header->len);
852 uint16_t frag_off = ntohs(static_cast<uint16_t>(iph->frag_off));
853 uint16_t fragment_offset = frag_off &
static_cast<uint16_t
>(0x1FFF);
857 if (fragment_offset == 0)
859 header_size =
sizeof(
struct ethhdr) + iphdrlen + sizeof(struct udphdr);
863 header_size =
sizeof(
struct ethhdr) + iphdrlen;
871 ROS_WARN(
"Unexpected protocol: %u", iph->protocol);
881 else if (result == -2)
883 ROS_INFO(
"Done reading pcap file.");
888 uint32_t iphdrlen = last_iph->ihl * 4u;
889 auto last_tcph =
reinterpret_cast<const tcphdr*
>(&(
last_tcp_packet_[0]) + iphdrlen);
890 uint32_t data_offset = last_tcph->doff * 4u;
913 imu_messages.clear();
922 ROS_WARN_ONCE(
"IMU rate has not been configured; cannot produce sensor_msgs/Imu messages.");
929 ROS_WARN_THROTTLE(1.0,
"No INSSTDEV or INSCOV data yet; orientation covariance will be unavailable.");
936 novatel_gps_msgs::NovatelCorrectedImuDataPtr corrimudata =
corrimudata_queue_.front();
939 double corrimudata_time = corrimudata->gps_week_num *
SECONDS_PER_WEEK + corrimudata->gps_seconds;
940 double inspva_time = inspva->novatel_msg_header.gps_week_num *
946 ROS_DEBUG(
"INSPVA and CORRIMUDATA were unacceptably far apart.");
947 if (corrimudata_time < inspva_time)
949 ROS_DEBUG(
"Discarding oldest CORRIMUDATA.");
965 sensor_msgs::ImuPtr imu = boost::make_shared<sensor_msgs::Imu>();
967 imu->header.stamp = corrimudata->header.stamp;
974 imu->orientation_covariance =
latest_inscov_->attitude_covariance;
980 imu->orientation_covariance[8] = std::pow(2,
latest_insstdev_->azimuth_dev);
984 imu->orientation_covariance[0] =
985 imu->orientation_covariance[4] =
986 imu->orientation_covariance[8] = 1e-3;
989 imu->angular_velocity.x = corrimudata->pitch_rate *
imu_rate_;
990 imu->angular_velocity.y = corrimudata->roll_rate *
imu_rate_;
991 imu->angular_velocity.z = corrimudata->yaw_rate *
imu_rate_;
992 imu->angular_velocity_covariance[0] =
993 imu->angular_velocity_covariance[4] =
994 imu->angular_velocity_covariance[8] = 1e-3;
996 imu->linear_acceleration.x = corrimudata->lateral_acceleration *
imu_rate_;
997 imu->linear_acceleration.y = corrimudata->longitudinal_acceleration *
imu_rate_;
998 imu->linear_acceleration.z = corrimudata->vertical_acceleration *
imu_rate_;
999 imu->linear_acceleration_covariance[0] =
1000 imu->linear_acceleration_covariance[4] =
1001 imu->linear_acceleration_covariance[8] = 1e-3;
1006 size_t new_size =
imu_msgs_.size() - previous_size;
1007 ROS_DEBUG(
"Created %lu new sensor_msgs/Imu messages.", new_size);
1012 ROS_INFO(
"IMU sample rate: %f", imu_rate);
1014 if (imu_rate_forced)
1022 ROS_INFO(
"Serial baud rate : %d", serial_baud);
1029 switch (
msg.header_.message_id_)
1034 position->header.stamp = stamp;
1042 xyz_position->header.stamp = stamp;
1049 utm_position->header.stamp = stamp;
1056 velocity->header.stamp = stamp;
1064 heading->header.stamp = stamp;
1071 heading->header.stamp = stamp;
1078 imu->header.stamp = stamp;
1092 inscov->header.stamp = stamp;
1100 inspva->header.stamp = stamp;
1114 inspvax->header.stamp = stamp;
1121 insstdev->header.stamp = stamp;
1129 psrdop2->header.stamp = stamp;
1137 range->header.stamp = stamp;
1146 time->header.stamp = stamp;
1153 trackstat->header.stamp = stamp;
1158 ROS_WARN(
"Unexpected binary message id: %u",
msg.header_.message_id_);
1167 double most_recent_utc_time) noexcept(
false)
1175 if (most_recent_utc_time < gpgga_time)
1177 most_recent_utc_time = gpgga_time;
1180 gpgga->header.stamp = stamp -
ros::Duration(most_recent_utc_time - gpgga_time);
1190 if (most_recent_utc_time < gprmc_time)
1192 most_recent_utc_time = gprmc_time;
1195 gprmc->header.stamp = stamp -
ros::Duration(most_recent_utc_time - gprmc_time);
1225 if (sentence.id ==
"BESTPOSA")
1228 position->header.stamp = stamp;
1232 else if (sentence.id ==
"BESTXYZA")
1235 position->header.stamp = stamp;
1238 else if (sentence.id ==
"BESTUTMA")
1241 utm_position->header.stamp = stamp;
1244 else if (sentence.id ==
"BESTVELA")
1247 velocity->header.stamp = stamp;
1251 else if (sentence.id ==
"HEADING2A")
1254 heading->header.stamp = stamp;
1257 else if (sentence.id ==
"DUALANTENNAHEADINGA")
1260 heading->header.stamp = stamp;
1263 else if (sentence.id ==
"CORRIMUDATAA")
1266 imu->header.stamp = stamp;
1276 else if (sentence.id ==
"INSCOVA")
1279 inscov->header.stamp = stamp;
1283 else if (sentence.id ==
"INSPVAA")
1286 inspva->header.stamp = stamp;
1296 else if (sentence.id ==
"INSPVAXA")
1299 inspvax->header.stamp = stamp;
1302 else if (sentence.id ==
"INSSTDEVA")
1305 insstdev->header.stamp = stamp;
1309 else if (sentence.id ==
"PSRDOP2A")
1312 psrdop2->header.stamp = stamp;
1316 else if (sentence.id ==
"TIMEA")
1321 time->header.stamp = stamp;
1324 else if (sentence.id ==
"RANGEA")
1327 range->header.stamp = stamp;
1330 else if (sentence.id ==
"TRACKSTATA")
1333 trackstat->header.stamp = stamp;
1336 else if (sentence.id ==
"RAWIMUXA")
1338 static std::map<std::string, std::pair<double, std::string>> rates = {
1339 {
"0", std::pair<double, std::string>(100,
"Unknown") },
1340 {
"1", std::pair<double, std::string>(100,
"Honeywell HG1700 AG11") },
1341 {
"4", std::pair<double, std::string>(100,
"Honeywell HG1700 AG17") },
1342 {
"5", std::pair<double, std::string>(100,
"Honeywell HG1700 CA29") },
1343 {
"8", std::pair<double, std::string>(200,
"Litton LN-200 (200hz model)") },
1344 {
"11", std::pair<double, std::string>(100,
"Honeywell HG1700 AG58") },
1345 {
"12", std::pair<double, std::string>(100,
"Honeywell HG1700 AG62") },
1346 {
"13", std::pair<double, std::string>(200,
"iMAR ilMU-FSAS") },
1347 {
"16", std::pair<double, std::string>(200,
"KVH 1750 IMU") },
1348 {
"19", std::pair<double, std::string>(200,
"Northrop Grumman Litef LCI-1") },
1349 {
"20", std::pair<double, std::string>(100,
"Honeywell HG1930 AA99") },
1350 {
"26", std::pair<double, std::string>(100,
"Northrop Grumman Litef ISA-100C") },
1351 {
"27", std::pair<double, std::string>(100,
"Honeywell HG1900 CA50") },
1352 {
"28", std::pair<double, std::string>(100,
"Honeywell HG1930 CA50") },
1353 {
"31", std::pair<double, std::string>(200,
"Analog Devices ADIS16488") },
1354 {
"32", std::pair<double, std::string>(125,
"Sensonor STIM300") },
1355 {
"33", std::pair<double, std::string>(200,
"KVH1750 IMU") },
1356 {
"34", std::pair<double, std::string>(200,
"Northrop Grumman Litef ISA-100") },
1357 {
"38", std::pair<double, std::string>(400,
"Northrop Grumman Litef ISA-100 400Hz") },
1358 {
"39", std::pair<double, std::string>(400,
"Northrop Grumman Litef ISA-100C 400Hz") },
1359 {
"41", std::pair<double, std::string>(125,
"Epson G320N") },
1360 {
"45", std::pair<double, std::string>(200,
"KVH 1725 IMU?") },
1362 {
"52", std::pair<double, std::string>(200,
"Litef microIMU") },
1363 {
"56", std::pair<double, std::string>(125,
"Sensonor STIM300, Direct Connection") },
1364 {
"58", std::pair<double, std::string>(200,
"Honeywell HG4930 AN01") },
1365 {
"61", std::pair<double, std::string>(100,
"Epson G370N") },
1369 std::string
id = sentence.body.size() > 1 ? sentence.body[1] :
"";
1370 if (rates.find(
id) != rates.end())
1372 double rate = rates[id].first;
1374 ROS_INFO(
"IMU Type %s Found, Rate: %f Hz", rates[
id].second.c_str(), (float)rate);
1385 ROS_ERROR(
"Unknown IMU Type Received: %s",
id.c_str());
1388 else if (sentence.id ==
"CLOCKSTEERINGA")
1399 std::vector<uint8_t> bytes(command.begin(), command.end());
1404 if (written != (int32_t)command.length())
1406 ROS_ERROR(
"Failed to send command: %s", command.c_str());
1408 return written == (int32_t)command.length();
1412 boost::system::error_code error;
1418 written = boost::asio::write(
tcp_socket_, boost::asio::buffer(bytes), error);
1426 ROS_ERROR(
"Error writing TCP data: %s", error.message().c_str());
1430 return written == (int32_t) command.length();
1432 catch (std::exception& e)
1435 ROS_ERROR(
"Exception writing TCP data: %s", e.what());
1449 bool configured =
true;
1450 configured = configured &&
Write(
"unlogall THISPORT_ALL\r\n");
1454 configured = configured &&
Write(
"vehiclebodyrotation 0 0 90\r\n");
1455 configured = configured &&
Write(
"applyvehiclebodyrotation\r\n");
1458 for(
const auto& option : opts)
1461 command << std::setprecision(3);
1462 if (option.first.find(
"heading2") != std::string::npos)
1464 command <<
"log " << option.first <<
" onnew " <<
"\r\n";
1466 else if (option.second < 0.0)
1468 command <<
"log " << option.first <<
" onchanged\r\n";
1472 command <<
"log " << option.first <<
" ontime " << option.second <<
"\r\n";
1474 configured = configured &&
Write(command.str());
1478 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::InspvaPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg 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...
novatel_gps_msgs::InspvaxPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
boost::array< uint8_t, 10000 > socket_buffer_
Fixed-size buffer for reading directly from sockets.
GpggaParser gpgga_parser_
novatel_gps_msgs::InscovPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
DualAntennaHeadingParser dual_antenna_heading_parser_
boost::circular_buffer< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_msgs_
boost::circular_buffer< novatel_gps_msgs::GprmcPtr > gprmc_msgs_
TrackstatParser trackstat_parser_
novatel_gps_msgs::NovatelHeading2Ptr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
novatel_gps_msgs::InsstdevPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
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...
#define ROS_WARN_THROTTLE(rate,...)
static const std::string MESSAGE_NAME
CorrImuDataParser corrimudata_parser_
novatel_gps_msgs::NovatelPositionPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
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.
novatel_gps_msgs::NovatelVelocityPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
static constexpr double IMU_TOLERANCE_S
novatel_gps_msgs::NovatelXYZPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence 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
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...
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...
swri_serial_util::SerialPort serial_
bpf_program pcap_packet_filter_
std::vector< uint8_t > data_buffer_
static constexpr uint16_t MESSAGE_ID
novatel_gps_msgs::GpgsvPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
InsstdevParser insstdev_parser_
novatel_gps_msgs::TimePtr ParseAscii(const NovatelSentence &sentence) noexcept(false) 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
novatel_gps_msgs::NovatelPsrdop2Ptr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
static constexpr uint32_t MESSAGE_ID
static constexpr uint16_t DEFAULT_UDP_PORT
novatel_gps_msgs::NovatelUtmPositionPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) 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...
novatel_gps_msgs::NovatelVelocityPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
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_
boost::circular_buffer< novatel_gps_msgs::GpgsvPtr > gpgsv_msgs_
novatel_gps_msgs::RangePtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence 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.
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.
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())
novatel_gps_msgs::InsstdevPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
novatel_gps_msgs::GprmcPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
GprmcParser gprmc_parser_
static constexpr uint16_t MESSAGE_ID
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...
BestutmParser bestutm_parser_
static const std::string MESSAGE_NAME
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_
BestxyzParser bestxyz_parser_
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > bestpos_sync_buffer_
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_
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::NovatelPositionPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
NovatelGps::ReadResult ParseBinaryMessage(const BinaryMessage &msg, const ros::Time &stamp) noexcept(false)
Converts a BinaryMessage object into a ROS message of the appropriate type and places it in the appro...
#define ROS_WARN_ONCE(...)
static constexpr uint32_t MESSAGE_ID
novatel_gps_msgs::InsstdevPtr latest_insstdev_
novatel_gps_msgs::NovatelPsrdop2Ptr latest_psrdop2_
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_
novatel_gps_msgs::TrackstatPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
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_
boost::circular_buffer< novatel_gps_msgs::GphdtPtr > gphdt_msgs_
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.
int32_t Write(const std::vector< uint8_t > &input)
novatel_gps_msgs::GphdtPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
ConnectionType connection_
Heading2Parser heading2_parser_
boost::circular_buffer< sensor_msgs::ImuPtr > imu_msgs_
NovatelGps::ReadResult ParseNovatelSentence(const NovatelSentence &sentence, const ros::Time &stamp) noexcept(false)
Converts a NovatelSentence object into a ROS message of the appropriate type and places it in the app...
novatel_gps_msgs::TimePtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
novatel_gps_msgs::NovatelUtmPositionPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
#define ROS_DEBUG_STREAM(args)
novatel_gps_msgs::NovatelPsrdop2Ptr 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...
novatel_gps_msgs::ClockSteeringPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
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)
novatel_gps_msgs::GpgsaPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
static const std::string MESSAGE_NAME
boost::circular_buffer< novatel_gps_msgs::NovatelHeading2Ptr > heading2_msgs_
boost::circular_buffer< novatel_gps_msgs::GpggaPtr > gpgga_msgs_
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
GphdtParser gphdt_parser_
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.
novatel_gps_msgs::TrackstatPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
double UtcFloatToSeconds(double utc_float)
GpgsaParser gpgsa_parser_
boost::asio::io_service io_service_
novatel_gps_msgs::NovatelDualAntennaHeadingPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
static constexpr uint32_t MESSAGE_ID
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...
GpgsvParser gpgsv_parser_
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
novatel_gps_msgs::NovatelCorrectedImuDataPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
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
static const std::string MESSAGE_NAME
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
static constexpr uint16_t MESSAGE_ID
novatel_gps_msgs::NovatelCorrectedImuDataPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg 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_.
novatel_gps_msgs::InscovPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
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::InspvaPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
std::string ErrorMsg() const
novatel_gps_msgs::NovatelXYZPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
boost::circular_buffer< novatel_gps_msgs::InspvaxPtr > inspvax_msgs_
boost::circular_buffer< novatel_gps_msgs::NovatelVelocityPtr > bestvel_sync_buffer_
novatel_gps_msgs::RangePtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
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.
novatel_gps_msgs::InspvaxPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
static constexpr uint32_t MESSAGE_ID
NovatelGps::ReadResult ParseNmeaSentence(const NmeaSentence &sentence, const ros::Time &stamp, double most_recent_utc_time) noexcept(false)
Converts an NMEA sentence into a ROS message of the appropriate type and places it in the appropriate...
boost::circular_buffer< novatel_gps_msgs::NovatelPsrdop2Ptr > psrdop2_msgs_
std::queue< novatel_gps_msgs::InspvaPtr > inspva_queue_
novatel_gps_msgs::NovatelHeading2Ptr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
static constexpr uint16_t MESSAGE_ID
Psrdop2Parser psrdop2_parser_
static constexpr uint16_t MESSAGE_ID
std::vector< uint8_t > last_tcp_packet_
novatel_gps_msgs::NovatelDualAntennaHeadingPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
novatel_gps_msgs::GpggaPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
char pcap_errbuf_[MAX_BUFFER_SIZE]
InspvaxParser inspvax_parser_
void SetSerialBaud(int32_t serial_baud)
Sets the serial baud rate; should be called before configuring a serial connection.