Public Member Functions | Private Member Functions | Private Attributes
simple_grasping::ShapeGraspPlanner Class Reference

A simple grasp planner that uses the bounding box shape to generate viable grasps. More...

#include <shape_grasp_planner.h>

List of all members.

Public Member Functions

virtual int plan (const grasping_msgs::Object &object, std::vector< moveit_msgs::Grasp > &grasps)
 ShapeGraspPlanner (ros::NodeHandle &nh)
 Constructor, loads grasp planner configuration from ROS params.

Private Member Functions

int createGrasp (const geometry_msgs::PoseStamped &pose, double gripper_opening, double gripper_pitch, double x_offset, double z_offset, double quality)
 Generate a grasp, add it to internal grasps_.
int createGraspSeries (const geometry_msgs::PoseStamped &pose, double depth, double width, double height, bool use_vertical=true)
 Generate a series of grasps around the edge of a shape.
trajectory_msgs::JointTrajectory makeGraspPosture (double pose)

Private Attributes

double approach_desired_translation_
std::string approach_frame_
double approach_min_translation_
double finger_depth_
double grasp_duration_
std::vector< moveit_msgs::Grasp > grasps_
double gripper_tolerance_
std::string left_joint_
double max_effort_
double max_opening_
double retreat_desired_translation_
std::string retreat_frame_
double retreat_min_translation_
std::string right_joint_
double tool_offset_

Detailed Description

A simple grasp planner that uses the bounding box shape to generate viable grasps.

Definition at line 46 of file shape_grasp_planner.h.


Constructor & Destructor Documentation

Constructor, loads grasp planner configuration from ROS params.

Parameters:
nhNodehandle to use for accessing grasp planner parameters.

Definition at line 75 of file shape_grasp_planner.cpp.


Member Function Documentation

int simple_grasping::ShapeGraspPlanner::createGrasp ( const geometry_msgs::PoseStamped &  pose,
double  gripper_opening,
double  gripper_pitch,
double  x_offset,
double  z_offset,
double  quality 
) [private]

Generate a grasp, add it to internal grasps_.

Parameters:
poseThe pose of the end effector tool point
gripper_pitchThe pitch of the gripper on approach
x_offsetThe offset in the x direction (in).
z_offsetThe offset in the z direction (up).
qualityThe quality to ascribe to this grasp.
Returns:
The number of grasps generated.

Definition at line 108 of file shape_grasp_planner.cpp.

int simple_grasping::ShapeGraspPlanner::createGraspSeries ( const geometry_msgs::PoseStamped &  pose,
double  depth,
double  width,
double  height,
bool  use_vertical = true 
) [private]

Generate a series of grasps around the edge of a shape.

Parameters:
poseThe pose of the end effector tool point.
depthThe depth of the shape.
widthThe width of the shape.
heightThe height of the shape.
use_verticalWhether to include vertical poses. If coming from two sides, the second call probably should not generate vertical poses.
Returns:
The number of grasps generated.

Definition at line 162 of file shape_grasp_planner.cpp.

trajectory_msgs::JointTrajectory simple_grasping::ShapeGraspPlanner::makeGraspPosture ( double  pose) [private]

Definition at line 292 of file shape_grasp_planner.cpp.

int simple_grasping::ShapeGraspPlanner::plan ( const grasping_msgs::Object &  object,
std::vector< moveit_msgs::Grasp > &  grasps 
) [virtual]

Definition at line 215 of file shape_grasp_planner.cpp.


Member Data Documentation

Definition at line 104 of file shape_grasp_planner.h.

Definition at line 102 of file shape_grasp_planner.h.

Definition at line 103 of file shape_grasp_planner.h.

Definition at line 98 of file shape_grasp_planner.h.

Definition at line 96 of file shape_grasp_planner.h.

std::vector<moveit_msgs::Grasp> simple_grasping::ShapeGraspPlanner::grasps_ [private]

Definition at line 112 of file shape_grasp_planner.h.

Definition at line 99 of file shape_grasp_planner.h.

Definition at line 93 of file shape_grasp_planner.h.

Definition at line 95 of file shape_grasp_planner.h.

Definition at line 94 of file shape_grasp_planner.h.

Definition at line 109 of file shape_grasp_planner.h.

Definition at line 107 of file shape_grasp_planner.h.

Definition at line 108 of file shape_grasp_planner.h.

Definition at line 93 of file shape_grasp_planner.h.

Definition at line 97 of file shape_grasp_planner.h.


The documentation for this class was generated from the following files:


simple_grasping
Author(s): Michael Ferguson
autogenerated on Thu Jun 6 2019 19:12:06