echo_driver.h
Go to the documentation of this file.
1 #ifndef TOPOSENS_ECHO_DRIVER_ECHO_DRIVER_H
2 #define TOPOSENS_ECHO_DRIVER_ECHO_DRIVER_H
3 
4 #include <memory>
5 #include <vector>
6 
7 #include <boost/thread/recursive_mutex.hpp>
8 
9 #include <dynamic_reconfigure/server.h>
10 #include <ros/ros.h>
12 
13 #include <toposens/sensor_lib.h>
14 
15 #include "toposens_echo_driver/EchoOneDriverConfig.h"
17 
18 namespace toposens_echo_driver
19 {
20 using EchoOneDriverConfigServer = dynamic_reconfigure::Server<EchoOneDriverConfig>;
21 
23 {
24 public:
27 
32  void measure();
33 
38 
39 private:
40  void initialize();
42  void reconfigure(const EchoOneDriverConfig& config, uint32_t level);
43 
49 
50  std::unique_ptr<EchoOneDriverConfigServer> dynamic_reconfigure_server_;
51  boost::recursive_mutex dynamic_reconfigure_server_mutex_;
52 };
53 
54 } // namespace toposens_echo_driver
55 
56 #endif // TOPOSENS_ECHO_DRIVER_ECHO_DRIVER_H
ros::ServiceServer adc_dump_service_
Definition: echo_driver.h:46
boost::recursive_mutex dynamic_reconfigure_server_mutex_
Definition: echo_driver.h:51
EchoOneDriver(ros::NodeHandle nh, RosParameters parameters)
Definition: echo_driver.cpp:11
void publishStaticTransforms()
Publish static TFs between sensor coordinate frames.
Definition: echo_driver.cpp:88
void measure()
Triggers single-shot measurement from sensor and publishes TsScan ROS message with result...
Definition: echo_driver.cpp:74
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
Definition: echo_driver.h:47
This file contains the highlevel interface prototypes to the low-level Protocol.
std::unique_ptr< EchoOneDriverConfigServer > dynamic_reconfigure_server_
Definition: echo_driver.h:50
void reconfigure(const EchoOneDriverConfig &config, uint32_t level)
dynamic_reconfigure::Server< EchoOneDriverConfig > EchoOneDriverConfigServer
Definition: echo_driver.h:20


toposens_echo_driver
Author(s): Tobias Roth , Dennis Maier , Baris Yazici
autogenerated on Mon Feb 28 2022 23:57:42