graspnetAPI.utils.dexnet.grasping package¶
Subpackages¶
- graspnetAPI.utils.dexnet.grasping.meshpy package
- Submodules
- graspnetAPI.utils.dexnet.grasping.meshpy.mesh module
- graspnetAPI.utils.dexnet.grasping.meshpy.obj_file module
- graspnetAPI.utils.dexnet.grasping.meshpy.sdf module
- graspnetAPI.utils.dexnet.grasping.meshpy.sdf_file module
- graspnetAPI.utils.dexnet.grasping.meshpy.stable_pose module
- Module contents
Submodules¶
graspnetAPI.utils.dexnet.grasping.contacts module¶
Copyright ©2017. The Regents of the University of California (Regents). All Rights Reserved. Permission to use, copy, modify, and distribute this software and its documentation for educational, research, and not-for-profit purposes, without fee and without a signed licensing agreement, is hereby granted, provided that the above copyright notice, this paragraph and the following two paragraphs appear in all copies, modifications, and distributions. Contact The Office of Technology Licensing, UC Berkeley, 2150 Shattuck Avenue, Suite 510, Berkeley, CA 94720-1620, (510) 643- 7201, otl@berkeley.edu, http://ipira.berkeley.edu/industry-info for commercial licensing opportunities.
IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED HEREUNDER IS PROVIDED “AS IS”. REGENTS HAS NO OBLIGATION TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
-
class
graspnetAPI.utils.dexnet.grasping.contacts.
Contact
[source]¶ Bases:
object
Abstract class for contact models.
-
class
graspnetAPI.utils.dexnet.grasping.contacts.
Contact3D
(graspable, contact_point, in_direction=None)[source]¶ Bases:
graspnetAPI.utils.dexnet.grasping.contacts.Contact
3D contact points.
- graspable
GraspableObject3D
object to use to get contact information
- contact_point3x1
numpy.ndarray
point of contact on the object
- in_direction3x1
numpy.ndarray
direction along which contact was made
- normalnormalized 3x1
numpy.ndarray
surface normal at the contact point
-
friction_cone
(num_cone_faces=8, friction_coef=0.5)[source]¶ Computes the friction cone and normal for a contact point.
- num_cone_facesint
number of cone faces to use in discretization
- friction_coeffloat
coefficient of friction at contact point
- successbool
False when cone can’t be computed
- cone_support
numpy.ndarray
array where each column is a vector on the boundary of the cone
- normalnormalized 3x1
numpy.ndarray
outward facing surface normal
-
property
graspable
¶
-
property
in_direction
¶
-
property
normal
¶
-
normal_force_magnitude
()[source]¶ Returns the component of the force that the contact would apply along the normal direction.
- float
magnitude of force along object surface normal
-
property
point
¶
-
reference_frame
(align_axes=True)[source]¶ Returns the local reference frame of the contact. Z axis in the in direction (or surface normal if not specified) X and Y axes in the tangent plane to the direction
- align_axesbool
whether or not to align to the object axes
RigidTransform
rigid transformation from contact frame to object frame
-
surface_information
(width, num_steps, sigma_range=0.1, sigma_spatial=1, back_up=0.0, max_projection=0.1, direction=None, debug_objs=None, samples_per_grid=2)[source]¶ Returns the local surface window, gradient, and curvature for a single contact.
- widthfloat
width of surface window in object frame
- num_stepsint
number of steps to use along the in direction
- sigma_rangefloat
bandwidth of bilateral range filter on window
- sigma_spatialfloat
bandwidth of gaussian spatial filter of bilateral filter
- back_upfloat
amount to back up before finding a contact in meters
- max_projectionfloat
maximum amount to search forward for a contact (meters)
- direction3x1
numpy.ndarray
direction along width to render the window
- debug_objs
list
list to put debugging info into
- samples_per_gridfloat
number of samples per grid when finding contacts
- surface_window
SurfaceWindow
window information for local surface patch of contact on the given object
-
surface_window_projection
(width=0.01, num_steps=21, max_projection=0.1, back_up=0.0, samples_per_grid=2.0, sigma_range=0.1, sigma_spatial=1, direction=None, compute_pca=False, vis=False, debug_objs=None)[source]¶ Projects the local surface onto the tangent plane at a contact point.
- widthfloat
width of the window in obj frame
- num_stepsint
number of steps to use along the in direction
- max_projectionfloat
maximum amount to search forward for a contact (meters)
- back_upfloat
amount to back up before finding a contact in meters
- samples_per_gridfloat
number of samples per grid when finding contacts
- sigma_rangefloat
bandwidth of bilateral range filter on window
- sigma_spatialfloat
bandwidth of gaussian spatial filter of bilateral filter
- direction3x1
numpy.ndarray
dir to do the projection along
- windowNUM_STEPSxNUM_STEPS
numpy.ndarray
array of distances from tangent plane to obj, False if surface window can’t be computed
-
surface_window_projection_unaligned
(width=0.01, num_steps=21, max_projection=0.1, back_up=0.0, samples_per_grid=2.0, sigma=1.5, direction=None, vis=False)[source]¶ Projects the local surface onto the tangent plane at a contact point. Deprecated.
-
surface_window_sdf
(width=0.01, num_steps=21)[source]¶ Returns a window of SDF values on the tangent plane at a contact point. Used for patch computation.
- widthfloat
width of the window in obj frame
- num_stepsint
number of steps to use along the contact in direction
- windowNUM_STEPSxNUM_STEPS
numpy.ndarray
array of distances from tangent plane to obj along in direction, False if surface window can’t be computed
-
tangents
(direction=None, align_axes=True, max_samples=1000)[source]¶ Returns the direction vector and tangent vectors at a contact point. The direction vector defaults to the inward-facing normal vector at this contact. The direction and tangent vectors for a right handed coordinate frame.
- direction3x1
numpy.ndarray
direction to find orthogonal plane for
- align_axesbool
whether or not to align the tangent plane to the object reference frame
- max_samplesint
number of samples to use in discrete optimization for alignment of reference frame
- directionnormalized 3x1
numpy.ndarray
direction to find orthogonal plane for
- t1normalized 3x1
numpy.ndarray
first tangent vector, x axis
- t2normalized 3x1
numpy.ndarray
second tangent vector, y axis
- direction3x1
-
torques
(forces)[source]¶ Get the torques that can be applied by a set of force vectors at the contact point.
- forces3xN
numpy.ndarray
the forces applied at the contact
- successbool
whether or not computation was successful
- torques3xN
numpy.ndarray
the torques that can be applied by given forces at the contact
- forces3xN
- graspable
-
class
graspnetAPI.utils.dexnet.grasping.contacts.
SurfaceWindow
(proj_win, grad, hess_x, hess_y, gauss_curvature)[source]¶ Bases:
object
Struct for encapsulating local surface window features.
- proj_winNxN
numpy.ndarray
the window of distances to a surface (depth image created by orthographic projection)
- gradNxN
numpy.ndarray
X and Y gradients of the projection window
- hess_xNxN
numpy.ndarray
hessian, partial derivatives of the X gradient window
- hess_yNxN
numpy.ndarray
hessian, partial derivatives of the Y gradient window
- gauss_curvatureNxN
numpy.ndarray
gauss curvature at each point (function of hessian determinant)
-
property
curvature
¶
-
property
grad_x
¶
-
property
grad_x_2d
¶
-
property
grad_y
¶
-
property
grad_y_2d
¶
-
property
proj_win
¶
-
property
proj_win_2d
¶
- proj_winNxN
graspnetAPI.utils.dexnet.grasping.grasp module¶
-
class
graspnetAPI.utils.dexnet.grasping.grasp.
Grasp
[source]¶ Bases:
object
Abstract grasp class.
- configuration
numpy.ndarray
vector specifying the parameters of the grasp (e.g. hand pose, opening width, joint angles, etc)
- frame
str
string name of grasp reference frame (defaults to obj)
-
abstract
close_fingers
(obj)[source]¶ Finds the contact points by closing on the given object.
- obj
GraspableObject3D
object to find contacts on
- obj
-
abstract static
configuration_from_params
(*params)[source]¶ Convert param list to a configuration vector for the class
-
abstract static
params_from_configuration
(configuration)[source]¶ Convert configuration vector to a set of params for the class
-
samples_per_grid
= 2¶
- configuration
-
class
graspnetAPI.utils.dexnet.grasping.grasp.
ParallelJawPtGrasp3D
(configuration, max_grasp_depth=0, frame='object', grasp_id=None)[source]¶ Bases:
graspnetAPI.utils.dexnet.grasping.grasp.PointGrasp
Parallel Jaw point grasps in 3D space.
-
property
T_grasp_obj
¶ Rigid transformation from grasp frame to object frame. Rotation matrix is X-axis along approach direction, Y axis pointing between the jaws, and Z-axis orthogonal. Translation vector is the grasp center.
RigidTransform
transformation from grasp to object coordinates
-
property
approach_angle
¶ float : approach angle of the grasp
-
property
axis
¶ numpy.ndarray
: normalized 3-vector specifying the line between the jaws
-
property
center
¶ numpy.ndarray
: 3-vector specifying the center of the jaws
-
close_fingers
(obj, vis=False, check_approach=True, approach_dist=1.0)[source]¶ Steps along grasp axis to find the locations of contact with an object
- obj
GraspableObject3D
object to close fingers on
- visbool
whether or not to plot the line of action and contact points
- check_approachbool
whether or not to check if the contact points can be reached
- approach_distfloat
how far back to check the approach distance, only if checking the approach is set
- successbool
whether or not contacts were found
- c1
Contact3D
the contact point for jaw 1
- c2
Contact3D
the contact point for jaw 2
- obj
-
close_fingers_with_contacts
(obj, contacts, vis=False, check_approach=True, approach_dist=0.5)[source]¶ Steps along grasp axis to find the locations of contact with an object
- obj
GraspableObject3D
object to close fingers on
- visbool
whether or not to plot the line of action and contact points
- check_approachbool
whether or not to check if the contact points can be reached
- approach_distfloat
how far back to check the approach distance, only if checking the approach is set
- successbool
whether or not contacts were found
- c1
Contact3D
the contact point for jaw 1
- c2
Contact3D
the contact point for jaw 2
- obj
-
property
close_width
¶ float : minimum opening width of the jaws
-
property
configuration
¶ numpy.ndarray
: vector specifying the parameters of the grasp as follows (grasp_center, grasp_axis, grasp_angle, grasp_width, jaw_width)
-
static
configuration_from_params
(center, axis, width, angle=0, jaw_width=0, min_width=0)[source]¶ Converts grasp parameters to a configuration vector.
-
static
create_line_of_action
(g, axis, width, obj, num_samples, min_width=0, convert_grid=True)[source]¶ Creates a straight line of action, or list of grid points, from a given point and direction in world or grid coords
- g3x1
numpy.ndarray
start point to create the line of action
- axisnormalized 3x1
numpy.ndarray
normalized numpy 3 array of grasp direction
- widthfloat
the grasp width
- num_samplesint
number of discrete points along the line of action
- convert_gridbool
whether or not the points are specified in world coords
- line_of_action
list
of 3x1numpy.ndarrays
coordinates to pass through in 3D space for contact checking
- g3x1
-
static
distance
(g1, g2, alpha=0.05)[source]¶ Evaluates the distance between two grasps.
- g1
ParallelJawPtGrasp3D
the first grasp to use
- g2
ParallelJawPtGrasp3D
the second grasp to use
- alphafloat
parameter weighting rotational versus spatial distance
- float
distance between grasps g1 and g2
- g1
-
property
endpoints
¶ numpy.ndarray
location of jaws in 3D space at max opening width
-
static
find_contact
(line_of_action, obj, vis=False, strict=False)[source]¶ Find the point at which a point traveling along a given line of action hits a surface.
- line_of_action
list
of 3x1numpy.ndarray
the points visited as the fingers close (grid coords)
- obj
GraspableObject3D
to check contacts on
- visbool
whether or not to display the contact check (for debugging)
- contact_foundbool
whether or not the point contacts the object surface
- contact
Contact3D
found along line of action (None if contact not found)
- line_of_action
-
property
frame
¶ str
: name of grasp reference frame
-
grasp_angles_from_stp_z
(stable_pose)[source]¶ Get angles of the the grasp from the table plane: 1) the angle between the grasp axis and table normal 2) the angle between the grasp approach axis and the table normal
- stable_pose
StablePose
orRigidTransform
the stable pose to compute the angles for
- psifloat
grasp y axis rotation from z axis in stable pose
- phifloat
grasp x axis rotation from z axis in stable pose
- stable_pose
-
static
grasp_from_contact_and_axis_on_grid
(obj, grasp_c1_world, grasp_axis_world, grasp_width_world, grasp_angle=0, jaw_width_world=0, min_grasp_width_world=0, vis=False, backup=0.5)[source]¶ Creates a grasp from a single contact point in grid coordinates and direction in grid coordinates.
- obj
GraspableObject3D
object to create grasp for
- grasp_c1_grid3x1
numpy.ndarray
contact point 1 in world
- grasp_axisnormalized 3x1
numpy.ndarray
normalized direction of the grasp in world
- grasp_width_worldfloat
grasp_width in world coords
- jaw_width_worldfloat
width of jaws in world coords
- min_grasp_width_worldfloat
min closing width of jaws
- visbool
whether or not to visualize the grasp
- g
ParallelJawGrasp3D
grasp created by finding the second contact
- c1
Contact3D
first contact point on the object
- c2
Contact3D
second contact point on the object
- obj
-
static
grasp_from_endpoints
(g1, g2, width=None, approach_angle=0, close_width=0)[source]¶ Create a grasp from given endpoints in 3D space, making the axis the line between the points.
- g1
numpy.ndarray
location of the first jaw
- g2
numpy.ndarray
location of the second jaw
- widthfloat
maximum opening width of jaws
- approach_anglefloat
approach angle of grasp
- close_widthfloat
width of gripper when fully closed
- g1
-
grasp_y_axis_offset
(theta)[source]¶ Return a new grasp with the given approach angle.
- thetafloat
approach angle for the new grasp
ParallelJawPtGrasp3D
grasp with the given approach angle
-
gripper_pose
(gripper=None)[source]¶ Returns the RigidTransformation from the gripper frame to the object frame when the gripper is executing the given grasp. Differs from the grasp reference frame because different robots use different conventions for the gripper reference frame.
- gripper
RobotGripper
gripper to get the pose for
RigidTransform
transformation from gripper frame to object frame
- gripper
-
property
id
¶ int : id of grasp
-
property
jaw_width
¶ float : width of the jaws in the tangent plane to the grasp axis
-
property
open_width
¶ float : maximum opening width of the jaws
-
parallel_table
(stable_pose)[source]¶ Returns a grasp with approach_angle set to be perpendicular to the table normal specified in the given stable pose.
- stable_pose
StablePose
the pose specifying the table
ParallelJawPtGrasp3D
aligned grasp
- stable_pose
-
static
params_from_configuration
(configuration)[source]¶ Converts configuration vector into grasp parameters.
- grasp_center
numpy.ndarray
center of grasp in 3D space
- grasp_axis
numpy.ndarray
normalized axis of grasp in 3D space
- max_widthfloat
maximum opening width of jaws
- anglefloat
approach angle
- jaw_widthfloat
width of jaws
- min_widthfloat
minimum closing width of jaws
- grasp_center
-
perpendicular_table
(stable_pose)[source]¶ Returns a grasp with approach_angle set to be aligned width the table normal specified in the given stable pose.
- stable_pose
StablePose
orRigidTransform
the pose specifying the orientation of the table
ParallelJawPtGrasp3D
aligned grasp
- stable_pose
-
project_camera
(T_obj_camera, camera_intr)[source]¶ Project a grasp for a given gripper into the camera specified by a set of intrinsics.
- T_obj_camera
autolab_core.RigidTransform
rigid transformation from the object frame to the camera frame
- camera_intr
perception.CameraIntrinsics
intrinsics of the camera to use
- T_obj_camera
-
property
rotated_full_axis
¶ Rotation matrix from canonical grasp reference frame to object reference frame. X axis points out of the gripper palm along the grasp approach angle, Y axis points between the jaws, and the Z axs is orthogonal.
numpy.ndarray
rotation matrix of grasp
-
surface_information
(graspable, width=0.02, num_steps=21, direction=None)[source]¶ Return the patch surface information at the contacts that this grasp makes on a graspable.
- graspable
GraspableObject3D
object to get surface information for
- widthfloat
width of the window in obj frame
- num_stepsint
number of steps
list
ofSurfaceWindow
surface patches, one for each contact
- graspable
-
property
unrotated_full_axis
¶ Rotation matrix from canonical grasp reference frame to object reference frame. X axis points out of the gripper palm along the 0-degree approach direction, Y axis points between the jaws, and the Z axs is orthogonal.
numpy.ndarray
rotation matrix of grasp
-
property
-
class
graspnetAPI.utils.dexnet.grasping.grasp.
PointGrasp
[source]¶ Bases:
graspnetAPI.utils.dexnet.grasping.grasp.Grasp
Abstract grasp class for grasps with a point contact model.
- configuration
numpy.ndarray
vector specifying the parameters of the grasp (e.g. hand pose, opening width, joint angles, etc)
- frame
str
string name of grasp reference frame (defaults to obj)
- configuration
-
class
graspnetAPI.utils.dexnet.grasping.grasp.
VacuumPoint
(configuration, frame='object', grasp_id=None)[source]¶ Bases:
graspnetAPI.utils.dexnet.grasping.grasp.Grasp
Defines a vacuum target point and axis in 3D space (5 DOF)
-
property
axis
¶
-
property
center
¶
-
property
configuration
¶ Returns the numpy array representing the hand configuration
-
static
configuration_from_params
(center, axis)[source]¶ Converts grasp parameters to a configuration vector.
-
property
frame
¶ Returns the string name of the grasp reference frame
-
property
graspnetAPI.utils.dexnet.grasping.grasp_quality_config module¶
Copyright ©2017. The Regents of the University of California (Regents). All Rights Reserved. Permission to use, copy, modify, and distribute this software and its documentation for educational, research, and not-for-profit purposes, without fee and without a signed licensing agreement, is hereby granted, provided that the above copyright notice, this paragraph and the following two paragraphs appear in all copies, modifications, and distributions. Contact The Office of Technology Licensing, UC Berkeley, 2150 Shattuck Avenue, Suite 510, Berkeley, CA 94720-1620, (510) 643- 7201, otl@berkeley.edu, http://ipira.berkeley.edu/industry-info for commercial licensing opportunities.
IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED HEREUNDER IS PROVIDED “AS IS”. REGENTS HAS NO OBLIGATION TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
-
class
graspnetAPI.utils.dexnet.grasping.grasp_quality_config.
GraspQualityConfig
(config)[source]¶ Bases:
object
Base wrapper class for parameters used in grasp quality computation. Used to elegantly enforce existence and type of required parameters.
- config
dict
dictionary mapping parameter names to parameter values
- config
-
class
graspnetAPI.utils.dexnet.grasping.grasp_quality_config.
GraspQualityConfigFactory
[source]¶ Bases:
object
Helper class to automatically create grasp quality configurations of different types.
-
class
graspnetAPI.utils.dexnet.grasping.grasp_quality_config.
QuasiStaticGraspQualityConfig
(config)[source]¶ Bases:
graspnetAPI.utils.dexnet.grasping.grasp_quality_config.GraspQualityConfig
Parameters for quasi-static grasp quality computation.
- config
dict
dictionary mapping parameter names to parameter values
Required configuration key-value pairs in Other Parameters.
- quality_method
str
string name of quasi-static quality metric
- friction_coeffloat
coefficient of friction at contact point
- num_cone_facesint
number of faces to use in friction cone approximation
- soft_fingersbool
whether to use a soft finger model
- quality_type
str
string name of grasp quality type (e.g. quasi-static, robust quasi-static)
- check_approachbool
whether or not to check the approach direction
-
REQUIRED_KEYS
= ['quality_method', 'friction_coef', 'num_cone_faces', 'soft_fingers', 'quality_type', 'check_approach', 'all_contacts_required']¶
- config
-
class
graspnetAPI.utils.dexnet.grasping.grasp_quality_config.
RobustQuasiStaticGraspQualityConfig
(config)[source]¶ Bases:
graspnetAPI.utils.dexnet.grasping.grasp_quality_config.GraspQualityConfig
Parameters for quasi-static grasp quality computation.
- config
dict
dictionary mapping parameter names to parameter values
Required configuration key-value pairs in Other Parameters.
- quality_method
str
string name of quasi-static quality metric
- friction_coeffloat
coefficient of friction at contact point
- num_cone_facesint
number of faces to use in friction cone approximation
- soft_fingersbool
whether to use a soft finger model
- quality_type
str
string name of grasp quality type (e.g. quasi-static, robust quasi-static)
- check_approachbool
whether or not to check the approach direction
- num_quality_samplesint
number of samples to use
-
ROBUST_REQUIRED_KEYS
= ['num_quality_samples']¶
- config
graspnetAPI.utils.dexnet.grasping.grasp_quality_function module¶
graspnetAPI.utils.dexnet.grasping.graspable_object module¶
Copyright ©2017. The Regents of the University of California (Regents). All Rights Reserved. Permission to use, copy, modify, and distribute this software and its documentation for educational, research, and not-for-profit purposes, without fee and without a signed licensing agreement, is hereby granted, provided that the above copyright notice, this paragraph and the following two paragraphs appear in all copies, modifications, and distributions. Contact The Office of Technology Licensing, UC Berkeley, 2150 Shattuck Avenue, Suite 510, Berkeley, CA 94720-1620, (510) 643- 7201, otl@berkeley.edu, http://ipira.berkeley.edu/industry-info for commercial licensing opportunities.
IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED HEREUNDER IS PROVIDED “AS IS”. REGENTS HAS NO OBLIGATION TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
-
class
graspnetAPI.utils.dexnet.grasping.graspable_object.
GraspableObject
(sdf, mesh, key='', model_name='', mass=1.0, convex_pieces=None)[source]¶ Bases:
object
Encapsulates geometric structures for computing contact in grasping.
- sdf
Sdf3D
signed distance field, for quickly computing contact points
- mesh
Mesh3D
3D triangular mesh to specify object geometry, should match SDF
- key
str
object identifier, usually given from the database
- model_name
str
name of the object mesh as a .obj file, for use in collision checking
- massfloat
mass of the object
- convex_pieces
list
ofMesh3D
convex decomposition of the object geom for collision checking
-
property
convex_pieces
¶
-
property
key
¶
-
property
mass
¶
-
property
mesh
¶
-
property
model_name
¶
-
property
sdf
¶
- sdf
-
class
graspnetAPI.utils.dexnet.grasping.graspable_object.
GraspableObject3D
(sdf, mesh, key='', model_name='', mass=1.0, convex_pieces=None)[source]¶ Bases:
graspnetAPI.utils.dexnet.grasping.graspable_object.GraspableObject
3D Graspable object for computing contact in grasping.
- sdf
Sdf3D
signed distance field, for quickly computing contact points
- mesh
Mesh3D
3D triangular mesh to specify object geometry, should match SDF
- key
str
object identifier, usually given from the database
- model_name
str
name of the object mesh as a .obj file, for use in collision checking
- massfloat
mass of the object
- convex_pieces
list
ofMesh3D
convex decomposition of the object geom for collision checking
-
moment_arm
(x)[source]¶ Computes the moment arm to a point x.
- x3x1
numpy.ndarray
point to get moment arm for
3x1
numpy.ndarray
- x3x1
-
rescale
(scale)[source]¶ Rescales uniformly by a given factor.
- scalefloat
the amount to scale the object
GraspableObject3D
the graspable object rescaled by the given factor
-
surface_information
(grasp, width, num_steps, plot=False, direction1=None, direction2=None)[source]¶ Returns the patches on this object for a given grasp.
- grasp
ParallelJawPtGrasp3D
grasp to get the patch information for
- widthfloat
width of jaw opening
- num_stepsint
number of steps
- plotbool
whether to plot the intermediate computation, for debugging
- direction1normalized 3x1
numpy.ndarray
direction along which to compute the surface information for the first jaw, if None then defaults to grasp axis
- direction2normalized 3x1
numpy.ndarray
direction along which to compute the surface information for the second jaw, if None then defaults to grasp axis
list
ofSurfaceWindow
surface patches, one for each contact
- grasp
-
transform
(delta_T)[source]¶ Transform by a delta transform.
- delta_T
RigidTransform
the transformation from the current reference frame to the alternate reference frame
GraspableObject3D
graspable object trasnformed by the delta
- delta_T
- sdf
graspnetAPI.utils.dexnet.grasping.quality module¶
-
class
graspnetAPI.utils.dexnet.grasping.quality.
PointGraspMetrics3D
[source]¶ Bases:
object
Class to wrap functions for quasistatic point grasp quality metrics.
-
static
ferrari_canny_L1
(forces, torques, normals, soft_fingers=False, params=None, wrench_norm_thresh=0.001, wrench_regularizer=1e-10)[source]¶ Ferrari & Canny’s L1 metric. Also known as the epsilon metric.
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
- wrench_norm_threshfloat
threshold to use to determine equivalence of target wrenches
- wrench_regularizerfloat
small float to make quadratic program positive semidefinite
float : value of metric
- forces3xN
-
static
ferrari_canny_L1_force_only
(forces, torques, normals, soft_fingers=False, params=None, wrench_norm_thresh=0.001, wrench_regularizer=1e-10)[source]¶ Ferrari & Canny’s L1 metric with force only. Also known as the epsilon metric.
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
- wrench_norm_threshfloat
threshold to use to determine equivalence of target wrenches
- wrench_regularizerfloat
small float to make quadratic program positive semidefinite
float : value of metric
- forces3xN
-
static
force_closure
(c1, c2, friction_coef, use_abs_value=True)[source]¶ ” Checks force closure using the antipodality trick.
- c1
Contact3D
first contact point
- c2
Contact3D
second contact point
- friction_coeffloat
coefficient of friction at the contact point
- use_abs_valuebool
whether or not to use directoinality of the surface normal (useful when mesh is not oriented)
int : 1 if in force closure, 0 otherwise
- c1
-
static
force_closure_qp
(forces, torques, normals, soft_fingers=False, wrench_norm_thresh=0.001, wrench_regularizer=1e-10, params=None)[source]¶ Checks force closure by solving a quadratic program (whether or not zero is in the convex hull)
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- wrench_norm_threshfloat
threshold to use to determine equivalence of target wrenches
- wrench_regularizerfloat
small float to make quadratic program positive semidefinite
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
int : 1 if in force closure, 0 otherwise
- forces3xN
-
static
grasp_isotropy
(forces, torques, normals, soft_fingers=False, params=None)[source]¶ Condition number of grasp matrix - ratio of “weakest” wrench that the grasp can exert to the “strongest” one.
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
float : value of grasp isotropy metric
- forces3xN
-
static
grasp_matrix
(forces, torques, normals, soft_fingers=False, finger_radius=0.005, params=None)[source]¶ Computes the grasp map between contact forces and wrenchs on the object in its reference frame.
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- finger_radiusfloat
the radius of the fingers to use
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
- G6xM
numpy.ndarray
grasp map
- forces3xN
-
static
grasp_quality
(grasp, obj, params, contacts=None, vis=False)[source]¶ Computes the quality of a two-finger point grasps on a given object using a quasi-static model.
- grasp
ParallelJawPtGrasp3D
grasp to evaluate
- obj
GraspableObject3D
object to evaluate quality on
- params
GraspQualityConfig
parameters of grasp quality function
- grasp
-
static
min_norm_vector_in_facet
(facet, wrench_regularizer=1e-10)[source]¶ Finds the minimum norm point in the convex hull of a given facet (aka simplex) by solving a QP.
- facet6xN
numpy.ndarray
vectors forming the facet
- wrench_regularizerfloat
small float to make quadratic program positive semidefinite
- float
minimum norm of any point in the convex hull of the facet
- Nx1
numpy.ndarray
vector of coefficients that achieves the minimum
- facet6xN
-
static
min_singular
(forces, torques, normals, soft_fingers=False, params=None)[source]¶ Min singular value of grasp matrix - measure of wrench that grasp is “weakest” at resisting.
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
float : value of smallest singular value
- forces3xN
-
static
partial_closure
(forces, torques, normals, soft_fingers=False, wrench_norm_thresh=0.001, wrench_regularizer=1e-10, params=None)[source]¶ Evalutes partial closure: whether or not the forces and torques can resist a specific wrench. Estimates resistance by sollving a quadratic program (whether or not the target wrench is in the convex hull).
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- wrench_norm_threshfloat
threshold to use to determine equivalence of target wrenches
- wrench_regularizerfloat
small float to make quadratic program positive semidefinite
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
int : 1 if in partial closure, 0 otherwise
- forces3xN
-
static
wrench_in_positive_span
(wrench_basis, target_wrench, force_limit, num_fingers=1, wrench_norm_thresh=0.0001, wrench_regularizer=1e-10)[source]¶ Check whether a target can be exerted by positive combinations of wrenches in a given basis with L1 norm fonger force limit limit.
- wrench_basis6xN
numpy.ndarray
basis for the wrench space
- target_wrench6x1
numpy.ndarray
target wrench to resist
- force_limitfloat
L1 upper bound on the forces per finger (aka contact point)
- num_fingersint
number of contacts, used to enforce L1 finger constraint
- wrench_norm_threshfloat
threshold to use to determine equivalence of target wrenches
- wrench_regularizerfloat
small float to make quadratic program positive semidefinite
- int
whether or not wrench can be resisted
- float
minimum norm of the finger forces required to resist the wrench
- wrench_basis6xN
-
static
wrench_resistance
(forces, torques, normals, soft_fingers=False, wrench_norm_thresh=0.001, wrench_regularizer=1e-10, finger_force_eps=1e-09, params=None)[source]¶ Evalutes wrench resistance: the inverse norm of the contact forces required to resist a target wrench Estimates resistance by sollving a quadratic program (min normal contact forces to produce a wrench).
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- wrench_norm_threshfloat
threshold to use to determine equivalence of target wrenches
- wrench_regularizerfloat
small float to make quadratic program positive semidefinite
- finger_force_epsfloat
small float to prevent numeric issues in wrench resistance metric
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
float : value of wrench resistance metric
- forces3xN
-
static
wrench_volume
(forces, torques, normals, soft_fingers=False, params=None)[source]¶ Volume of grasp matrix singular values - score of all wrenches that the grasp can resist.
- forces3xN
numpy.ndarray
set of forces on object in object basis
- torques3xN
numpy.ndarray
set of torques on object in object basis
- normals3xN
numpy.ndarray
surface normals at the contact points
- soft_fingersbool
whether or not to use the soft finger contact model
- params
GraspQualityConfig
set of parameters for grasp matrix and contact model
float : value of wrench volume
- forces3xN
-
static
Module contents¶
Copyright ©2017. The Regents of the University of California (Regents). All Rights Reserved. Permission to use, copy, modify, and distribute this software and its documentation for educational, research, and not-for-profit purposes, without fee and without a signed licensing agreement, is hereby granted, provided that the above copyright notice, this paragraph and the following two paragraphs appear in all copies, modifications, and distributions. Contact The Office of Technology Licensing, UC Berkeley, 2150 Shattuck Avenue, Suite 510, Berkeley, CA 94720-1620, (510) 643- 7201, otl@berkeley.edu, http://ipira.berkeley.edu/industry-info for commercial licensing opportunities.
IN NO EVENT SHALL REGENTS BE LIABLE TO ANY PARTY FOR DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES, INCLUDING LOST PROFITS, ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF REGENTS HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
REGENTS SPECIFICALLY DISCLAIMS ANY WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE AND ACCOMPANYING DOCUMENTATION, IF ANY, PROVIDED HEREUNDER IS PROVIDED “AS IS”. REGENTS HAS NO OBLIGATION TO PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.