Utility functions for managing each finger of Shadow Hand. Contains struct to hold necessary data about each finger, and each instance can be passed around to planning utilities. Also contains some functionality for operating on BioTac sensor attached to the respective finger.
More...
|
struct | Finger |
| Utility struct for managing each finger of Shadow Hand. Contains all the information about the Finger instance, including joint limits, MoveGroup, MoveIt plan, and joint control publishers. More...
|
|
|
std::string | getSavedStateName (std::string finger_name, std::string saved_state) |
| Get preloaded plan as string for open or close. More...
|
|
std::string | getMoveGroupName (std::string finger_name) |
| Get planning group names given common name for finger. More...
|
|
std::vector< std::string > | getJointNames (moveit::planning_interface::MoveGroupInterface &move_group_interface) |
| Get names of joints from given MoveGroupInterface. More...
|
|
std::vector< std::string > | getJointNames (moveit::planning_interface::MoveGroupInterface::Plan &plan) |
|
std::vector< double > | getJointValues (moveit::planning_interface::MoveGroupInterface &move_group_interface) |
| Get current values of joints from given MoveGroupInterface, they are in the same order as the names of joints obtained from getJointNames() More...
|
|
std::vector< std::tuple< float, float > > | getFingerJointLimits (std::vector< std::string > &joint_names) |
| Get limits of each joint in given vector of joint names. This is obtained from the /robot_description URDF passed to ROS from the robot. More...
|
|
int | getBiotacIdx (std::string &finger_name) |
| Fetch BioTac index given name of finger. More...
|
|
std::vector< std::string > | getJointNames (shadow_finger::Finger &finger) |
|
std::vector< double > | getJointValues (shadow_finger::Finger &finger) |
|
|
static const std::vector< std::string > | biotac_idx |
| Lookup table that maps finger name to BioTac index. More...
|
|
Utility functions for managing each finger of Shadow Hand. Contains struct to hold necessary data about each finger, and each instance can be passed around to planning utilities. Also contains some functionality for operating on BioTac sensor attached to the respective finger.
shadow_finger.hpp "include/shadowlibs/shadow_finger.hpp"
int shadow_finger::getBiotacIdx |
( |
std::string & |
finger_name | ) |
|
|
inline |
Fetch BioTac index given name of finger.
- Parameters
-
finger_name | String with name of finger |
- Returns
- Integer index of BioTac, to be used for fetching correct data from ROS
std::vector<std::tuple<float, float> > shadow_finger::getFingerJointLimits |
( |
std::vector< std::string > & |
joint_names | ) |
|
|
inline |
Get limits of each joint in given vector of joint names. This is obtained from the /robot_description URDF passed to ROS from the robot.
- Parameters
-
joint_names | The vector of strings containing the names of the joints |
- Returns
- Vector of tuples, each with (upper,lower) limits of each joint, in the same order as the input vector
std::vector<std::string> shadow_finger::getJointNames |
( |
moveit::planning_interface::MoveGroupInterface & |
move_group_interface | ) |
|
|
inline |
Get names of joints from given MoveGroupInterface.
- Parameters
-
move_group_interface | The MoveGroupInterface for the finger |
- Returns
- The vector of strings containing the joints in that MoveGroup
std::vector<std::string> shadow_finger::getJointNames |
( |
moveit::planning_interface::MoveGroupInterface::Plan & |
plan | ) |
|
|
inline |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
std::vector<double> shadow_finger::getJointValues |
( |
moveit::planning_interface::MoveGroupInterface & |
move_group_interface | ) |
|
|
inline |
Get current values of joints from given MoveGroupInterface, they are in the same order as the names of joints obtained from getJointNames()
- Parameters
-
move_group_interface | The MoveGroupInterface for the finger |
- Returns
- The vector of doubles containing the values of joints in that MoveGroup
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
std::string shadow_finger::getMoveGroupName |
( |
std::string |
finger_name | ) |
|
|
inline |
Get planning group names given common name for finger.
- Parameters
-
finger_name | The name of the finger to operate on |
- Returns
- Formatted string with the MoveGroup name
std::string shadow_finger::getSavedStateName |
( |
std::string |
finger_name, |
|
|
std::string |
saved_state |
|
) |
| |
|
inline |
Get preloaded plan as string for open or close.
- Parameters
-
finger_name | Name of the finger, or thumb |
saved_state | Either "open" or "close" |
- Returns
- Formatted string that is accepted by MoveIt planner
shadow_finger::biotac_idx |
|
static |
Initial value:= {"first", "middle", "ring",
"little", "thumb"}
Lookup table that maps finger name to BioTac index.