#include <sr_hand_finder.hpp>
Public Member Functions | |
std::map< std::string, std::string > | get_calibration_path () |
HandControllerTuning | get_hand_controller_tuning () |
std::map< std::string, std::vector< std::string > > | get_joints () |
SrHandFinder () | |
virtual | ~SrHandFinder () |
Private Member Functions | |
void | generate_calibration_path () |
void | generate_hand_controller_tuning_path () |
void | generate_joints_with_prefix () |
Private Attributes | |
std::map< std::string, std::string > | calibration_path_ |
HandConfig | hand_config_ |
HandControllerTuning | hand_controller_tuning_ |
std::map< std::string, std::vector< std::string > > | joints_ |
ros::NodeHandle | node_handle_ |
Static Private Attributes | |
static const char * | joint_names_ [] |
static const size_t | number_of_joints_ = 20 |
Definition at line 43 of file sr_hand_finder.hpp.
Definition at line 39 of file sr_hand_finder.cpp.
virtual shadow_robot::SrHandFinder::~SrHandFinder | ( | ) | [inline, virtual] |
Definition at line 65 of file sr_hand_finder.hpp.
void shadow_robot::SrHandFinder::generate_calibration_path | ( | ) | [private] |
Definition at line 66 of file sr_hand_finder.cpp.
void shadow_robot::SrHandFinder::generate_hand_controller_tuning_path | ( | ) | [private] |
Definition at line 76 of file sr_hand_finder.cpp.
void shadow_robot::SrHandFinder::generate_joints_with_prefix | ( | ) | [private] |
Definition at line 54 of file sr_hand_finder.cpp.
Definition at line 112 of file sr_hand_finder.cpp.
Definition at line 116 of file sr_hand_finder.cpp.
map< string, vector< string > > shadow_robot::SrHandFinder::get_joints | ( | ) |
Definition at line 108 of file sr_hand_finder.cpp.
std::map<std::string, std::string> shadow_robot::SrHandFinder::calibration_path_ [private] |
Definition at line 56 of file sr_hand_finder.hpp.
Definition at line 53 of file sr_hand_finder.hpp.
Definition at line 54 of file sr_hand_finder.hpp.
const char * shadow_robot::SrHandFinder::joint_names_ [static, private] |
{"FFJ1", "FFJ2", "FFJ3", "FFJ4", "MFJ1", "MFJ2", "MFJ3", "MFJ4", "RFJ1", "RFJ2", "RFJ3", "RFJ4", "LFJ1", "LFJ2", "LFJ3", "LFJ4", "LFJ5", "THJ1", "THJ2", "THJ3", "THJ4", "THJ5", "WRJ1", "WRJ2"}
Definition at line 51 of file sr_hand_finder.hpp.
std::map<std::string, std::vector<std::string> > shadow_robot::SrHandFinder::joints_ [private] |
Definition at line 55 of file sr_hand_finder.hpp.
Definition at line 52 of file sr_hand_finder.hpp.
const size_t shadow_robot::SrHandFinder::number_of_joints_ = 20 [static, private] |
Definition at line 50 of file sr_hand_finder.hpp.