33 #ifndef SIMPLE_GRASPING_SHAPE_GRASP_PLANNER_H    34 #define SIMPLE_GRASPING_SHAPE_GRASP_PLANNER_H    37 #include <grasping_msgs/GraspableObject.h>    55   virtual int plan(
const grasping_msgs::Object& 
object,
    56                    std::vector<moveit_msgs::Grasp>& 
grasps);
    69                   double gripper_opening,
    87                         double depth, 
double width, 
double height,
    88                         bool use_vertical = 
true);
   117 #endif  // SIMPLE_GRASPING_SHAPE_GRASP_PLANNER_H 
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. 
double approach_min_translation_
ShapeGraspPlanner(ros::NodeHandle &nh)
Constructor, loads grasp planner configuration from ROS params. 
double retreat_desired_translation_
std::string retreat_frame_
double approach_desired_translation_
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_. 
double gripper_tolerance_
double retreat_min_translation_
std::string approach_frame_
virtual int plan(const grasping_msgs::Object &object, std::vector< moveit_msgs::Grasp > &grasps)
std::vector< moveit_msgs::Grasp > grasps_
trajectory_msgs::JointTrajectory makeGraspPosture(double pose)
A simple grasp planner that uses the bounding box shape to generate viable grasps.