#include <sr_subscriber.h>
Public Member Functions | |
| SRSubscriber (boost::shared_ptr< SRArticulatedRobot > sr_art_robot) | |
| ~SRSubscriber () | |
| Destructor. More... | |
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 More... | |
| void | sendupdateCallback (const sr_robot_msgs::sendupdateConstPtr &msg) |
Private Attributes | |
| Subscriber | config_sub |
| The subscriber to the config topic. More... | |
| Subscriber | contrlr_sub |
| The subscriber to the contrlr topic. More... | |
| std::vector< Subscriber > | controllers_sub |
| The vector of subscribers to the different joint topics. More... | |
| NodeHandle | n_tilde |
| NodeHandle | node |
| ros node handle More... | |
| Subscriber | sendupdate_sub |
| The subscriber to the sendupdate topic. More... | |
| 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). More... | |
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 60 of file sr_subscriber.h.
|
explicit |
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 47 of file sr_subscriber.cpp.
| shadowrobot::SRSubscriber::~SRSubscriber | ( | ) |
Destructor.
Definition at line 57 of file sr_subscriber.cpp.
|
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 113 of file sr_subscriber.cpp.
|
private |
process the config command: send new parameters to the palm.
| msg | the config message received |
Definition at line 142 of file sr_subscriber.cpp.
|
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 119 of file sr_subscriber.cpp.
|
private |
init function
Definition at line 61 of file sr_subscriber.cpp.
|
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 93 of file sr_subscriber.cpp.
|
private |
The subscriber to the config topic.
Definition at line 126 of file sr_subscriber.h.
|
private |
The subscriber to the contrlr topic.
Definition at line 117 of file sr_subscriber.h.
|
private |
The vector of subscribers to the different joint topics.
Definition at line 107 of file sr_subscriber.h.
|
private |
Definition at line 75 of file sr_subscriber.h.
|
private |
ros node handle
Definition at line 75 of file sr_subscriber.h.
|
private |
The subscriber to the sendupdate topic.
Definition at line 96 of file sr_subscriber.h.
|
private |
The shadowhand / shadowarm object (can be either an object connected to the real robot or a virtual hand).
Definition at line 78 of file sr_subscriber.h.