ev3_touch_controller.h
1 /*
2  * This file (ev3_touch_controller.h) is part of h4r_ev3_control.
3  * Date: 01.01.2016
4  *
5  * Author: Christian Holl
6  * http://github.com/Hacks4ROS
7  *
8  * h4r_ev3_control is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * h4r_ev3_control is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with h4r_ev3_control. If not, see <http://www.gnu.org/licenses/>.
20  *
21  */
22 #ifndef TOUCH_CONTROLLER_H_
23 #define TOUCH_CONTROLLER_H_
24 
25 #include <controller_interface/controller.h>
26 #include <pluginlib/class_list_macros.h>
27 #include <realtime_tools/realtime_publisher.h>
28 #include <boost/shared_ptr.hpp>
29 #include <std_msgs/Bool.h>
30 #include <limits>
31 
32 #include <h4r_ev3_control/Ev3SensorInterface.h>
33 
34 namespace ev3_control
35 {
36 
51 class Ev3TouchController: public controller_interface::Controller<
52  Ev3SensorInterface>
53 {
54 private:
55  std::string port_;
56  Ev3SensorHandle handle_;
57  H4REv3TouchSensorSpecIface touch_interface_;
58  bool sensor_mode_needs_init_;
59 
60  std::string frame_id_;
61 
62  //Range Publisher
63  typedef boost::shared_ptr<
64  realtime_tools::RealtimePublisher<std_msgs::Bool> > RtBoolPublisherPtr;
65  RtBoolPublisherPtr realtime_bool_publisher_;
66 
67 
68 
69  ros::Time last_publish_time_;
70  double publish_rate_;
71 
72 public:
74  virtual ~Ev3TouchController();
75 
76  virtual bool init(Ev3SensorInterface* hw,
77  ros::NodeHandle &root_nh,
78  ros::NodeHandle& ctrl_nh);
79 
80  virtual void starting(const ros::Time& time);
81  virtual void update(const ros::Time& time, const ros::Duration& /*period*/);
82  virtual void stopping(const ros::Time& /*time*/){}
83 
84 };
85 
86 } /* namespace ev3_control */
87 
88 #endif /* TOUCH_CONTROLLER_H_ */
Definition: Ev3SensorInterface.h:35
Definition: ev3_touch_controller.h:51
Definition: Ev3SensorInterface.h:97