Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #ifndef SIMPLE_GRASPING_SHAPE_GRASP_PLANNER_H
00034 #define SIMPLE_GRASPING_SHAPE_GRASP_PLANNER_H
00035
00036 #include <ros/ros.h>
00037 #include <grasping_msgs/GraspableObject.h>
00038
00039 namespace simple_grasping
00040 {
00041
00046 class ShapeGraspPlanner
00047 {
00048 public:
00053 ShapeGraspPlanner(ros::NodeHandle& nh);
00054
00055 virtual int plan(const grasping_msgs::Object& object,
00056 std::vector<moveit_msgs::Grasp>& grasps);
00057
00058 private:
00068 int createGrasp(const geometry_msgs::PoseStamped& pose,
00069 double gripper_opening,
00070 double gripper_pitch,
00071 double x_offset,
00072 double z_offset,
00073 double quality);
00074
00086 int createGraspSeries(const geometry_msgs::PoseStamped& pose,
00087 double depth, double width, double height,
00088 bool use_vertical = true);
00089
00090 trajectory_msgs::JointTrajectory makeGraspPosture(double pose);
00091
00092
00093 std::string left_joint_, right_joint_;
00094 double max_opening_;
00095 double max_effort_;
00096 double grasp_duration_;
00097 double tool_offset_;
00098 double finger_depth_;
00099 double gripper_tolerance_;
00100
00101
00102 std::string approach_frame_;
00103 double approach_min_translation_;
00104 double approach_desired_translation_;
00105
00106
00107 std::string retreat_frame_;
00108 double retreat_min_translation_;
00109 double retreat_desired_translation_;
00110
00111
00112 std::vector<moveit_msgs::Grasp> grasps_;
00113 };
00114
00115 }
00116
00117 #endif // SIMPLE_GRASPING_SHAPE_GRASP_PLANNER_H