UBI0.hpp
Go to the documentation of this file.
1 /*
2 * @file UBI0.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 * Biotac tactiles.
23 *
24 *
25 */
26 
27 #ifndef _UBI0_HPP_
28 #define _UBI0_HPP_
29 
30 #include <vector>
31 #include <string>
32 #include <sr_robot_msgs/UBI0All.h>
33 #include <sr_robot_msgs/UBI0.h>
34 #include <sr_robot_msgs/AuxSpiData.h>
35 #include <sr_robot_msgs/MidProxDataAll.h>
36 #include <sr_robot_msgs/MidProxData.h>
38 
41 
42 namespace tactiles
43 {
44 template<class StatusType, class CommandType>
45 class UBI0 :
46  public GenericTactiles<StatusType, CommandType>
47 {
48 public:
49  UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
51 
52  UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
54  boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector);
55 
56  /*
57  * This function is called in the constructors, to initialize the necessary objects
58  */
59  void init(std::vector<generic_updater::UpdateConfig> update_configs_vector,
61 
62  /*
63  * This function is called each time a new etherCAT message
64  * is received in the sr06.cpp driver. It updates the tactile
65  * sensors values contained in tactiles_vector.
66  *
67  * @param status_data the received etherCAT message
68  */
69  virtual void update(StatusType *status_data);
70 
71  /*
72  * Publish the information to a ROS topic.
73  *
74  */
75  virtual void publish();
76 
77  /*
78  * This function adds the diagnostics for the tactiles to the
79  * multi diagnostic status published by the hand.
80  */
81  virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
83 
84 
85  virtual std::vector<AllTactileData> *get_tactile_data();
86 
87 protected:
90 
93 
94  // Auxiliar Spi data (sometimes it is a palm tactile sensor) real time publisher
96 }; // end class
97 
98 
99 // class template specialization.
100 
101 /*
102 * This is a specialization of the template class to avoid that the compiler try to access non existent fields,
103 * as it will compile the class for all the desired combinations of StatusType and CommandType,
104 * but in runtime this class will only be instantiated for those StatusType that actually contain UBI0 sensor data
105 */
106 template<>
107 class UBI0<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> :
108  public GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
109  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>
110 {
111 public:
112  UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
114  : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
115  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
116  {
117  ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
118  }
119 
120  UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
122  boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector)
123  : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
124  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
125  {
126  ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
127  }
128 
130  {
131  };
132 }; // end class
133 
134 template<>
135 class UBI0<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND> :
136  public GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
137  ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>
138 {
139 public:
140  UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
142  : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
143  ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
144  {
145  ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
146  }
147 
148  UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
150  boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector)
151  : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
152  ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
153  {
154  ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
155  }
156 
158  {
159  };
160 }; // end class
161 
162 template<>
163 class UBI0<ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_COMMAND> :
164  public GenericTactiles<ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_STATUS,
165  ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_COMMAND>
166 {
167 public:
168  UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
170  : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_STATUS,
171  ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
172  {
173  ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
174  }
175 
176  UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
178  boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector)
179  : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_STATUS,
180  ETHERCAT_DATA_STRUCTURE_0240_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
181  {
182  ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
183  }
184 
186  {
187  };
188 }; // end class
189 
190 } // namespace tactiles
191 
192 /* For the emacs weenies in the crowd.
193 Local Variables:
194  c-basic-offset: 2
195 End:
196 */
197 
198 #endif /* _UBI0_HPP_ */
d
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector< GenericTactileData > > init_tactiles_vector)
Definition: UBI0.hpp:120
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: UBI0.cpp:37
virtual std::vector< AllTactileData > * get_tactile_data()
Definition: UBI0.cpp:220
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: UBI0.hpp:112
virtual void update(StatusType *status_data)
Definition: UBI0.cpp:84
void init(std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: UBI0.cpp:62
boost::shared_ptr< UBI0PalmData > palm_tactiles
the object containing the data from the palm sensors
Definition: UBI0.hpp:92
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: UBI0.hpp:168
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
Definition: UBI0.hpp:140
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::AuxSpiData > > aux_spi_publisher
Definition: UBI0.hpp:95
boost::shared_ptr< std::vector< UBI0Data > > tactiles_vector
the vector containing the data for the tactiles.
Definition: UBI0.hpp:89
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector< GenericTactileData > > init_tactiles_vector)
Definition: UBI0.hpp:176
virtual void publish()
Definition: UBI0.cpp:177
#define ROS_ERROR(...)
virtual void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
Definition: UBI0.cpp:194
UBI0(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector< GenericTactileData > > init_tactiles_vector)
Definition: UBI0.hpp:148


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