sr_tactile_sensor_controller.hpp
Go to the documentation of this file.
1  /*
2 * @file sr_tactile_sensor_controller.hpp
3 * @author Guillaume Walck <gwalck@techfak.uni-bielefeld.de>
4 * @date Aug 22 2014
5 *
6 * Copyright 2014 University of Bielefeld
7 *
8 * @brief Generic controller for tactile sensor data publishing.
9 *
10 */
11 
13 // Copyright (C) 2012, hiDOF INC.
14 // Copyright (C) 2013, PAL Robotics S.L.
15 //
16 // Redistribution and use in source and binary forms, with or without
17 // modification, are permitted provided that the following conditions are met:
18 // * Redistributions of source code must retain the above copyright notice,
19 // this list of conditions and the following disclaimer.
20 // * Redistributions in binary form must reproduce the above copyright
21 // notice, this list of conditions and the following disclaimer in the
22 // documentation and/or other materials provided with the distribution.
23 // * Neither the name of PAL Robotics S.L. nor the names of its
24 // contributors may be used to endorse or promote products derived from
25 // this software without specific prior written permission.
26 //
27 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
28 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
29 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
30 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
31 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
32 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
33 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
34 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
35 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
36 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
37 // POSSIBILITY OF SUCH DAMAGE.
40 
41 #pragma once
42 
45 #include <sr_hardware_interface/sr_actuator.hpp>
46 #include <boost/shared_ptr.hpp>
47 #include <ros_ethercat_model/robot_state_interface.hpp>
48 
50 #include <vector>
51 #include <string>
52 
53 namespace controller
54 {
55 // this controller gets access to the SrTactileSensorInterface
56 class SrTactileSensorController: public controller_interface::Controller<ros_ethercat_model::RobotStateInterface>
57 {
58 public:
60  virtual bool init(ros_ethercat_model::RobotStateInterface* hw,
61  ros::NodeHandle &root_nh,
62  ros::NodeHandle& controller_nh);
63  virtual void starting(const ros::Time& time);
64  virtual void update(const ros::Time& time, const ros::Duration& period);
65  virtual void stopping(const ros::Time& time);
66 
67 protected:
68  std::vector<tactiles::AllTactileData>* sensors_;
69  double publish_rate_;
71  std::string prefix_;
74 };
75 
76 } // namespace controller
77 
78 /* For the emacs weenies in the crowd.
79 Local Variables:
80  c-basic-offset: 2
81 End:
82 */
83 
virtual void stopping(const ros::Time &time)
virtual void starting(const ros::Time &time)
boost::shared_ptr< SrTactileSensorPublisher > sensor_publisher_
virtual void update(const ros::Time &time, const ros::Duration &period)
std::vector< tactiles::AllTactileData > * sensors_
virtual bool init(ros_ethercat_model::RobotStateInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Publishes PST tactile state.
derived from ImuSensorController author: Adolfo Rodriguez Tsouroukdissian


sr_tactile_sensor_controller
Author(s): Guillaume Walck
autogenerated on Tue Oct 13 2020 04:02:07