#include <grasp_filter.h>
Public Member Functions | |
bool | chooseBestGrasp (const std::vector< moveit_msgs::Grasp > &possible_grasps, moveit_msgs::Grasp &chosen) |
bool | filterGrasps (std::vector< moveit_msgs::Grasp > &possible_grasps, std::vector< trajectory_msgs::JointTrajectoryPoint > &ik_solutions, bool filter_pregrasp, const std::string &ee_parent_link, const std::string &planning_group) |
Choose the 1st grasp that is kinematically feasible. | |
bool | filterNthGrasp (std::vector< moveit_msgs::Grasp > &possible_grasps, int n) |
GraspFilter (robot_state::RobotState robot_state, moveit_visual_tools::MoveItVisualToolsPtr &visual_tools) | |
~GraspFilter () | |
Private Member Functions | |
void | filterGraspThread (IkThreadStruct ik_thread_struct) |
Thread for checking part of the possible grasps list. | |
Private Attributes | |
std::map< std::string, std::vector < kinematics::KinematicsBaseConstPtr > > | kin_solvers_ |
robot_state::RobotState | robot_state_ |
bool | verbose_ |
moveit_visual_tools::MoveItVisualToolsPtr | visual_tools_ |
Definition at line 112 of file grasp_filter.h.
moveit_simple_grasps::GraspFilter::GraspFilter | ( | robot_state::RobotState | robot_state, |
moveit_visual_tools::MoveItVisualToolsPtr & | visual_tools | ||
) |
Definition at line 45 of file grasp_filter.cpp.
Definition at line 54 of file grasp_filter.cpp.
bool moveit_simple_grasps::GraspFilter::chooseBestGrasp | ( | const std::vector< moveit_msgs::Grasp > & | possible_grasps, |
moveit_msgs::Grasp & | chosen | ||
) |
Definition at line 58 of file grasp_filter.cpp.
bool moveit_simple_grasps::GraspFilter::filterGrasps | ( | std::vector< moveit_msgs::Grasp > & | possible_grasps, |
std::vector< trajectory_msgs::JointTrajectoryPoint > & | ik_solutions, | ||
bool | filter_pregrasp, | ||
const std::string & | ee_parent_link, | ||
const std::string & | planning_group | ||
) |
Choose the 1st grasp that is kinematically feasible.
\param | |
whether | to also check ik feasibility for the pregrasp position |
Definition at line 71 of file grasp_filter.cpp.
void moveit_simple_grasps::GraspFilter::filterGraspThread | ( | IkThreadStruct | ik_thread_struct | ) | [private] |
Thread for checking part of the possible grasps list.
Definition at line 192 of file grasp_filter.cpp.
bool moveit_simple_grasps::GraspFilter::filterNthGrasp | ( | std::vector< moveit_msgs::Grasp > & | possible_grasps, |
int | n | ||
) |
std::map<std::string, std::vector<kinematics::KinematicsBaseConstPtr> > moveit_simple_grasps::GraspFilter::kin_solvers_ [private] |
Definition at line 119 of file grasp_filter.h.
robot_state::RobotState moveit_simple_grasps::GraspFilter::robot_state_ [private] |
Definition at line 116 of file grasp_filter.h.
bool moveit_simple_grasps::GraspFilter::verbose_ [private] |
Definition at line 124 of file grasp_filter.h.
moveit_visual_tools::MoveItVisualToolsPtr moveit_simple_grasps::GraspFilter::visual_tools_ [private] |
Definition at line 122 of file grasp_filter.h.