Public Member Functions | Private Member Functions | Private Attributes | List of all members
shadowrobot::SRSubscriber Class Reference

#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< Subscribercontrollers_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< SRArticulatedRobotsr_articulated_robot
 The shadowhand / shadowarm object (can be either an object connected to the real robot or a virtual hand). More...
 

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 60 of file sr_subscriber.h.

Constructor & Destructor Documentation

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

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 47 of file sr_subscriber.cpp.

shadowrobot::SRSubscriber::~SRSubscriber ( )

Destructor.

Definition at line 57 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 113 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 142 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 119 of file sr_subscriber.cpp.

void shadowrobot::SRSubscriber::init ( )
private

init function

Definition at line 61 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 93 of file sr_subscriber.cpp.

Member Data Documentation

Subscriber shadowrobot::SRSubscriber::config_sub
private

The subscriber to the config topic.

Definition at line 126 of file sr_subscriber.h.

Subscriber shadowrobot::SRSubscriber::contrlr_sub
private

The subscriber to the contrlr topic.

Definition at line 117 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 107 of file sr_subscriber.h.

NodeHandle shadowrobot::SRSubscriber::n_tilde
private

Definition at line 75 of file sr_subscriber.h.

NodeHandle shadowrobot::SRSubscriber::node
private

ros node handle

Definition at line 75 of file sr_subscriber.h.

Subscriber shadowrobot::SRSubscriber::sendupdate_sub
private

The subscriber to the sendupdate topic.

Definition at line 96 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 78 of file sr_subscriber.h.


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


sr_hand
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:53