panda_autograsp.grasp_planners package¶
Submodules¶
panda_autograsp.grasp_planners.gqcnn_grasp_planner module¶
This module uses the BerkleyAutomation GQCNN grasp detector to compute a valid grasp out of RBG-D sensor data.
-
class
panda_autograsp.grasp_planners.gqcnn_grasp_planner.
GQCNNGrasp
[source]¶ Bases:
object
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
-
-
class
panda_autograsp.grasp_planners.gqcnn_grasp_planner.
GraspPlanner
(model='FC-GQCNN-4.0-PJ', sensor_type='kinectv2')[source]¶ Bases:
object
Class used to compute the grasp pose out of the RGB-D data.
-
cfg
¶ autolab_core.YamlConfig
The graspyaml
configuration file.
-
policy_cfg
¶ autolab_core.YamlConfig
The policyyaml
configuration file.
-
sensor
¶ perception.Kinect2Sensor
The sensor object.
-
grasping_policy
¶ gqcnn.CrossEntropyRobustGraspingPolicy
The grasp policy.
-
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: tuple
ofperception.ColorImage
,perception.DepthImage
,perception.IrImage
,numpy.ndarray
– The ColorImage, DepthImage, and IrImage of the current frame.
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 NoneReturns: 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 objectReturns: Computed optimal grasp. Return type: GQCNNGrasp
-
execute_policy
(rgbd_image_state, grasping_policy, pose_frame)[source]¶ Executes a grasping policy on an RgbdImageState.
Parameters: - rgbd_image_state (
gqcnn.RgbdImageState
) – Thegqcnn.RgbdImageState
that encapsulates the depth and color image along with camera intrinsics. - grasping_policy (
gqcnn.grasping.policy.policy.GraspingPolicy
) – Grasping policy to use. - pose_frame (
str
) – Frame of reference to publish pose in.
- rgbd_image_state (
-
panda_autograsp.grasp_planners.gqcnn_grasp_planner_ros module¶
This is the ROS version of the gqcnn_grap_planner
module.
This module uses the BerkleyAutomation GQCNN
grasp detector to compute a valid grasp out of RBG-D sensor data.
-
class
panda_autograsp.grasp_planners.gqcnn_grasp_planner_ros.
GraspPlannerROS
(cfg, cv_bridge, grasping_policy, grasp_pose_publisher)[source]¶ Bases:
object
Class used to compute the grasp pose out of the RGB-D data.
-
cfg
¶ The grasp
yaml
configuration file.Type: YamlConfig
-
grasping_policy
¶ The grasp policy.
Type: CrossEntropyRobustGraspingPolicy
-
__init__
(cfg, cv_bridge, grasping_policy, grasp_pose_publisher)[source]¶ Parameters: - cfg (dict) – Dictionary of configuration parameters.
- cv_bridge (
CvBridge
) – ROS CvBridge. - grasping_policy (
GraspingPolicy
) – Grasping policy to use. - grasp_pose_publisher (
Publisher
) –
-
read_images
(req)[source]¶ Retrieves the input images from a ROS service request.
Parameters: req ( ROS ServiceRequest
) – ROS ServiceRequest for grasp planner service.
-
plan_grasp
(req)[source]¶ Grasp planner request handler.
Parameters: req ( ROS ServiceRequest
) – ROS ServiceRequest for grasp planner service.
-
plan_grasp_bb
(req)[source]¶ Grasp planner request handler.
Parameters: req ( ROS ServiceRequest
) – ROS ServiceRequest for grasp planner service.
-
plan_grasp_segmask
(req)[source]¶ Grasp planner request handler.
Parameters: req ( ROS ServiceRequest
) – ROS ServiceRequest for grasp planner service.
-
execute_policy
(rgbd_image_state, grasping_policy, grasp_pose_publisher, pose_frame)[source]¶ Executes a grasping policy on an RgbdImageState.
Parameters: - rgbd_image_state (
RgbdImageState
) – RgbdImageState from BerkeleyAutomation/perception to encapsulate depth and color image along with camera intrinsics. - grasping_policy (
GraspingPolicy
) – Grasping policy to use. - grasp_pose_publisher (
Publisher
) – ROS publisher to publish pose of planned grasp for visualization. - pose_frame (
str
) – Frame of reference to publish pose in.
- rgbd_image_state (
-
Module contents¶
Module containing a number of autonomous grasping solutions.
gqcnn_grasp_planner |
This module uses the BerkleyAutomation GQCNN grasp detector to compute a valid grasp out of RBG-D sensor data. |
gqcnn_grasp_planner_ros |
This is the ROS version of the gqcnn_grap_planner module. |