, including all inherited members.
cm_ | GraspSequenceValidator | [protected] |
consistent_angle_ | GraspSequenceValidator | [protected] |
feedback_function_ | object_manipulator::GraspTester | [protected] |
getCollisionModels() | GraspSequenceValidator | [protected] |
getGroupJoints(const std::string &group_name, std::vector< std::string > &group_links) | GraspSequenceValidator | |
getGroupLinks(const std::string &group_name, std::vector< std::string > &group_links) | GraspSequenceValidator | |
getInterpolatedIK(const std::string &arm_name, const tf::Transform &first_pose, const tf::Vector3 &direction, const double &distance, const std::vector< double > &ik_solution, const bool &reverse, const bool &premultiply, trajectory_msgs::JointTrajectory &traj) | GraspSequenceValidator | [protected] |
getInterpolatedIK(const std::string &arm_name, const tf::Transform &initialTransform, const tf::Quaternion &rot, const std::vector< double > &ikSolutionAtStart, std::vector< double > &ikSolutionAtEnd, trajectory_msgs::JointTrajectory &traj) | GraspSequenceValidator | [protected] |
getPlanningSceneState() | GraspSequenceValidator | [protected] |
GraspSequenceValidator(planning_environment::CollisionModels *cm=NULL, const std::string &plugin_name="") | GraspSequenceValidator | |
GraspTester() | object_manipulator::GraspTester | |
ik_solver_map_ | GraspSequenceValidator | [protected] |
interrupt_function_ | object_manipulator::GraspTester | [protected] |
kinematics_loader_ | GraspSequenceValidator | |
linkPaddingForGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal) | GraspSequenceValidator | [protected, virtual] |
marker_publisher_ | object_manipulator::GraspTester | [protected] |
num_points_ | GraspSequenceValidator | [protected] |
redundancy_ | GraspSequenceValidator | [protected] |
Result(int result_code, bool continuation) | object_manipulator::GraspTester | |
setFeedbackFunction(boost::function< void(size_t)> f) | object_manipulator::GraspTester | |
setInterruptFunction(boost::function< bool()> f) | object_manipulator::GraspTester | |
setMarkerPublisher(GraspMarkerPublisher *pub) | object_manipulator::GraspTester | |
setPlanningSceneState(planning_models::KinematicState *state) | GraspSequenceValidator | [inline] |
state_ | GraspSequenceValidator | [protected] |
testGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp, object_manipulator::GraspExecutionInfo &execution_info) | GraspSequenceValidator | [inline, virtual] |
object_manipulator::GraspTester::testGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal, const manipulation_msgs::Grasp &grasp, GraspExecutionInfo &execution_info)=0 | object_manipulator::GraspTester | [protected, pure virtual] |
testGrasps(const object_manipulation_msgs::PickupGoal &pickup_goal, const std::vector< object_manipulation_msgs::Grasp > &grasps, std::vector< object_manipulator::GraspExecutionInfo > &execution_info, bool return_on_first_hit) | GraspSequenceValidator | [virtual] |
testGrasps(const object_manipulation_msgs::PickupGoal &pickup_goal, const std::vector< object_manipulation_msgs::Grasp > &grasps, double twistAngle, std::vector< GraspSequenceDetails > &execution_info, bool return_on_first_hit) | GraspSequenceValidator | [virtual] |
object_manipulator::GraspTester::testGrasps(const object_manipulation_msgs::PickupGoal &pickup_goal, const std::vector< manipulation_msgs::Grasp > &grasps, std::vector< GraspExecutionInfo > &execution_info, bool return_on_first_hit) | object_manipulator::GraspTester | [virtual] |
vis_marker_array_publisher_ | GraspSequenceValidator | [protected] |
vis_marker_publisher_ | GraspSequenceValidator | [protected] |
~GraspSequenceValidator() | GraspSequenceValidator | |