30 #ifndef NOVATEL_OEM628_NOVATEL_GPS_H_ 31 #define NOVATEL_OEM628_NOVATEL_GPS_H_ 38 #include <boost/asio.hpp> 39 #include <boost/circular_buffer.hpp> 45 #include <gps_common/GPSFix.h> 47 #include <novatel_gps_msgs/Gpgga.h> 48 #include <novatel_gps_msgs/Gpgsa.h> 49 #include <novatel_gps_msgs/Gprmc.h> 50 #include <novatel_gps_msgs/Inspva.h> 51 #include <novatel_gps_msgs/Insstdev.h> 52 #include <novatel_gps_msgs/NovatelCorrectedImuData.h> 53 #include <novatel_gps_msgs/NovatelPosition.h> 54 #include <novatel_gps_msgs/NovatelXYZ.h> 55 #include <novatel_gps_msgs/NovatelUtmPosition.h> 56 #include <novatel_gps_msgs/NovatelVelocity.h> 57 #include <novatel_gps_msgs/Range.h> 58 #include <novatel_gps_msgs/Time.h> 59 #include <novatel_gps_msgs/Trackstat.h> 81 #include <sensor_msgs/Imu.h> 143 void GetFixMessages(std::vector<gps_common::GPSFixPtr>& fix_messages);
149 void GetGpggaMessages(std::vector<novatel_gps_msgs::GpggaPtr>& gpgga_messages);
155 void GetGpgsaMessages(std::vector<novatel_gps_msgs::GpgsaPtr>& gpgsa_messages);
161 void GetGpgsvMessages(std::vector<novatel_gps_msgs::GpgsvPtr>& gpgsv_messages);
167 void GetGprmcMessages(std::vector<novatel_gps_msgs::GprmcPtr>& gprmc_messages);
185 void GetImuMessages(std::vector<sensor_msgs::ImuPtr>& imu_messages);
191 void GetInscovMessages(std::vector<novatel_gps_msgs::InscovPtr>& inscov_messages);
197 void GetInspvaMessages(std::vector<novatel_gps_msgs::InspvaPtr>& inspva_messages);
239 void GetRangeMessages(std::vector<novatel_gps_msgs::RangePtr>& range_messages);
245 void GetTimeMessages(std::vector<novatel_gps_msgs::TimePtr>& time_messages);
291 void SetImuRate(
double imu_rate,
bool force =
true);
320 bool Configure(NovatelMessageOpts
const& opts);
496 boost::circular_buffer<novatel_gps_msgs::TimePtr>
time_msgs_;
511 #endif // NOVATEL_OEM628_NOVATEL_GPS_H_
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::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_
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...
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.
static constexpr double IMU_TOLERANCE_S
bool CreateIpConnection(const std::string &endpoint, NovatelMessageOpts const &opts)
Establishes an IP connection with a NovAtel device.
static constexpr uint32_t SECONDS_PER_WEEK
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...
swri_serial_util::SerialPort serial_
bpf_program pcap_packet_filter_
std::vector< uint8_t > data_buffer_
InsstdevParser insstdev_parser_
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 uint16_t DEFAULT_UDP_PORT
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_
boost::circular_buffer< novatel_gps_msgs::GpgsvPtr > gpgsv_msgs_
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.
boost::circular_buffer< novatel_gps_msgs::GpgsaPtr > gpgsa_msgs_
boost::shared_ptr< boost::asio::ip::udp::endpoint > udp_endpoint_
GprmcParser gprmc_parser_
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_
BestxyzParser bestxyz_parser_
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::InsstdevPtr latest_insstdev_
static constexpr size_t MAX_BUFFER_SIZE
std::string ErrorMsg() const
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.
double gpgga_gprmc_sync_tol_
boost::circular_buffer< novatel_gps_msgs::Gprmc > gprmc_sync_buffer_
ConnectionType connection_
Heading2Parser heading2_parser_
boost::circular_buffer< sensor_msgs::ImuPtr > imu_msgs_
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...
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.
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...
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_
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_
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 size_t SYNC_BUFFER_SIZE
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_
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.
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_
std::vector< uint8_t > last_tcp_packet_
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.