35 #ifndef URG_NODE_URG_NODE_DRIVER_H 36 #define URG_NODE_URG_NODE_DRIVER_H 40 #include <dynamic_reconfigure/server.h> 44 #include <urg_node/URGConfig.h> 45 #include <std_srvs/Trigger.h> 80 bool statusCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
138 #endif // URG_NODE_URG_NODE_DRIVER_H void calibrate_time_offset()
ros::Publisher status_pub_
std::string product_name_
bool updateStatus()
Trigger an update of the lidar's status publish the latest known information about the lidar on latch...
std::string protocol_version_
boost::shared_ptr< urg_node::URGCWrapper > urg_
double diagnostics_window_time_
boost::shared_ptr< diagnostic_updater::HeaderlessTopicDiagnostic > laser_freq_
boost::thread diagnostics_thread_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
boost::thread scan_thread_
void update_reconfigure_limits()
boost::shared_ptr< diagnostic_updater::HeaderlessTopicDiagnostic > echoes_freq_
std::string firmware_version_
boost::mutex lidar_mutex_
std::string device_status_
volatile bool service_yield_
laser_proc::LaserPublisher echoes_pub_
bool statusCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
std::string firmware_date_
boost::shared_ptr< dynamic_reconfigure::Server< urg_node::URGConfig > > srv_
Dynamic reconfigure server.
ros::Publisher laser_pub_
double diagnostics_tolerance_
ros::ServiceServer status_service_
void populateDiagnosticsStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
void run()
Start's the nodes threads to run the lidar.
bool reconfigure_callback(urg_node::URGConfig &config, int level)