sr_tactile_sensor_publisher.hpp
Go to the documentation of this file.
1 /*
2 * @file sr_tactile_sensor_publisher.hpp
3 * @author Ugo Cupcic <ugo@shadowrobot.com>
4 *
5 * Copyright 2015 Shadow Robot Company Ltd.
6 *
7 * This program is free software: you can redistribute it and/or modify it
8 * under the terms of the GNU General Public License as published by the Free
9 * Software Foundation version 2 of the License.
10 *
11 * This program is distributed in the hope that it will be useful, but WITHOUT
12 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
13 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 * more details.
15 *
16 * You should have received a copy of the GNU General Public License along
17 * with this program. If not, see <http://www.gnu.org/licenses/>.
18 *
19 * @brief Publishes PST tactile state
20 *
21 */
22 
23 #pragma once
24 
25 #include <sr_hardware_interface/tactile_sensors.hpp>
26 #include <sr_robot_msgs/ShadowPST.h>
28 #include <ros/ros.h>
29 #include <vector>
30 #include <string>
31 
32 namespace controller
33 {
34 
36 {
37 public:
38  SrTactileSensorPublisher(std::vector<tactiles::AllTactileData>* sensors, double publish_rate,
39  ros::NodeHandle nh_prefix, std::string prefix);
41  virtual void init(const ros::Time& time) {}
42  virtual void update(const ros::Time& time, const ros::Duration& period) {}
43 
44 protected:
45  std::vector<tactiles::AllTactileData>* sensors_;
47  double publish_rate_;
49  std::string prefix_;
50 };
51 
52 } // namespace controller
53 
54 /* For the emacs weenies in the crowd.
55 Local Variables:
56  c-basic-offset: 2
57 End:
58 */
virtual void init(const ros::Time &time)
virtual void update(const ros::Time &time, const ros::Duration &period)
SrTactileSensorPublisher(std::vector< tactiles::AllTactileData > *sensors, double publish_rate, ros::NodeHandle nh_prefix, std::string prefix)
std::vector< tactiles::AllTactileData > * sensors_
derived from ImuSensorController author: Adolfo Rodriguez Tsouroukdissian


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