etherCAT_compatibility_hand.hpp
Go to the documentation of this file.
1 /*
2 * Copyright 2011 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 
31 #ifndef _ETHERCAT_COMPATIBILITY_HAND_HPP_
32 # define _ETHERCAT_COMPATIBILITY_HAND_HPP_
33 
35 #include <sensor_msgs/JointState.h>
36 
37 #include <string>
38 #include <vector>
39 
40 namespace shadowrobot
41 {
42 // THIS CLASS IS CONSIDERED DEPRECATED AND SHOULD NOT BE USED FOR ANY NEW PACKAGE.
43 // IT IS NOT MARKED AS DEPRECATED THOUGH, AS IT IS STILL USED IN SOME OLD NODES
50  public SRArticulatedRobot
51 {
52 public:
57 
59 
60  // virtual classes defined in Shadowhand
68  virtual int16_t sendupdate(std::string joint_name, double target);
69 
76  virtual JointData getJointData(std::string joint_name);
77 
78  virtual JointsMap getAllJointsData();
79 
80  virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data);
81 
82  virtual JointControllerData getContrl(std::string ctrlr_name);
83 
84  virtual int16_t setConfig(std::vector<std::string> myConfig);
85 
86  virtual void getConfig(std::string joint_name);
87 
94  virtual std::vector<DiagnosticData> getDiagnostics();
95 
96 protected:
98 
105  void joint_states_callback(const sensor_msgs::JointStateConstPtr &msg);
106 
110  void initializeMap();
111 
120  std::string findControllerTopicName(std::string joint_name);
121 
122  // This vector stores publishers to each joint controller.
123  std::vector<ros::Publisher> etherCAT_publishers;
124 
125  // a subscriber for the /joint_states topic.
127 }; // end class
128 } // namespace shadowrobot
129 
130 /* For the emacs weenies in the crowd.
131 Local Variables:
132  c-basic-offset: 2
133 End:
134 */
135 
136 
137 #endif // _ETHERCAT_COMPATIBILITY_HAND_HPP_
virtual JointData getJointData(std::string joint_name)
std::map< std::string, JointData > JointsMap
This compatibility interface is a wrapper around the new etherCAT Hand ROS driver. It is used to present the same interface as the CAN hand.
std::string findControllerTopicName(std::string joint_name)
virtual std::vector< DiagnosticData > getDiagnostics()
virtual JointControllerData getContrl(std::string ctrlr_name)
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...
virtual int16_t sendupdate(std::string joint_name, double target)
virtual void getConfig(std::string joint_name)
void joint_states_callback(const sensor_msgs::JointStateConstPtr &msg)
virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data)
virtual int16_t setConfig(std::vector< std::string > myConfig)
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...


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