sr_muscle_hand_lib.hpp
Go to the documentation of this file.
1 /*
2 * @file sr_muscle_hand_lib.hpp
3 * @author Ugo Cupcic <ugo@shadowrobot.com>, Toni Oliver <toni@shadowrobot.com>, contact <software@shadowrobot.com>
4 * @date Tue Mar 19 17:12:13 2013
5 *
6 *
7 /* Copyright 2013 Shadow Robot Company Ltd.
8 *
9 * This program is free software: you can redistribute it and/or modify it
10 * under the terms of the GNU General Public License as published by the Free
11 * Software Foundation version 2 of the License.
12 *
13 * This program is distributed in the hope that it will be useful, but WITHOUT
14 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
15 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
16 * more details.
17 *
18 * You should have received a copy of the GNU General Public License along
19 * with this program. If not, see <http://www.gnu.org/licenses/>.
20 *
21 * @brief This is a library for the etherCAT muscle hand.
22 * You can find it instantiated in the sr_edc_ethercat_drivers.
23 *
24 *
25 */
26 
27 #ifndef _SR_MUSCLE_HAND_LIB_HPP_
28 #define _SR_MUSCLE_HAND_LIB_HPP_
29 
31 #include <std_srvs/Empty.h>
32 
33 // to be able to load the configuration from the
34 // parameter server
35 #include <ros/ros.h>
36 #include <string>
37 #include <vector>
38 
39 
40 namespace shadow_robot
41 {
42 template<class StatusType, class CommandType>
44  public SrMuscleRobotLib<StatusType, CommandType>
45 {
46 public:
47  SrMuscleHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde,
48  std::string device_id, std::string joint_prefix);
49 
50  /*
51  * Reset the muscle driver at motor index.
52  *
53  * @param request empty
54  * @param response empty
55  * @param muscle_driver_index The index of the muscle driver we're resetting
56  *
57  * @return true if success
58  */
59  bool reset_muscle_driver_callback(std_srvs::Empty::Request &request,
60  std_srvs::Empty::Response &response,
61  int muscle_driver_index);
62 
63 #ifdef DEBUG_PUBLISHER
64  /*
65  * This is a service callback: we set the debug data we want to publish
66  * at full speed in the debug topics.
67  *
68  * @param request Contains the motor index and the MOTOR_DATA type
69  * @param response True if succeeded.
70  *
71  * @return true if succeeded.
72  */
73  bool set_debug_data_to_publish(sr_robot_msgs::SetDebugData::Request& request,
74  sr_robot_msgs::SetDebugData::Response& response);
75 #endif
76 
77 protected:
78  /*
79  * Initializes the hand library with the needed values.
80  *
81  * @param joint_names A vector containing all the joint names.
82  * @param actuator_ids A vector containing the corresponding actuator ids.
83  * @param joint_to_sensors A vector mapping the joint to the sensor index we read from the palm.
84  */
85  virtual void initialize(std::vector<std::string> joint_names, std::vector<int> actuator_ids,
86  std::vector<shadow_joints::JointToSensor> joint_to_sensors);
87 
88  /*
89  * Initializes the hand library with the needed values.
90  *
91  * @param joint_names A vector containing all the joint names.
92  * @param actuator_ids A vector containing the corresponding actuator ids.
93  * @param joint_to_sensors A vector mapping the joint to the sensor index we read from the palm.
94  */
95  void initialize(std::vector<std::string> joint_names, std::vector<shadow_joints::JointToMuscle> actuator_ids,
96  std::vector<shadow_joints::JointToSensor> joint_to_sensors);
97 
98 private:
99  /*
100  * Reads the mapping associating a joint to a muscle.
101  * If the muscle index is -1, then no muscle is associated
102  * to this joint.
103  *
104  *
105  * @return a vector of JointToMuscle structures (containing the indexes of the muscles for the joint), ordered by joint.
106  */
107  std::vector<shadow_joints::JointToMuscle> read_joint_to_muscle_mapping();
108 
109 
110  static const int nb_muscle_data;
111  static const char *human_readable_muscle_data_types[];
112  static const int32u muscle_data_types[];
113 
114 #ifdef DEBUG_PUBLISHER
115  ros::ServiceServer debug_service;
117 #endif
118 };
119 } // namespace shadow_robot
120 
121 /* For the emacs weenies in the crowd.
122 Local Variables:
123  c-basic-offset: 2
124 End:
125 */
126 
127 #endif
bool reset_muscle_driver_callback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response, int muscle_driver_index)
static const int32u muscle_data_types[]
unsigned int int32u
virtual void initialize(std::vector< std::string > joint_names, std::vector< int > actuator_ids, std::vector< shadow_joints::JointToSensor > joint_to_sensors)
static const char * human_readable_muscle_data_types[]
SrMuscleHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix)
std::vector< shadow_joints::JointToMuscle > read_joint_to_muscle_mapping()


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