panda_autograsp.grasp_planners.gqcnn_grasp_planner

This module uses the BerkleyAutomation GQCNN grasp detector to compute a valid grasp out of RBG-D sensor data.

Classes

GQCNNGrasp() Class for storing the computed grasps.
GraspPlanner([model, sensor_type]) Class used to compute the grasp pose out of the RGB-D data.
class panda_autograsp.grasp_planners.gqcnn_grasp_planner.GQCNNGrasp[source]

Class for storing the computed grasps. This class is a trimmed down version of the original gqcnn.grasping.policy.policy.GraspAction.

PARALLEL_JAW

PARALLEL_JAW Specifies parallel jaw gripper type information

SUCTION

SUCTION Specifies suction jaw gripper type information

class panda_autograsp.grasp_planners.gqcnn_grasp_planner.GraspPlanner(model='FC-GQCNN-4.0-PJ', sensor_type='kinectv2')[source]

Class used to compute the grasp pose out of the RGB-D data.

cfg

autolab_core.YamlConfig The grasp yaml configuration file.

policy_cfg

autolab_core.YamlConfig The policy yaml configuration file.

sensor_type

str The type of sensor that is used.

gqcnn_model

str The GQCNN model that is used.

gripper_mode

unicode The gripper that is used.

sensor

perception.Kinect2Sensor The sensor object.

grasping_policy

gqcnn.CrossEntropyRobustGraspingPolicy The grasp policy.

min_width

int The minimum allowed image width.

min_height

int The minimum allowed image height.

__init__(model='FC-GQCNN-4.0-PJ', sensor_type='kinectv2')[source]
Parameters:
  • model (str, optional) – Name of the grasp detection model, by default DEFAULT_MODEL.
  • sensor_type (str, optional) – The name of the RGBD sensor, by default kinectv2.
start()[source]

Calls the _start_sensor method.

read_images(skip_registration=False)[source]

Retrieves data frames from the sensor.

Parameters:skip_registration (bool, optional) – If True, the registration step is skipped, by default False.
Returns:
Raises:exceptions.RuntimeError – If the Kinect stream is not running.
plan_grasp()[source]

Samples the image and computes possible grasps.

Returns:Computed optimal grasp.
Return type:GQCNNGrasp
plan_grasp_bb(bounding_box=None)[source]

Samples the image and computes possible grasps while taking into account the supplied bounding box.

Parameters:bounding_box (perception.RgbdDetection, optional) – A bounding box specifying the object, by default None
Returns:Computed optimal grasp.
Return type:GQCNNGrasp
plan_grasp_segmask(segmask)[source]

Samples the image and computes possible grasps while taking into account the supplied segmask.

Parameters:segmask (perception.BinaryImage) – Binary segmask of detected object
Returns:Computed optimal grasp.
Return type:GQCNNGrasp
execute_policy(rgbd_image_state, grasping_policy, pose_frame)[source]

Executes a grasping policy on an RgbdImageState.

Parameters: