28 #ifndef SR_HAND_SR_SUBSCRIBER_H 29 #define SR_HAND_SR_SUBSCRIBER_H 36 #include <boost/smart_ptr.hpp> 39 #include <sr_robot_msgs/joints_data.h> 40 #include <sr_robot_msgs/joint.h> 41 #include <sr_robot_msgs/contrlr.h> 42 #include <sr_robot_msgs/sendupdate.h> 43 #include <sr_robot_msgs/config.h> 44 #include <sr_robot_msgs/reverseKinematics.h> 45 #include <std_msgs/Float64.h> 104 void cmd_callback(
const std_msgs::Float64ConstPtr &msg, std::string &joint_name);
131 #endif // SR_HAND_SR_SUBSCRIBER_H void contrlrCallback(const sr_robot_msgs::contrlrConstPtr &msg)
boost::shared_ptr< SRArticulatedRobot > sr_articulated_robot
The shadowhand / shadowarm object (can be either an object connected to the real robot or a virtual h...
Subscriber config_sub
The subscriber to the config topic.
void configCallback(const sr_robot_msgs::configConstPtr &msg)
~SRSubscriber()
Destructor.
void sendupdateCallback(const sr_robot_msgs::sendupdateConstPtr &msg)
std::vector< Subscriber > controllers_sub
The vector of subscribers to the different joint topics.
Subscriber sendupdate_sub
The subscriber to the sendupdate topic.
void cmd_callback(const std_msgs::Float64ConstPtr &msg, std::string &joint_name)
Subscriber contrlr_sub
The subscriber to the contrlr topic.
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...
NodeHandle node
ros node handle
SRSubscriber(boost::shared_ptr< SRArticulatedRobot > sr_art_robot)
This is a parent class for the different types of Shadowhand we can have. It makes it possible to swa...