shadow_PSTs.hpp
Go to the documentation of this file.
1 /*
2 * @file shadow_PSTs.hpp
3 * @author Toni Oliver <toni@shadowrobot.com>
4 * @date Th Oct 20 10:06:14 2011
5 *
6 /* Copyright 2011 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 *
21 * @brief This is a class for accessing the data from the
22 * PSTs tactiles.
23 *
24 *
25 */
26 
27 #ifndef _SHADOW_PSTS_HPP_
28 #define _SHADOW_PSTS_HPP_
29 
30 #include <vector>
31 #include <string>
32 #include <sr_robot_msgs/ShadowPST.h>
34 
35 #include <sr_hardware_interface/tactile_sensors.hpp>
38 
39 namespace tactiles
40 {
41 template<class StatusType, class CommandType>
42 class ShadowPSTs :
43  public GenericTactiles<StatusType, CommandType>
44 {
45 public:
46  ShadowPSTs(ros::NodeHandle nh, std::string device_id,
47  std::vector<generic_updater::UpdateConfig> update_configs_vector,
49 
50  ShadowPSTs(ros::NodeHandle nh, std::string device_id,
51  std::vector<generic_updater::UpdateConfig> update_configs_vector,
53  boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector);
54 
55  void init(std::vector<generic_updater::UpdateConfig> update_configs_vector,
57 
58  /*
59  * This function is called each time a new etherCAT message
60  * is received in the sr06.cpp driver. It updates the tactile
61  * sensors values contained in tactiles_vector.
62  *
63  * @param status_data the received etherCAT message
64  */
65  virtual void update(StatusType *status_data);
66 
67  /*
68  * Publish the information to a ROS topic.
69  *
70  */
71  virtual void publish();
72 
73  /*
74  * This function adds the diagnostics for the tactiles to the
75  * multi diagnostic status published by the hand.
76  */
77  virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
79 
82 
83  virtual std::vector<AllTactileData> *get_tactile_data();
84 
85 protected:
86 }; // end class
87 } // namespace tactiles
88 
89 /* For the emacs weenies in the crowd.
90 Local Variables:
91  c-basic-offset: 2
92 End:
93 */
94 
95 #endif /* _SHADOW_PSTS_HPP_ */
d
virtual void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
virtual std::vector< AllTactileData > * get_tactile_data()
void init(std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: shadow_PSTs.cpp:63
boost::shared_ptr< std::vector< PST3Data > > tactiles_vector
the vector containing the data for the tactiles.
Definition: shadow_PSTs.hpp:81
virtual void publish()
ShadowPSTs(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: shadow_PSTs.cpp:37
virtual void update(StatusType *status_data)
Definition: shadow_PSTs.cpp:78


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Tue Oct 13 2020 04:01:57