Public Member Functions | |
def | __init__ |
def | compute_grasp |
def | fit_bag_file |
def | fit_joint_state_messages |
def | fit_joint_values |
def | synergy_range |
def | trained |
Private Attributes | |
_D | |
_N | |
_pca | |
_transformed_joint_angles |
A grasp synergy (aka eigengrasp) is a lower-dimensional representation of the hand configuration useful to simplify all manners of grasping things. Essentially this is just a utilitarian wrapper around PCA.
Definition at line 17 of file grasp_synergy.py.
Definition at line 25 of file grasp_synergy.py.
def grasp_synergy.grasp_synergy.GraspSynergy.compute_grasp | ( | self, | |
alphas | |||
) |
Reconstruct a grasp given a combination of (low-dimensional) synergy coefficients to get a (full-dimensional) grasp configuration. The coefficients are a weighting vector of the various (ordered) principal grasp components. :return mean + sum_i alpha_i * coeff_i. If the synergy is not already computed this returns None.
Definition at line 117 of file grasp_synergy.py.
def grasp_synergy.grasp_synergy.GraspSynergy.fit_bag_file | ( | self, | |
bag_filepath | |||
) |
Extract *all* joint state messages from the given bag file, then compute the hand synergies. :param bag_filepath: Fully-qualified filepath of the bagfile.
Definition at line 95 of file grasp_synergy.py.
def grasp_synergy.grasp_synergy.GraspSynergy.fit_joint_state_messages | ( | self, | |
joint_state_messages | |||
) |
Extract joint state values from a list of ROS messages, then compute the grasp synergies. :param joint_state_messages A list of ROS sensor_msgs/JointState.
Definition at line 75 of file grasp_synergy.py.
def grasp_synergy.grasp_synergy.GraspSynergy.fit_joint_values | ( | self, | |
joint_values | |||
) |
Fit the principal components of the given joint values to compute the grasp synergies (aka eigengrasps). We compute and store *all* D principal components here. The dimensionality of the lower-dimensional subspace is determined at grasp computation time. :param joint_values A numpy array (N by D) with N datapoints of D dimensions. :return True if the synergies were properly fit.
Definition at line 43 of file grasp_synergy.py.
def grasp_synergy.grasp_synergy.GraspSynergy.synergy_range | ( | self, | |
component_num | |||
) |
Compute the range of values for the i'th component of the synergy, using the transformed original values used to train the PCA. If there are no synergies or the component number is invalid, returns (0, 0). :return (min, max) for transformed values
Definition at line 148 of file grasp_synergy.py.
def grasp_synergy.grasp_synergy.GraspSynergy.trained | ( | self | ) |
:return True if the synergy space has been computed.
Definition at line 37 of file grasp_synergy.py.
Definition at line 25 of file grasp_synergy.py.
Definition at line 25 of file grasp_synergy.py.
Definition at line 25 of file grasp_synergy.py.
Definition at line 25 of file grasp_synergy.py.