#include <hand_commander.hpp>
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 (const std::string &ns="") | |
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 |
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 hand_commander.hpp.
shadowrobot::HandCommander::HandCommander | ( | const std::string & | ns = "" | ) |
Definition at line 41 of file hand_commander.cpp.
Destructor.
Definition at line 81 of file hand_commander.cpp.
std::vector< std::string > shadowrobot::HandCommander::get_all_joints | ( | ) |
Get all the joint names from the robot description. Ideal for looping over all joints.
Definition at line 183 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.
joint_name | the joint for which you want the topic. |
Definition at line 200 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.
joint_name | name of the joint (upper or lower case) (e.g. FFJ3) |
Definition at line 142 of file hand_commander.cpp.
void shadowrobot::HandCommander::initializeEthercatHand | ( | ) | [private] |
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 85 of file hand_commander.cpp.
void shadowrobot::HandCommander::sendCommands | ( | std::vector< sr_robot_msgs::joint > | joint_vector | ) |
Definition at line 113 of file hand_commander.cpp.
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 102 of file hand_commander.hpp.
bool shadowrobot::HandCommander::ethercat_controllers_found [private] |
Definition at line 113 of file hand_commander.hpp.
Definition at line 112 of file hand_commander.hpp.
NodeHandle shadowrobot::HandCommander::node_ [private] |
ros node handle
Definition at line 99 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 110 of file hand_commander.hpp.
Publisher for the CAN hand targets.
Definition at line 105 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 107 of file hand_commander.hpp.
const double shadowrobot::HandCommander::TIMEOUT_TO_DETECT_CONTROLLER_MANAGER = 3.0 [static, private] |
Definition at line 121 of file hand_commander.hpp.