CAN_compatibility_arm.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 
32 #ifndef _CAN_COMPATIBILITY_ARM_HPP_
33 # define _CAN_COMPATIBILITY_ARM_HPP_
34 
36 #include <sensor_msgs/JointState.h>
37 
38 #include <string>
39 #include <vector>
40 
41 namespace shadowrobot
42 {
49  public SRArticulatedRobot
50 {
51 public:
56 
57  virtual ~CANCompatibilityArm();
58 
59  // virtual classes defined in Shadowhand
67  virtual int16_t sendupdate(std::string joint_name, double target);
68 
75  virtual JointData getJointData(std::string joint_name);
76 
77  virtual JointsMap getAllJointsData();
78 
79  virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data);
80 
81  virtual JointControllerData getContrl(std::string ctrlr_name);
82 
83  virtual int16_t setConfig(std::vector <std::string> myConfig);
84 
85  virtual void getConfig(std::string joint_name);
86 
93  virtual std::vector <DiagnosticData> getDiagnostics();
94 
95 protected:
97 
104  void joint_states_callback(const sensor_msgs::JointStateConstPtr &msg);
105 
109  void initializeMap();
110 
111  // This vector stores publishers to each joint controller.
112  std::vector <ros::Publisher> CAN_publishers;
113 
114  // a subscriber for the /joint_states topic.
116 }; // end class
117 } // namespace shadowrobot
118 
119 /* For the emacs weenies in the crowd.
120 Local Variables:
121  c-basic-offset: 2
122 End:
123 */
124 
125 
126 #endif // _ETHERCAT_COMPATIBILITY_HAND_HPP_
virtual JointControllerData getContrl(std::string ctrlr_name)
std::map< std::string, JointData > JointsMap
virtual int16_t sendupdate(std::string joint_name, double target)
void joint_states_callback(const sensor_msgs::JointStateConstPtr &msg)
virtual std::vector< DiagnosticData > getDiagnostics()
virtual JointData getJointData(std::string joint_name)
virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data)
This compatibility interface is a wrapper around the new CAN Hand ROS driver. It is used to present t...
#define ROS_DEPRECATED
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...
virtual void getConfig(std::string joint_name)
std::vector< ros::Publisher > CAN_publishers
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