#include <sr_subscriber.h>
Public Member Functions | |
SRSubscriber (boost::shared_ptr< SRArticulatedRobot > sr_art_robot) | |
~SRSubscriber () | |
Destructor. | |
Private Member Functions | |
void | cmd_callback (const std_msgs::Float64ConstPtr &msg, std::string &joint_name) |
void | configCallback (const sr_robot_msgs::configConstPtr &msg) |
void | contrlrCallback (const sr_robot_msgs::contrlrConstPtr &msg) |
void | init () |
init function | |
void | sendupdateCallback (const sr_robot_msgs::sendupdateConstPtr &msg) |
Private Attributes | |
Subscriber | config_sub |
The subscriber to the config topic. | |
Subscriber | contrlr_sub |
The subscriber to the contrlr topic. | |
std::vector< Subscriber > | controllers_sub |
The vector of subscribers to the different joint topics. | |
NodeHandle | n_tilde |
NodeHandle | node |
ros node handle | |
Subscriber | sendupdate_sub |
The subscriber to the sendupdate topic. | |
boost::shared_ptr < SRArticulatedRobot > | sr_articulated_robot |
The shadowhand / shadowarm object (can be either an object connected to the real robot or a virtual hand). |
This ROS subscriber is used to issue commands to the hand / arm, from sending a set of targets, to changing the controller parameters.
Definition at line 59 of file sr_subscriber.h.
shadowrobot::SRSubscriber::SRSubscriber | ( | boost::shared_ptr< SRArticulatedRobot > | sr_art_robot | ) |
Constructor initializing the ROS node, and setting the topic to which it subscribes.
sr_art_robot | A Shadowhand object, where the information to be published comes from. |
Definition at line 45 of file sr_subscriber.cpp.
Destructor.
Definition at line 55 of file sr_subscriber.cpp.
void shadowrobot::SRSubscriber::cmd_callback | ( | const std_msgs::Float64ConstPtr & | msg, |
std::string & | joint_name | ||
) | [private] |
Callback the etherCAT way: one topic per joint.
msg | the target in radians |
joint_name | name of the joint we're sending the command to |
Definition at line 110 of file sr_subscriber.cpp.
void shadowrobot::SRSubscriber::configCallback | ( | const sr_robot_msgs::configConstPtr & | msg | ) | [private] |
process the config command: send new parameters to the palm.
msg | the config message received |
Definition at line 140 of file sr_subscriber.cpp.
void shadowrobot::SRSubscriber::contrlrCallback | ( | const sr_robot_msgs::contrlrConstPtr & | msg | ) | [private] |
process the contrlr command: send new parameters to a given controller.
msg | the contrlr message received. contrlr_name + list_of_parameters in a string array e.g. [p:10] sets the p value of the specified controller to 10. |
Definition at line 116 of file sr_subscriber.cpp.
void shadowrobot::SRSubscriber::init | ( | void | ) | [private] |
init function
Definition at line 59 of file sr_subscriber.cpp.
void shadowrobot::SRSubscriber::sendupdateCallback | ( | const sr_robot_msgs::sendupdateConstPtr & | msg | ) | [private] |
process the sendupdate command: send new targets to the Dextrous Hand (or the Shadow Robot Arm), through the shadowhand object.
msg | the sendupdate message received. The sendupdate message, contains the number of sendupdate commands and a vector of joints with names and targets. |
Definition at line 89 of file sr_subscriber.cpp.
The subscriber to the config topic.
Definition at line 121 of file sr_subscriber.h.
The subscriber to the contrlr topic.
Definition at line 113 of file sr_subscriber.h.
std::vector<Subscriber> shadowrobot::SRSubscriber::controllers_sub [private] |
The vector of subscribers to the different joint topics.
Definition at line 104 of file sr_subscriber.h.
NodeHandle shadowrobot::SRSubscriber::n_tilde [private] |
Definition at line 74 of file sr_subscriber.h.
NodeHandle shadowrobot::SRSubscriber::node [private] |
ros node handle
Definition at line 74 of file sr_subscriber.h.
The subscriber to the sendupdate topic.
Definition at line 94 of file sr_subscriber.h.
boost::shared_ptr<SRArticulatedRobot> shadowrobot::SRSubscriber::sr_articulated_robot [private] |
The shadowhand / shadowarm object (can be either an object connected to the real robot or a virtual hand).
Definition at line 77 of file sr_subscriber.h.