#include <exception>#include <string>#include <boost/accumulators/accumulators.hpp>#include <boost/accumulators/statistics/max.hpp>#include <boost/accumulators/statistics/mean.hpp>#include <boost/accumulators/statistics/min.hpp>#include <boost/accumulators/statistics/rolling_mean.hpp>#include <boost/accumulators/statistics/stats.hpp>#include <boost/accumulators/statistics/variance.hpp>#include <boost/circular_buffer.hpp>#include <diagnostic_msgs/DiagnosticStatus.h>#include <diagnostic_updater/diagnostic_updater.h>#include <diagnostic_updater/publisher.h>#include <gps_common/GPSFix.h>#include <nodelet/nodelet.h>#include <novatel_gps_msgs/NovatelCorrectedImuData.h>#include <novatel_gps_msgs/NovatelFRESET.h>#include <novatel_gps_msgs/NovatelMessageHeader.h>#include <novatel_gps_msgs/NovatelPosition.h>#include <novatel_gps_msgs/NovatelPsrdop2.h>#include <novatel_gps_msgs/NovatelUtmPosition.h>#include <novatel_gps_msgs/NovatelVelocity.h>#include <novatel_gps_msgs/NovatelHeading2.h>#include <novatel_gps_msgs/NovatelDualAntennaHeading.h>#include <novatel_gps_msgs/Gpgga.h>#include <novatel_gps_msgs/Gprmc.h>#include <novatel_gps_msgs/Range.h>#include <novatel_gps_msgs/Time.h>#include <novatel_gps_msgs/Inspva.h>#include <novatel_gps_msgs/Inspvax.h>#include <novatel_gps_driver/novatel_gps.h>#include <ros/ros.h>#include <sensor_msgs/Imu.h>#include <sensor_msgs/NavSatFix.h>#include <std_msgs/Time.h>#include <swri_math_util/math_util.h>#include <swri_roscpp/parameters.h>#include <swri_roscpp/publisher.h>#include <swri_roscpp/subscriber.h>#include <swri_nodelet/class_list_macros.h>
Go to the source code of this file.
Classes | |
| class | novatel_gps_driver::NovatelGpsNodelet |
Namespaces | |
| novatel_gps_driver | |
This nodelet is a driver for Novatel OEM6 and FlexPack6 GPS receivers. It publishes standard ROS gps_common/GPSFix messages, as well as custom NovatelPosition, GPGGA, and GPRMC messages.
Topics Subscribed:
gps_sync std_msgs/Time - Timestamped sync pulses from a DIO module (optional). These are used to improve the accuracy of the time stamps of the messages published.
Topics Published:
gps gps_common/GPSFix - GPS data for navigation corrimudata novatel_gps_message/NovatelCorrectedImuData - Raw Novatel IMU data. (only published if publish_imu_messages is set true) gppga novatel_gps_driver/Gpgga - Raw GPGGA data for debugging (only published if publish_nmea_messages is set true) gpgsa novatel_gps_msgs/Gpgsa - Raw GPGSA data for debugging (only published if publish_gpgsa is set true) gprmc novatel_gps_msgs/Gprmc - Raw GPRMC data for debugging (only published if publish_nmea_messages is set true) bestpos novatel_gps_msgs/NovatelPosition - High fidelity Novatel- specific position and receiver status data. (only published if publish_novatel_positions is set true) bestutm novatel_gps_msgs/NovatelUtmPosition - High fidelity Novatel- specific position in UTM coordinates and receiver status data. (only published if publish_novatel_utm_positions is set true) bestvel novatel_gps_msgs/NovatelVelocity - High fidelity Novatel- specific velocity and receiver status data. (only published if publish_novatel_velocity is set true) range novatel_gps_msgs/Range - Satellite ranging information (only published if publish_range_messages is set true) time novatel_gps_msgs/Time - Novatel-specific time data. (Only published if publish_time is set true.) trackstat novatel_gps_msgs/Trackstat - Novatel-specific trackstat data at 1 Hz. (Only published if publish_trackstat is set true.)
Services:
freset novatel_gps_msgs/NovatelFRESET - Sends a freset message to the device with the specified target string to reset. By default does FRESET standard
Parameters:
connection_type str - "serial", "udp", or "tcp" as appropriate for the Novatel device connected. ["serial"] device str - The path to the device, e.g. /dev/ttyUSB0 for serial connections or "192.168.1.10:3001" for IP. [""] frame_id str - The TF frame ID to set in all published message headers. [""] gpgga_gprmc_sync_tol dbl - Sync tolarance (seconds) for syncing GPGGA messages with GPRMC messages. [0.01] gpgga_position_sync_tol dbl - Sync tolarance (seconds) for syncing GPGGA messages with BESTPOS messages. [0.01] imu_rate dbl - Rate at which to publish sensor_msgs/Imu messages. [100.0] imu_sample_rate dbl - Rate at which the device internally samples its IMU. [200.0] polling_period dbl - The number of seconds in between messages requested from the GPS. (Does not affect time messages) [0.05] publish_diagnostics bool - If set true, the driver publishes ROS diagnostics [true] publish_clocksteering bool - If set to true, the driver publishes Novatel ClockSteering messages [false] publish_imu_messages boot - If set true, the driver publishes Novatel CorrImuData, InsPva, InsPvax, InsStdev, and sensor_msgs/Imu messages [false] publish_gpgsa bool - If set true, the driver requests GPGSA messages from the device at 20 Hz and publishes them on gpgsa publish_nmea_messages bool - If set true, the driver publishes GPGGA and GPRMC messages (see Topics Published) [false] publish_novatel_messages bool - If set true, the driver publishes Novatel Bestpos messages (see Topics Published) [false] publish_novatel_velocity bool - If set true, the driver publishes Novatel Bestvel messages (see Topics Published) [false] publish_range_messages bool - If set true, the driver publishes Novatel RANGE messages [false] publish_sync_diagnostic bool - If true, publish a Sync diagnostic. This is ignored if publish_diagnostics is false. [true] publish_time bool - If set true, the driver publishes Novatel Time messages (see Topics Published) [false] publish_trackstat bool - If set true, the driver publishes Novatel Trackstat messages (see Topics Published) [false] reconnect_delay_s bool</t> - If the driver is disconnected from the device, how long (in seconds) to wait between reconnect attempts. [0.5] use_binary_message bool - If set true, the driver requests binary NovAtel messages from the device; if false, it requests ASCII messages. [false] wait_for_position bool - Wait for BESTPOS messages to arrive before publishing GPSFix messages. [false] span_frame_to_ros_frame bool - Translate the SPAN coordinate frame to a ROS coordinate frame using the VEHICLEBODYROTATION and APPLYVEHICLEBODYROTATION commands. [false]
Definition in file novatel_gps_nodelet.cpp.