biotac.hpp
Go to the documentation of this file.
1 /*
2 * @file biotac.hpp
3 * @author Ugo Cupcic <ugo@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 * Biotac tactiles.
23 *
24 *
25 */
26 
27 #ifndef _BIOTAC_HPP_
28 #define _BIOTAC_HPP_
29 
30 #include <vector>
31 #include <string>
32 #include <sr_robot_msgs/BiotacAll.h>
33 #include <sr_robot_msgs/Biotac.h>
35 
38 
39 namespace tactiles
40 {
41 template<class StatusType, class CommandType>
42 class Biotac :
43  public GenericTactiles<StatusType, CommandType>
44 {
45 public:
46  Biotac(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
48 
49  Biotac(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
51  boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector);
52 
53  /*
54  * This function is called in the constructors, to initialize the necessary objects
55  */
56  void init(std::vector<generic_updater::UpdateConfig> update_configs_vector,
58 
59  /*
60  * This function is called each time a new etherCAT message
61  * is received in the sr06.cpp driver. It updates the tactile
62  * sensors values contained in tactiles_vector.
63  *
64  * @param status_data the received etherCAT message
65  */
66  virtual void update(StatusType *status_data);
67 
68  /*
69  * Publish the information to a ROS topic.
70  *
71  */
72  virtual void publish();
73 
74  /*
75  * This function adds the diagnostics for the tactiles to the
76  * multi diagnostic status published by the hand.
77  */
78  virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
80 
81 
82  virtual std::vector<AllTactileData> *get_tactile_data();
83 
85 
86 protected:
88 
89  static const size_t nb_electrodes_v1_;
90  static const size_t nb_electrodes_v2_;
91 }; // end class
92 } // namespace tactiles
93 
94 /* For the emacs weenies in the crowd.
95 Local Variables:
96  c-basic-offset: 2
97 End:
98 */
99 
100 #endif /* _SHADOW_PSTS_HPP_ */
d
virtual void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
Definition: biotac.cpp:396
void init(std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: biotac.cpp:70
static const size_t nb_electrodes_v1_
Definition: biotac.hpp:89
virtual void update(StatusType *status_data)
Definition: biotac.cpp:84
void set_version_specific_details()
Definition: biotac.cpp:428
static const size_t nb_electrodes_v2_
Definition: biotac.hpp:90
Biotac(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: biotac.cpp:44
size_t nb_electrodes_
Definition: biotac.hpp:87
virtual std::vector< AllTactileData > * get_tactile_data()
Definition: biotac.cpp:422
virtual void publish()
Definition: biotac.cpp:390


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