#include <simple_grasps.h>
Public Member Functions | |
| MOVEIT_DEPRECATED bool | generateAllGrasps (const geometry_msgs::Pose &object_pose, const GraspData &grasp_data, std::vector< moveit_msgs::Grasp > &possible_grasps) |
| Moved to generateBlockGrasps. | |
| bool | generateAxisGrasps (const geometry_msgs::Pose &object_pose, grasp_axis_t axis, grasp_direction_t direction, grasp_rotation_t rotation, double hand_roll, const GraspData &grasp_data, std::vector< moveit_msgs::Grasp > &possible_grasps) |
| Create grasp positions in one axis around a single pose Note: to visualize these grasps use moveit_visual_tools.publishAnimatedGrasps() function or moveit_visual_tools.publishIKSolutions() with the resulting data. | |
| bool | generateBlockGrasps (const geometry_msgs::Pose &object_pose, const GraspData &grasp_data, std::vector< moveit_msgs::Grasp > &possible_grasps) |
| Create all possible grasp positions for a block. | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | SimpleGrasps (moveit_visual_tools::MoveItVisualToolsPtr rviz_tools, bool verbose=false) |
| Constructor. | |
| ~SimpleGrasps () | |
| Destructor. | |
Static Public Member Functions | |
| static geometry_msgs::PoseStamped | getPreGraspPose (const moveit_msgs::Grasp &grasp, const std::string &ee_parent_link) |
| Using an input grasp description, get the pregrasp pose. | |
| static MOVEIT_DEPRECATED void | printObjectGraspData (const GraspData &data) |
| Print debug info DEPRECATRED: moved to grasp_data.cpp. | |
Private Attributes | |
| Eigen::Affine3d | object_global_transform_ |
| bool | verbose_ |
| moveit_visual_tools::MoveItVisualToolsPtr | visual_tools_ |
Definition at line 79 of file simple_grasps.h.
| moveit_simple_grasps::SimpleGrasps::SimpleGrasps | ( | moveit_visual_tools::MoveItVisualToolsPtr | rviz_tools, |
| bool | verbose = false |
||
| ) |
Constructor.
Definition at line 41 of file simple_grasps.cpp.
Destructor.
Definition at line 49 of file simple_grasps.cpp.
| MOVEIT_DEPRECATED bool moveit_simple_grasps::SimpleGrasps::generateAllGrasps | ( | const geometry_msgs::Pose & | object_pose, |
| const GraspData & | grasp_data, | ||
| std::vector< moveit_msgs::Grasp > & | possible_grasps | ||
| ) | [inline] |
Moved to generateBlockGrasps.
Definition at line 108 of file simple_grasps.h.
| bool moveit_simple_grasps::SimpleGrasps::generateAxisGrasps | ( | const geometry_msgs::Pose & | object_pose, |
| grasp_axis_t | axis, | ||
| grasp_direction_t | direction, | ||
| grasp_rotation_t | rotation, | ||
| double | hand_roll, | ||
| const GraspData & | grasp_data, | ||
| std::vector< moveit_msgs::Grasp > & | possible_grasps | ||
| ) |
Create grasp positions in one axis around a single pose Note: to visualize these grasps use moveit_visual_tools.publishAnimatedGrasps() function or moveit_visual_tools.publishIKSolutions() with the resulting data.
| pose | - center point of object to be grasped |
| axis | - axis relative to object pose to rotate generated grasps around |
| direction | - a parallel gripper is typically symetric such that it can perform the same grasp 180 degree around. this option allows to generate a flipped grasp pose |
| rotation | - amount to rotate around the object - 180 or 360 degrees |
| hand_roll | - amount in radians to roll wrist with respect to center point of object during grasp. use 0 by default |
| grasp_data | - parameters specific to the robot geometry |
| possible_grasps | - the output solution vector of possible grasps to attempt. ok if pre-populated |
Definition at line 68 of file simple_grasps.cpp.
| bool moveit_simple_grasps::SimpleGrasps::generateBlockGrasps | ( | const geometry_msgs::Pose & | object_pose, |
| const GraspData & | grasp_data, | ||
| std::vector< moveit_msgs::Grasp > & | possible_grasps | ||
| ) |
Create all possible grasp positions for a block.
| pose | of block, where vector arrow is parallel to table plane |
| data | describing end effector |
| resulting | generated possible grasps |
Definition at line 54 of file simple_grasps.cpp.
| geometry_msgs::PoseStamped moveit_simple_grasps::SimpleGrasps::getPreGraspPose | ( | const moveit_msgs::Grasp & | grasp, |
| const std::string & | ee_parent_link | ||
| ) | [static] |
Using an input grasp description, get the pregrasp pose.
| grasp | description |
| name | of parent link |
Definition at line 284 of file simple_grasps.cpp.
| static MOVEIT_DEPRECATED void moveit_simple_grasps::SimpleGrasps::printObjectGraspData | ( | const GraspData & | data | ) | [inline, static] |
Print debug info DEPRECATRED: moved to grasp_data.cpp.
Definition at line 161 of file simple_grasps.h.
Eigen::Affine3d moveit_simple_grasps::SimpleGrasps::object_global_transform_ [private] |
Definition at line 87 of file simple_grasps.h.
bool moveit_simple_grasps::SimpleGrasps::verbose_ [private] |
Definition at line 90 of file simple_grasps.h.
moveit_visual_tools::MoveItVisualToolsPtr moveit_simple_grasps::SimpleGrasps::visual_tools_ [private] |
Definition at line 84 of file simple_grasps.h.