generic_tactiles.hpp
Go to the documentation of this file.
1 /*
2 * @file generic_tactiles.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 the main class for accessing the data from the
22 * tactiles.
23 *
24 *
25 */
26 
27 #ifndef GENERIC_TACTILES_HPP_
28 #define GENERIC_TACTILES_HPP_
29 
30 #include <boost/smart_ptr.hpp>
32 
33 extern "C"
34 {
39 }
40 
41 #include <ros/ros.h>
42 #include <vector>
43 #include <string>
44 #include <std_srvs/Empty.h>
45 
46 #include <diagnostic_msgs/DiagnosticStatus.h>
48 
49 #include <sr_hardware_interface/tactile_sensors.hpp>
52 
53 namespace tactiles
54 {
55 template<class StatusType, class CommandType>
57 {
58 public:
59  GenericTactiles(ros::NodeHandle nh, std::string device_id,
60  std::vector<generic_updater::UpdateConfig> update_configs_vector,
62 
63  virtual ~GenericTactiles()
64  {
65  }
66 
67  /*
68  * This function is called each time a new etherCAT message
69  * is received in the sr06.cpp driver. It updates the tactile
70  * sensors values contained in tactiles_vector.
71  *
72  * @param status_data the received etherCAT message
73  */
74  virtual void update(StatusType *status_data);
75 
76  /*
77  * Publish the information to a ROS topic.
78  *
79  */
80  virtual void publish();
81 
82  /*
83  * This function adds the diagnostics for the tactiles to the
84  * multi diagnostic status published by the hand.
85  */
86  virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
88 
89  /*
90  * Reset the tactile sensors.
91  *
92  * @param request empty
93  * @param response empty
94  *
95  * @return true if success
96  */
97  bool reset(std_srvs::Empty::Request &request,
98  std_srvs::Empty::Response &response);
99 
101  static const unsigned int nb_tactiles;
102 
106 
107  virtual std::vector<AllTactileData> *get_tactile_data();
108 
109 protected:
111 
113  std::string device_id_;
114 
116 
117  // Contains the received data types.
119 
120  /*
121  * Sanitise a string coming from the palm. Make sure we're not
122  * outputting garbage in the diagnostics topic.
123  * The acceptable range for the char is [0x20 .. 0x7E]
124  *
125  * @param raw_string The incoming raw string
126  * @param str_size The max size of the string
127  *
128  * @return The sanitised string.
129  */
130  std::string sanitise_string(const char *raw_string, const unsigned int str_size);
131 
133 }; // end class
134 } // namespace tactiles
135 
136 /* For the emacs weenies in the crowd.
137 Local Variables:
138  c-basic-offset: 2
139 End:
140 */
141 
142 #endif /* GENERIC_TACTILES_HPP_ */
d
bool reset(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
static const unsigned int nb_tactiles
Number of tactile sensors (TODO: should probably be defined in the protocol)
virtual void update(StatusType *status_data)
boost::shared_ptr< generic_updater::SensorUpdater< CommandType > > sensor_updater
unsigned int int32u
boost::shared_ptr< std::vector< GenericTactileData > > tactiles_vector
the vector containing the data for the tactiles.
std::vector< int32u > initialization_received_data_vector
virtual std::vector< AllTactileData > * get_tactile_data()
GenericTactiles(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
void process_received_data_type(int32u data)
virtual void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
boost::shared_ptr< std::vector< AllTactileData > > all_tactile_data
std::string sanitise_string(const char *raw_string, const unsigned int str_size)
ros::ServiceServer reset_service_client_


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