hand_commander.hpp
Go to the documentation of this file.
1 /*
2 * Copyright 2012 Shadow Robot Company Ltd.
3 *
4 * This program is free software: you can redistribute it and/or modify it
5 * under the terms of the GNU General Public License as published by the Free
6 * Software Foundation version 2 of the License.
7 *
8 * This program is distributed in the hope that it will be useful, but WITHOUT
9 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 * more details.
12 *
13 * You should have received a copy of the GNU General Public License along
14 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 */
16 
30 #pragma once
31 
32 #include <ros/ros.h>
33 #include <vector>
34 #include <string>
35 #include <map>
36 #include <utility>
37 
38 #include <boost/smart_ptr.hpp>
39 #include <boost/ptr_container/ptr_map.hpp>
40 #include <sr_robot_msgs/joint.h>
41 #include <urdf/model.h>
42 
43 using ros::Publisher;
44 using ros::NodeHandle;
45 
47 {
48  enum HandType
49  {
51  CAN,
53  };
54 } // namespace shadowhandRosLib
55 
56 namespace shadowrobot
57 {
63 {
64 public:
65  explicit HandCommander(const std::string &ns = "");
66 
68  ~HandCommander();
69 
70  void sendCommands(std::vector<sr_robot_msgs::joint> joint_vector);
71 
80  std::string get_controller_state_topic(std::string joint_name);
81 
89  std::pair<double, double> get_min_max(std::string joint_name);
90 
97  std::vector<std::string> get_all_joints();
98 
99 private:
102 
104  std::map<std::string, urdf::JointSharedPtr> all_joints;
105 
109  boost::ptr_map<std::string, Publisher> sr_hand_target_pub_map;
110 
112  std::map<std::string, std::string> sr_hand_sub_topics;
113 
116 
121  void initializeEthercatHand();
122 
124 }; // end class ShadowhandSubscriber
125 
126 } // namespace shadowrobot
127 
128 /* For the emacs weenies in the crowd.
129 Local Variables:
130  c-basic-offset: 2
131 End:
132 */
Publisher sr_hand_target_pub
Publisher for the CAN hand targets.
boost::ptr_map< std::string, Publisher > sr_hand_target_pub_map
Publishers for the ethercat hand targets for every joint.
NodeHandle node_
ros node handle
shadowhandRosLib::HandType hand_type
static const double TIMEOUT_TO_DETECT_CONTROLLER_MANAGER
std::map< std::string, std::string > sr_hand_sub_topics
A map of topics for the controller states.
std::map< std::string, urdf::JointSharedPtr > all_joints
stores data about the hand (read from urdf)


sr_hand
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:24