1 #ifndef TOPOSENS_ECHO_DRIVER_ECHO_DRIVER_H 2 #define TOPOSENS_ECHO_DRIVER_ECHO_DRIVER_H 7 #include <boost/thread/recursive_mutex.hpp> 9 #include <dynamic_reconfigure/server.h> 15 #include "toposens_echo_driver/EchoOneDriverConfig.h" 42 void reconfigure(
const EchoOneDriverConfig& config, uint32_t level);
56 #endif // TOPOSENS_ECHO_DRIVER_ECHO_DRIVER_H ros::Publisher ts_scan_publisher_
ros::ServiceServer adc_dump_service_
RosParameters parameters_
void configureDynamicReconfigureServer()
boost::recursive_mutex dynamic_reconfigure_server_mutex_
EchoOneDriver(ros::NodeHandle nh, RosParameters parameters)
ros::Publisher point_cloud_publisher_
void publishStaticTransforms()
Publish static TFs between sensor coordinate frames.
void measure()
Triggers single-shot measurement from sensor and publishes TsScan ROS message with result...
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
This file contains the highlevel interface prototypes to the low-level Protocol.
std::unique_ptr< EchoOneDriverConfigServer > dynamic_reconfigure_server_
void reconfigure(const EchoOneDriverConfig &config, uint32_t level)
dynamic_reconfigure::Server< EchoOneDriverConfig > EchoOneDriverConfigServer