A simple grasp planner that uses the bounding box shape to generate viable grasps.
More...
#include <shape_grasp_planner.h>
|
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_. More...
|
|
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. More...
|
|
trajectory_msgs::JointTrajectory | makeGraspPosture (double pose) |
|
A simple grasp planner that uses the bounding box shape to generate viable grasps.
Definition at line 46 of file shape_grasp_planner.h.
simple_grasping::ShapeGraspPlanner::ShapeGraspPlanner |
( |
ros::NodeHandle & |
nh | ) |
|
Constructor, loads grasp planner configuration from ROS params.
- Parameters
-
nh | Nodehandle to use for accessing grasp planner parameters. |
Definition at line 75 of file shape_grasp_planner.cpp.
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
-
pose | The pose of the end effector tool point |
gripper_pitch | The pitch of the gripper on approach |
x_offset | The offset in the x direction (in). |
z_offset | The offset in the z direction (up). |
quality | The 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
-
pose | The pose of the end effector tool point. |
depth | The depth of the shape. |
width | The width of the shape. |
height | The height of the shape. |
use_vertical | Whether 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 |
int simple_grasping::ShapeGraspPlanner::plan |
( |
const grasping_msgs::Object & |
object, |
|
|
std::vector< moveit_msgs::Grasp > & |
grasps |
|
) |
| |
|
virtual |
double simple_grasping::ShapeGraspPlanner::approach_desired_translation_ |
|
private |
std::string simple_grasping::ShapeGraspPlanner::approach_frame_ |
|
private |
double simple_grasping::ShapeGraspPlanner::approach_min_translation_ |
|
private |
double simple_grasping::ShapeGraspPlanner::finger_depth_ |
|
private |
double simple_grasping::ShapeGraspPlanner::grasp_duration_ |
|
private |
std::vector<moveit_msgs::Grasp> simple_grasping::ShapeGraspPlanner::grasps_ |
|
private |
double simple_grasping::ShapeGraspPlanner::gripper_tolerance_ |
|
private |
std::string simple_grasping::ShapeGraspPlanner::left_joint_ |
|
private |
double simple_grasping::ShapeGraspPlanner::max_effort_ |
|
private |
double simple_grasping::ShapeGraspPlanner::max_opening_ |
|
private |
double simple_grasping::ShapeGraspPlanner::retreat_desired_translation_ |
|
private |
std::string simple_grasping::ShapeGraspPlanner::retreat_frame_ |
|
private |
double simple_grasping::ShapeGraspPlanner::retreat_min_translation_ |
|
private |
std::string simple_grasping::ShapeGraspPlanner::right_joint_ |
|
private |
double simple_grasping::ShapeGraspPlanner::tool_offset_ |
|
private |
The documentation for this class was generated from the following files: