Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
shadowrobot::HandCommander Class Reference

#include <hand_commander.hpp>

List of all members.

Public Member Functions

std::vector< std::string > get_all_joints ()
std::string get_controller_state_topic (std::string joint_name)
std::pair< double, double > get_min_max (std::string joint_name)
 HandCommander ()
void sendCommands (std::vector< sr_robot_msgs::joint > joint_vector)
 ~HandCommander ()
 Destructor.

Private Member Functions

void initializeEthercatHand ()

Private Attributes

std::map< std::string,
boost::shared_ptr< urdf::Joint > > 
all_joints
 stores data about the hand (read from urdf)
bool ethercat_controllers_found
shadowhandRosLib::HandType hand_type
NodeHandle node_
 ros node handle
std::map< std::string,
std::string > 
sr_hand_sub_topics
 A map of topics for the controller states.
Publisher sr_hand_target_pub
 Publisher for the CAN hand targets.
boost::ptr_map< std::string,
Publisher
sr_hand_target_pub_map
 Publishers for the ethercat hand targets for every joint.

Static Private Attributes

static const double TIMEOUT_TO_DETECT_CONTROLLER_MANAGER = 3.0

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 62 of file hand_commander.hpp.


Constructor & Destructor Documentation

Definition at line 41 of file hand_commander.cpp.

Destructor.

Definition at line 79 of file hand_commander.cpp.


Member Function Documentation

std::vector< std::string > shadowrobot::HandCommander::get_all_joints ( )

Get all the joint names from the robot description. Ideal for looping over all joints.

Returns:
A vector of joint names.

Definition at line 181 of file hand_commander.cpp.

std::string shadowrobot::HandCommander::get_controller_state_topic ( std::string  joint_name)

Returns the topic name for the controller state of a given joint. Useful for easily subscribing to the corresponding state topic in another node.

Parameters:
joint_namethe joint for which you want the topic
Returns:
the full name of the topic to which you need to subscribe

Definition at line 198 of file hand_commander.cpp.

std::pair< double, double > shadowrobot::HandCommander::get_min_max ( std::string  joint_name)

Reads the min and max for a given joint from the urdf description.

Parameters:
joint_namename of the joint (upper or lower case) (e.g. FFJ3)
Returns:
a pair containing first the min then the max for the given joint.

Definition at line 140 of file hand_commander.cpp.

init function for the ethercat hand It can be called if we know that there's an ethercat hand (pr2_controller_manager running)

Definition at line 83 of file hand_commander.cpp.

void shadowrobot::HandCommander::sendCommands ( std::vector< sr_robot_msgs::joint joint_vector)

Definition at line 111 of file hand_commander.cpp.


Member Data Documentation

std::map<std::string, boost::shared_ptr<urdf::Joint> > shadowrobot::HandCommander::all_joints [private]

stores data about the hand (read from urdf)

Definition at line 104 of file hand_commander.hpp.

Definition at line 115 of file hand_commander.hpp.

Definition at line 114 of file hand_commander.hpp.

ros node handle

Definition at line 101 of file hand_commander.hpp.

std::map<std::string, std::string> shadowrobot::HandCommander::sr_hand_sub_topics [private]

A map of topics for the controller states.

Definition at line 112 of file hand_commander.hpp.

Publisher for the CAN hand targets.

Definition at line 107 of file hand_commander.hpp.

boost::ptr_map<std::string,Publisher> shadowrobot::HandCommander::sr_hand_target_pub_map [private]

Publishers for the ethercat hand targets for every joint.

Definition at line 109 of file hand_commander.hpp.

Definition at line 123 of file hand_commander.hpp.


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


sr_hand
Author(s): Ugo Cupcic / ugo@shadowrobot.com, contact@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:44:03