Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
object_manipulator::GraspTesterFast Class Reference

#include <grasp_tester_fast.h>

Inheritance diagram for object_manipulator::GraspTesterFast:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void getGroupJoints (const std::string &group_name, std::vector< std::string > &group_links)
void getGroupLinks (const std::string &group_name, std::vector< std::string > &group_links)
 GraspTesterFast (planning_environment::CollisionModels *cm=NULL, const std::string &plugin_name="pr2_arm_kinematics/PR2ArmKinematicsPlugin")
 Also adds a grasp marker at the pre-grasp location.
void setPlanningSceneState (planning_models::KinematicState *state)
virtual void 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)
 Tests a set of grasps and provides their execution info.
 ~GraspTesterFast ()

Public Attributes

pluginlib::ClassLoader
< kinematics::KinematicsBase
kinematics_loader_

Protected Member Functions

planning_environment::CollisionModelsgetCollisionModels ()
bool 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)
planning_models::KinematicStategetPlanningSceneState ()
virtual std::vector
< arm_navigation_msgs::LinkPadding
linkPaddingForGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal)
 Dynamic link padding to be used for grasp operation.
virtual void testGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const manipulation_msgs::Grasp &grasp, GraspExecutionInfo &execution_info)
 Tests a single grasp.

Protected Attributes

planning_environment::CollisionModelscm_
double consistent_angle_
std::map< std::string,
arm_kinematics_constraint_aware::ArmKinematicsSolverConstraintAware * > 
ik_solver_map_
unsigned int num_points_
unsigned int redundancy_
planning_models::KinematicStatestate_
ros::Publisher vis_marker_array_publisher_
ros::Publisher vis_marker_publisher_

Detailed Description

Definition at line 74 of file grasp_tester_fast.h.


Constructor & Destructor Documentation

object_manipulator::GraspTesterFast::GraspTesterFast ( planning_environment::CollisionModels cm = NULL,
const std::string &  plugin_name = "pr2_arm_kinematics/PR2ArmKinematicsPlugin" 
)

Also adds a grasp marker at the pre-grasp location.

Definition at line 137 of file grasp_tester_fast.cpp.

Definition at line 177 of file grasp_tester_fast.cpp.


Member Function Documentation

Definition at line 186 of file grasp_tester_fast.cpp.

void object_manipulator::GraspTesterFast::getGroupJoints ( const std::string &  group_name,
std::vector< std::string > &  group_links 
)

Definition at line 230 of file grasp_tester_fast.cpp.

void object_manipulator::GraspTesterFast::getGroupLinks ( const std::string &  group_name,
std::vector< std::string > &  group_links 
)

Definition at line 220 of file grasp_tester_fast.cpp.

bool object_manipulator::GraspTesterFast::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 
) [protected]

Definition at line 240 of file grasp_tester_fast.cpp.

Definition at line 194 of file grasp_tester_fast.cpp.

Dynamic link padding to be used for grasp operation.

Zero padding on fingertip links

Definition at line 212 of file grasp_tester_fast.cpp.

Definition at line 122 of file grasp_tester_fast.h.

void object_manipulator::GraspTesterFast::testGrasp ( const object_manipulation_msgs::PickupGoal pickup_goal,
const manipulation_msgs::Grasp &  grasp,
GraspExecutionInfo execution_info 
) [protected, virtual]

Tests a single grasp.

Implements object_manipulator::GraspTester.

Definition at line 279 of file grasp_tester_fast.cpp.

void object_manipulator::GraspTesterFast::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 
) [virtual]

Tests a set of grasps and provides their execution info.

Reimplemented from object_manipulator::GraspTester.

Definition at line 283 of file grasp_tester_fast.cpp.


Member Data Documentation

Definition at line 109 of file grasp_tester_fast.h.

Definition at line 99 of file grasp_tester_fast.h.

Definition at line 96 of file grasp_tester_fast.h.

Definition at line 114 of file grasp_tester_fast.h.

Definition at line 100 of file grasp_tester_fast.h.

Definition at line 101 of file grasp_tester_fast.h.

Definition at line 110 of file grasp_tester_fast.h.

Definition at line 103 of file grasp_tester_fast.h.

Definition at line 104 of file grasp_tester_fast.h.


The documentation for this class was generated from the following files:


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Mon Oct 6 2014 02:59:51