29 #ifndef SR_HAND_HAND_VIRTUAL_SHADOWHAND_H 30 #define SR_HAND_HAND_VIRTUAL_SHADOWHAND_H 68 virtual int16_t
sendupdate(std::string joint_name,
double target);
86 virtual int16_t
setConfig(std::vector<std::string> myConfig);
88 virtual void getConfig(std::string joint_name);
108 void gazeboCallback(
const sensor_msgs::JointStateConstPtr& msg);
128 return deg * 3.14159265 / 180.0;
138 return rad * 180.0 / 3.14159265;
143 #endif // SR_HAND_HAND_VIRTUAL_SHADOWHAND_H virtual int16_t setContrl(std::string contrlr_name, JointControllerData ctrlr_data)
virtual JointControllerData getContrl(std::string ctrlr_name)
ros::NodeHandle node
ROS Node handles.
virtual int16_t setConfig(std::vector< std::string > myConfig)
std::map< std::string, JointData > JointsMap
virtual std::vector< DiagnosticData > getDiagnostics()
virtual void getConfig(std::string joint_name)
ControllersMap controllers_map
Contains the mapping between the controller names and their data.
The Virtual Shadowhand can be used as a simulator. As both the real hand and the virtual hand are chi...
virtual ~VirtualShadowhand()
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...
virtual JointsMap getAllJointsData()
double toDegrees(double rad)
virtual int16_t sendupdate(std::string joint_name, double target)
std::map< std::string, JointControllerData > ControllersMap
virtual JointData getJointData(std::string joint_name)
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...