DexNet¶
Class containing the high-level API for generating and reading Dex-Net databases.
-
class
dexnet.api.
DexNet
¶ Class providing an interface for main DexNet pipeline
-
database
¶ :obj:`dexnet.database.Database – Current active database. Can set manually, or with open_database
-
dataset
¶ :obj:`dexnet.database.Dataset – Current active dataset. Can set manually, or with open_dataset
-
default_config
¶ dictionary
– A dictionary containing default config values See Other Parameters for details. These parameters are also listed under the function(s) they are relevant to Also, see:dexnet.grasping.grasp_quality_config for metrics and their associated configs dexnet.database.mesh_processor for configs associated with initial mesh processing
Other Parameters: - cache_dir – Cache directory for to store intermediate files. If None uses a temporary directory
- use_default_mass – If True, clobbers mass and uses default_mass as mass always
- default_mass – Default mass value if mass is not given, or if use_default_mass is set
- gripper_dir – Directory where the grippers models and parameters are
- metric_display_rate – Number of grasps to compute metrics for before logging a line
- gravity_accel – Gravity acceleration for computing gravity-based metrics
- metrics – Dictionary mapping metric names to metric config dicts For available metrics and their config parameters see dexnet.grasping.grasp_quality_config
- grasp_sampler – type of grasp sampler to use. One of {‘antipodal’, ‘gaussian’, ‘uniform’}.
- max_grasp_sampling_iters – number of attempts to return an exact number of grasps before giving up
- export_format – Format for export. One of obj, stl, urdf
- export_scale – Scale for export.
- export_overwrite – If True, will overwrite existing files
- animate – Whether or not to animate the displayed object
- quality_scale – Range to scale quality metric values to
- show_gripper – Whether or not to show the gripper in the visualization
- min_metric – lowest value of metric to show grasps for
- max_plot_gripper – Number of grasps to plot
-
add_object
(filepath, config=None, mass=None, name=None)¶ Add graspable object to current open dataset
Parameters: - filepath (
str
) – Path to mesh file - config (
dict
) – Dictionary of parameters for mesh creating/processing Parameters are in Other parameters. Values from self.default_config are used for keys not provided. See dexnet.database.mesh_processor.py for details on the parameters available for mesh processor - name (
str
) – Name to use for graspable. If None defaults to the name of the obj file provided in filepath - mass (float) – Mass of object. Gets clobbered if use_default_mass is set in config.
Other Parameters: - cache_dir – Cache directory for mesh processor to store intermediate files. If None uses a temporary directory
- use_default_mass – If True, clobbers mass and uses default_mass as mass always
- default_mass – Default mass value if mass is not given, or if use_default_mass is set
Raises: RuntimeError
– Graspable with same name already in database. Database or dataset not opened.- filepath (
-
compute_metadata
(object_name, config=None, overwrite=False)¶ Compute metadata for object
Parameters: - object (
str
) – Object name to compute metadata for - overwrite (boolean) – If True, overwrites existing metadata. Otherwise, logs a warning and keeps existing metadata
Raises: RuntimeError
– Database or dataset not opened.- object (
-
compute_metrics
(config=None, metric_name=None, object_name=None, gripper_name=None, stable_pose=None, overwrite=True)¶ Compute metrics for an object or the entire dataset.
Parameters: - config (
dict
) – Configuration dict for metric computation. Parameters are in Other parameters. Values from self.default_config are used for keys not provided. - metric_name (
str
) – Metric to compute grasps for. If None does all metrics - object_name (
str
) – Object key to compute a grasp for. If None does the whole dataset - gripper_name (
str
) – Gripper to compute a grasp for. If None does all grippers - stable_pose (
str
) – ID of stable pose to use. If None does all stable poses. Note that setting this does not make sense if obj_name is None - overwrite (boolean) – If True, overwrites existing computed metrics. Otherwise logs a warning and keeps existing values
Other Parameters: - gripper_dir – Directory where the grippers models and parameters are
- metric_display_rate – Number of grasps to compute metrics for before logging a line
- gravity_accel – Gravity acceleration for computing gravity-based metrics
- metrics – Dictionary mapping metric names to metric config dicts For available metrics and their config parameters see dexnet.grasping.grasp_quality_config
Raises: ValueError
– invalid metric, object or gripper nameRuntimeError
– Database or dataset not opened.RuntimeWarning
– Grasps do not exist for given gripper on given object
- config (
-
compute_simulation_data
(object_name, config=None)¶ Compute normals and convex decomposition for object (preprocessing for simulation)
Parameters: - object_name – Object to compute normals and convex decomposition for
- config (
dict
) – Configuration dict for computing simulation data. Parameters are in Other parameters. Values from self.default_config are used for keys not provided.
Other Parameters: cache_dir – Cache directory for to store intermediate files. If None uses a temporary directory
Raises: RuntimeError
– Database or dataset not opened.
-
delete_object
(object_name)¶ Delete an object
Parameters: object_name (
str
) – Object to deleteRaises: ValueError
– invalid object nameRuntimeError
– Database or dataset not opened
-
display_grasps
(object_name, gripper_name, metric_name, config=None)¶ Display grasps for an object
Parameters: - object_name (
str
) – Object to display - gripper_name (
str
) – Gripper for which to display grasps - metric_name (
str
) – Metric to color/rank grasps with - config (
dict
) – Configuration dict for visualization. Parameters are in Other parameters. Values from self.default_config are used for keys not provided.
Other Parameters: - gripper_dir – Directory where the grippers models and parameters are.
- quality_scale – Range to scale quality metric values to
- show_gripper – Whether or not to show the gripper in the visualization
- min_metric – lowest value of metric to show grasps for
- max_plot_gripper – Number of grasps to plot
- animate – Whether or not to animate the displayed object
- object_name (
-
display_object
(object_name, config=None)¶ Display an object
Parameters: - object_name (
str
) – Ob ject to display. - config (
dict
) – Configuration dict for visualization. Parameters are in Other parameters. Values from self.default_config are used for keys not provided.
Other Parameters: animate – Whether or not to animate the displayed object
Raises: ValueError
– invalid object nameRuntimeError
– Database or dataset not opened.
- object_name (
-
display_stable_poses
(object_name, config=None)¶ Display an object’s stable poses
Parameters: - object_name (
str
) – Object to display. - config (
dict
) – Configuration dict for visualization. Parameters are in Other parameters. Values from self.default_config are used for keys not provided.
Other Parameters: animate – Whether or not to animate the displayed object
Raises: ValueError
– invalid object nameRuntimeError
– Database or dataset not opened.
- object_name (
-
export_objects
(output_dir, export_filters={}, to_export=None, config=None)¶ Export objects as .obj files to a directory. Provides filtering ability to only export some objects
Parameters: - output_dir (
str
) – Directory to output to objects to - export_filters (
dict
mappingstr
to :obj:function) – Functions to filter with. Each function takes in the metadata with its key as the key associated with each object and returns True or False. If True exports object, if False doesn’t. Example: {‘num_con_comps’ : (lambda x: x == 1)} will export only objects with exactly one connected component - to_export (
list
ofstr
) – List of objects to export. If None exports all objects in dataset - config (
dict
) – Configuration dict for computing simulation data. Parameters are in Other parameters. Values from self.default_config are used for keys not provided.
Other Parameters: - export_format – Format for export. One of obj, stl, urdf
- export_scale – Scale for export.
- export_overwrite – If True, will overwrite existing files
Raises: RuntimeError
– Database or dataset not opened.ValueError
– Export format not supported
- output_dir (
-
get_grasps
(object_name, gripper_name, metric_name=None)¶ Returns the list of grasps for the given graspable sorted by decreasing quality according to the given metric.
Parameters: - object_name (
str
) – name of object to get grasps for - gripper_name (
str
) – name of gripper - metric_name (
str
) – name of metric to use for sorting. If None does not sort grasps
Returns: list
ofdexnet.grasping.ParallelJawPtGrasp3D
– stored grasps for the object and gripper sorted by metric in descending order, empty list if gripper not foundlist
of float – values of metrics for the grasps sorted in descending order, empty list if gripper not found or if metric_name not given
- object_name (
-
get_metadata
(object_name, config=None)¶ Get metadata for object
Parameters: object_name ( str
) – object name to get metadata forRaises: RuntimeError
– Database or dataset not opened.
-
get_object
(object_name)¶ Get an object from current dataset by name
Parameters: object_name ( str
) – Name of object to getReturns: Specified object Return type: Mesh3D
-
get_stable_poses
(object_name)¶ Get stable poses for an object by name
Parameters: object_name ( str
) – Name of object to getReturns: Stable poses of object Return type: list
ofmeshpy.StablePose
-
list_grippers
(config=None)¶ List available grippers
Parameters: config ( dict
) – Configuration dict. Parameters are in Other parameters. Values from self.default_config are used for keys not provided.Other Parameters: gripper_dir – Directory where the grippers models and parameters are
-
list_metadata
()¶ List available metadata names.
Returns: List of metadata names Return type: list
ofstr
-
list_metrics
(config=None)¶ List available metrics
Parameters: config ( dict
) – Configuration dict. Parameters are in Other parameters. Values from self.default_config are used for keys not provided.Other Parameters: metrics – Dictionary mapping metric names to metric config dicts Returns: List of metric names Return type: list
ofstr
-
list_objects
()¶ List available objects in current dataset
Returns: List of objects in current dataset Return type: list
ofstr
-
open_database
(database_path, config=None, create_db=True)¶ Open/create a database.
Parameters: - database_path (
str
) – Path (can be relative) to the database, or the path to create a database at. - create_db (boolean) – If True, creates database if one does not exist at location specified. If False, raises error if database does not exist at location specified.
- config (
dict
) – Dictionary of parameters for database creation Parameters are in Other Parameters. Values from self.default_config are used for keys not provided.
Other Parameters: cache_dir – Cache directory for to store intermediate files. If None uses a temporary directory
Raises: ValueError
– If database_path does not have an extension corresponding to a hdf5 database. If database does not exist at path and create_db is False.- database_path (
-
open_dataset
(dataset_name, config=None, create_ds=True)¶ Open/create a dataset
Parameters: - dataset_name (
str
) – Name of dataset to open/create - create_ds (boolean) – If True, creates dataset if one does not exist with name specified. If False, raises error if specified dataset does not exist
- config (
dict
) – Dictionary containing a key ‘metrics’ that maps to a dictionary mapping metric names to metric config dicts For available metrics and their corresponding config parameters see dexnet.grasping.grasp_quality_config Values from self.default_config are used for keys not provided
Raises: ValueError
– If dataset_name is invalid. Also if dataset does not exist and create_ds is FalseRuntimeError
– No database open
- dataset_name (
-
sample_grasps
(config=None, object_name=None, gripper_name=None, overwrite=True, stable_pose=None)¶ Sample grasps for an object or the entire dataset
Parameters: - config (
dict
) – Configuration dict for grasping. The required Parameters are in ‘Other Parameters’. Values from self.default_config are used for keys not provided. - object_name (
str
) – Object key to compute a grasp for. If None does the whole dataset - gripper_name (
str
) – Gripper to compute a grasp for. If None does all grippers - overwrite (bool) – If True, overwrites existing grasps. Otherwise logs a warning and keeps existing grasps
- stable_pose (
str
) – ID of stable pose to use. If None does all stable poses. Note that setting this does not make sense if obj_name is None
Other Parameters: - grasp_sampler – type of grasp sampler to use. One of {‘antipodal’, ‘gaussian’, ‘uniform’}.
- max_grasp_sampling_iters – number of attempts to return an exact number of grasps before giving up
- gripper_dir – Directory where the grippers models and parameters are.
Raises: ValueError
– invalid object or gripper nameRuntimeError
– Grasps already exist for given object and gripper, and overwrite is False Database or dataset not opened.
- config (
-