sr_ubi_tactile_sensor_publisher.hpp
Go to the documentation of this file.
1 /*
2 * @file sr_ubi_tactile_sensor_publisher.hpp
3 * @author Guillaume Walck <gwalck@techfak.uni-bielefeld.de>
4 * @date Aug 25 2014
5 *
6 * Copyright 2015 Shadow Robot Company Ltd.
7 *
8 * This program is free software: you can redistribute it and/or modify it
9 * under the terms of the GNU General Public License as published by the Free
10 * Software Foundation version 2 of the License.
11 *
12 * This program is distributed in the hope that it will be useful, but WITHOUT
13 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
14 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
15 * more details.
16 *
17 * You should have received a copy of the GNU General Public License along
18 * with this program. If not, see <http://www.gnu.org/licenses/>.
19 *
20 * @brief Publishes ubi tactile state
21 *
22 */
23 
25 
26 #pragma once
27 
30 #include <sr_robot_msgs/UBI0All.h>
31 #include <sr_robot_msgs/MidProxDataAll.h>
32 #include <vector>
33 #include <string>
34 
35 namespace controller
36 {
37 
39 {
40 public:
41  SrUbiTactileSensorPublisher(std::vector<tactiles::AllTactileData>* sensors, double publish_rate,
42  ros::NodeHandle nh_prefix, std::string prefix)
43  : SrTactileSensorPublisher(sensors, publish_rate, nh_prefix, prefix) {}
44  virtual void init(const ros::Time& time);
45  virtual void update(const ros::Time& time, const ros::Duration& period);
46 
47 private:
52  UbiPublisherPtr ubi_realtime_pub_;
53  MidProxPublisherPtr midprox_realtime_pub_;
54 };
55 
56 } // namespace controller
57 
58 /* For the emacs weenies in the crowd.
59 Local Variables:
60  c-basic-offset: 2
61 End:
62 */
63 
virtual void update(const ros::Time &time, const ros::Duration &period)
SrUbiTactileSensorPublisher(std::vector< tactiles::AllTactileData > *sensors, double publish_rate, ros::NodeHandle nh_prefix, std::string prefix)
boost::shared_ptr< MidProxPublisher > MidProxPublisherPtr
Publishes PST tactile state.
derived from ImuSensorController author: Adolfo Rodriguez Tsouroukdissian
realtime_tools::RealtimePublisher< sr_robot_msgs::MidProxDataAll > MidProxPublisher
realtime_tools::RealtimePublisher< sr_robot_msgs::UBI0All > UbiPublisher


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