/* -*- mode: C++ -*- */ /* * Copyright (C) 2012 Austin Robot Technology, Jack O'Quin * Copyright (C) 2017 Robosense, Tony Zhang * * License: Modified BSD Software License Agreement * * $Id$ */ /** \file * * ROS driver interface for the RSLIDAR 3D LIDARs */ #ifndef _RSDRIVER_H_ #define _RSDRIVER_H_ #include "input.h" //#include //#include //#include //#include //#include //#include //#include //#include //#include #include #include "boost/thread.hpp" namespace rs_driver { struct lidarscan { double stamp; std::string frame_id; std::vector packets; }; class rslidarDriver { public: /** * @brief rslidarDriver * @param node raw packet output topic * @param private_nh 通过这个节点传参数 */ // rslidarDriver(ros::NodeHandle node, ros::NodeHandle private_nh); rslidarDriver(); ~rslidarDriver() {} bool poll(std::shared_ptr & rawscan); void difopPoll(void); private: /// Callback for dynamic reconfigure // void callback(rslidar_driver::rslidarNodeConfig &config, uint32_t level); // /// Pointer to dynamic reconfigure service srv_ // boost::shared_ptr< // dynamic_reconfigure::Server> // srv_; // configuration parameters struct { std::string frame_id; ///< tf frame ID std::string model; ///< device model name int npackets; ///< number of packets to collect double rpm; ///< device rotation rate (RPMs) double time_offset; ///< time in seconds added to each time stamp bool start_from_edge; } config_; boost::shared_ptr msop_input_; boost::shared_ptr difop_input_; // ros::Publisher msop_output_; // ros::Publisher difop_output_; boost::shared_ptr difop_thread_; // Converter convtor_; /** diagnostics updater */ // diagnostic_updater::Updater diagnostics_; // double diag_min_freq_; // double diag_max_freq_; // boost::shared_ptr diag_topic_; }; } // namespace rs_driver #endif