A simple grasp planner that uses the bounding box shape to generate viable grasps. More...
#include <shape_grasp_planner.h>
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_ |
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, loads grasp planner configuration from ROS params.
| 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_.
| 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. |
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.
| 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. |
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.
double simple_grasping::ShapeGraspPlanner::approach_desired_translation_ [private] |
Definition at line 104 of file shape_grasp_planner.h.
std::string simple_grasping::ShapeGraspPlanner::approach_frame_ [private] |
Definition at line 102 of file shape_grasp_planner.h.
double simple_grasping::ShapeGraspPlanner::approach_min_translation_ [private] |
Definition at line 103 of file shape_grasp_planner.h.
double simple_grasping::ShapeGraspPlanner::finger_depth_ [private] |
Definition at line 98 of file shape_grasp_planner.h.
double simple_grasping::ShapeGraspPlanner::grasp_duration_ [private] |
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.
double simple_grasping::ShapeGraspPlanner::gripper_tolerance_ [private] |
Definition at line 99 of file shape_grasp_planner.h.
std::string simple_grasping::ShapeGraspPlanner::left_joint_ [private] |
Definition at line 93 of file shape_grasp_planner.h.
double simple_grasping::ShapeGraspPlanner::max_effort_ [private] |
Definition at line 95 of file shape_grasp_planner.h.
double simple_grasping::ShapeGraspPlanner::max_opening_ [private] |
Definition at line 94 of file shape_grasp_planner.h.
double simple_grasping::ShapeGraspPlanner::retreat_desired_translation_ [private] |
Definition at line 109 of file shape_grasp_planner.h.
std::string simple_grasping::ShapeGraspPlanner::retreat_frame_ [private] |
Definition at line 107 of file shape_grasp_planner.h.
double simple_grasping::ShapeGraspPlanner::retreat_min_translation_ [private] |
Definition at line 108 of file shape_grasp_planner.h.
std::string simple_grasping::ShapeGraspPlanner::right_joint_ [private] |
Definition at line 93 of file shape_grasp_planner.h.
double simple_grasping::ShapeGraspPlanner::tool_offset_ [private] |
Definition at line 97 of file shape_grasp_planner.h.