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

#include <hand_commander.hpp>

Public Member Functions

std::vector< std::stringget_all_joints ()
 
std::string get_controller_state_topic (std::string joint_name)
 
std::pair< double, double > get_min_max (std::string joint_name)
 
 HandCommander (const std::string &ns="")
 
void sendCommands (std::vector< sr_robot_msgs::joint > joint_vector)
 
 ~HandCommander ()
 Destructor. More...
 

Private Member Functions

void initializeEthercatHand ()
 

Private Attributes

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

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

◆ HandCommander()

shadowrobot::HandCommander::HandCommander ( const std::string ns = "")
explicit

Definition at line 47 of file hand_commander.cpp.

◆ ~HandCommander()

shadowrobot::HandCommander::~HandCommander ( )

Destructor.

Definition at line 89 of file hand_commander.cpp.

Member Function Documentation

◆ get_all_joints()

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 192 of file hand_commander.cpp.

◆ get_controller_state_topic()

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 (fully resolved) of the topic to which you need to subscribe.

Definition at line 205 of file hand_commander.cpp.

◆ get_min_max()

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 153 of file hand_commander.cpp.

◆ initializeEthercatHand()

void shadowrobot::HandCommander::initializeEthercatHand ( )
private

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

Definition at line 93 of file hand_commander.cpp.

◆ sendCommands()

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

Definition at line 123 of file hand_commander.cpp.

Member Data Documentation

◆ all_joints

std::map<std::string, urdf::JointSharedPtr> shadowrobot::HandCommander::all_joints
private

stores data about the hand (read from urdf)

Definition at line 104 of file hand_commander.hpp.

◆ ethercat_controllers_found

bool shadowrobot::HandCommander::ethercat_controllers_found
private

Definition at line 115 of file hand_commander.hpp.

◆ hand_type

shadowhandRosLib::HandType shadowrobot::HandCommander::hand_type
private

Definition at line 114 of file hand_commander.hpp.

◆ node_

NodeHandle shadowrobot::HandCommander::node_
private

ros node handle

Definition at line 101 of file hand_commander.hpp.

◆ sr_hand_sub_topics

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.

◆ sr_hand_target_pub

Publisher shadowrobot::HandCommander::sr_hand_target_pub
private

Publisher for the CAN hand targets.

Definition at line 107 of file hand_commander.hpp.

◆ sr_hand_target_pub_map

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.

◆ TIMEOUT_TO_DETECT_CONTROLLER_MANAGER

const double shadowrobot::HandCommander::TIMEOUT_TO_DETECT_CONTROLLER_MANAGER = 3.0
staticprivate

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
autogenerated on Mon Feb 28 2022 23:52:24