.. _program_listing_file__tmp_ws_src_novatel_gps_driver_novatel_gps_driver_include_novatel_gps_driver_nodes_novatel_gps_node.h: Program Listing for File novatel_gps_node.h =========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/novatel_gps_driver/novatel_gps_driver/include/novatel_gps_driver/nodes/novatel_gps_node.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // ***************************************************************************** // // Copyright (c) 2019, Southwest Research Institute® (SwRI®) // All rights reserved. // // Redistribution and use in source and binary forms, with or without // modification, are permitted provided that the following conditions are met: // * Redistributions of source code must retain the above copyright // notice, this list of conditions and the following disclaimer. // * Redistributions in binary form must reproduce the above copyright // notice, this list of conditions and the following disclaimer in the // documentation and/or other materials provided with the distribution. // * Neither the name of Southwest Research Institute® (SwRI®) nor the // names of its contributors may be used to endorse or promote products // derived from this software without specific prior written permission. // // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. // // ***************************************************************************** #ifndef NOVATEL_GPS_DRIVER_NOVATEL_GPS_NODE_H #define NOVATEL_GPS_DRIVER_NOVATEL_GPS_NODE_H #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include using TimeParserMsgT = novatel_gps_driver::TimeParser::MessageType; namespace novatel_gps_driver { class NovatelGpsNode : public rclcpp::Node { public: explicit NovatelGpsNode(const rclcpp::NodeOptions& options); ~NovatelGpsNode() override; void SyncCallback(const builtin_interfaces::msg::Time::ConstSharedPtr& sync); void Spin(); private: // Parameters std::string device_; std::string connection_type_; int32_t serial_baud_; double polling_period_; bool publish_gpgsa_; bool publish_gpgsv_; bool publish_gphdt_; double imu_rate_; double imu_sample_rate_; bool span_frame_to_ros_frame_; bool publish_clock_steering_; bool publish_imu_messages_; bool publish_novatel_positions_; bool publish_novatel_xyz_positions_; bool publish_novatel_utm_positions_; bool publish_novatel_velocity_; bool publish_novatel_heading2_; bool publish_novatel_dual_antenna_heading_; bool publish_novatel_psrdop2_; bool publish_nmea_messages_; bool publish_range_messages_; bool publish_time_messages_; bool publish_time_reference_; bool publish_trackstat_; bool publish_diagnostics_; bool publish_sync_diagnostic_; bool publish_invalid_gpsfix_; double reconnect_delay_s_; bool use_binary_messages_; rclcpp::Publisher::SharedPtr clocksteering_pub_; rclcpp::Publisher::SharedPtr fix_pub_; rclcpp::Publisher::SharedPtr gps_pub_; rclcpp::Publisher::SharedPtr imu_pub_; rclcpp::Publisher::SharedPtr inscov_pub_; rclcpp::Publisher::SharedPtr inspva_pub_; rclcpp::Publisher::SharedPtr inspvax_pub_; rclcpp::Publisher::SharedPtr insstdev_pub_; rclcpp::Publisher::SharedPtr novatel_imu_pub_; rclcpp::Publisher::SharedPtr novatel_position_pub_; rclcpp::Publisher::SharedPtr novatel_xyz_position_pub_; rclcpp::Publisher::SharedPtr novatel_utm_pub_; rclcpp::Publisher::SharedPtr novatel_velocity_pub_; rclcpp::Publisher::SharedPtr novatel_heading2_pub_; rclcpp::Publisher::SharedPtr novatel_dual_antenna_heading_pub_; rclcpp::Publisher::SharedPtr novatel_psrdop2_pub_; rclcpp::Publisher::SharedPtr gpgga_pub_; rclcpp::Publisher::SharedPtr gpgsv_pub_; rclcpp::Publisher::SharedPtr gpgsa_pub_; rclcpp::Publisher::SharedPtr gphdt_pub_; rclcpp::Publisher::SharedPtr gprmc_pub_; rclcpp::Publisher::SharedPtr range_pub_; rclcpp::Publisher::SharedPtr time_pub_; rclcpp::Publisher::SharedPtr time_ref_pub_; rclcpp::Publisher::SharedPtr trackstat_pub_; rclcpp::Service::SharedPtr reset_service_; NovatelGps::ConnectionType connection_; NovatelGps gps_; boost::thread thread_; boost::mutex mutex_; swri::Subscriber sync_sub_; rclcpp::Time last_sync_; boost::circular_buffer sync_times_; boost::circular_buffer msg_times_; boost::accumulators::accumulator_set > offset_stats_; boost::accumulators::accumulator_set > rolling_offset_; // ROS diagnostics std::string error_msg_; diagnostic_updater::Updater diagnostic_updater_; std::string hw_id_; double expected_rate_; int32_t device_timeouts_; int32_t device_interrupts_; int32_t device_errors_; int32_t gps_parse_failures_; int32_t gps_insufficient_data_warnings_; int32_t publish_rate_warnings_; int32_t measurement_count_; rclcpp::Time last_published_; novatel_gps_msgs::msg::NovatelPosition::SharedPtr last_novatel_position_; std::string imu_frame_id_; std::string frame_id_; bool resetService(std::shared_ptr request_header, novatel_gps_msgs::srv::NovatelFRESET::Request::SharedPtr req, novatel_gps_msgs::srv::NovatelFRESET::Response::SharedPtr res); void CheckDeviceForData(); sensor_msgs::msg::NavSatFix::UniquePtr ConvertGpsFixToNavSatFix(const gps_msgs::msg::GPSFix::UniquePtr& msg); void CalculateTimeSync(); void FixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& status); void SyncDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& status); void DeviceDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& status); void GpsDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& status); void DataDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& status); void RateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& status); rclcpp::Time NovatelTimeToLocalTime(const TimeParserMsgT & utc_time); }; } #endif //NOVATEL_GPS_DRIVER_NOVATEL_GPS_NODE_H