Public Member Functions | Private Member Functions | Private Attributes
shadowrobot::SRSubscriber Class Reference

#include <sr_subscriber.h>

List of all members.

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< Subscribercontrollers_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).

Detailed Description

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.


Constructor & Destructor Documentation

shadowrobot::SRSubscriber::SRSubscriber ( boost::shared_ptr< SRArticulatedRobot sr_art_robot)

Constructor initializing the ROS node, and setting the topic to which it subscribes.

Parameters:
sr_art_robotA 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.


Member Function Documentation

void shadowrobot::SRSubscriber::cmd_callback ( const std_msgs::Float64ConstPtr &  msg,
std::string joint_name 
) [private]

Callback the etherCAT way: one topic per joint.

Parameters:
msgthe target in radians
joint_namename 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.

Parameters:
msgthe 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.

Parameters:
msgthe 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.

Parameters:
msgthe 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.


Member Data Documentation

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.

The vector of subscribers to the different joint topics.

Definition at line 104 of file sr_subscriber.h.

Definition at line 74 of file sr_subscriber.h.

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.

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.


The documentation for this class was generated from the following files:


sr_hand
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:24:55