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
00034
00035
00036 #ifndef _PLACE_TESTER_FAST_
00037 #define _PLACE_TESTER_FAST_
00038
00039 #include "object_manipulator/place_execution/descend_retreat_place.h"
00040 #include <arm_kinematics_constraint_aware/arm_kinematics_solver_constraint_aware.h>
00041
00042
00043 #include <pluginlib/class_loader.h>
00044
00045 namespace object_manipulator {
00046
00047 class PlaceTesterFast : public PlaceTester
00048 {
00049 protected:
00050
00051 geometry_msgs::Vector3 doNegate(const geometry_msgs::Vector3& vec) {
00052 geometry_msgs::Vector3 v;
00053 v.x = - vec.x;
00054 v.y = - vec.y;
00055 v.z = - vec.z;
00056 return v;
00057 }
00058
00059 virtual void testPlace(const object_manipulation_msgs::PlaceGoal &placre_goal,
00060 const geometry_msgs::PoseStamped &place_locations,
00061 PlaceExecutionInfo &execution_info);
00062
00064 std::vector<arm_navigation_msgs::LinkPadding>
00065 linkPaddingForPlace(const object_manipulation_msgs::PlaceGoal &place_goal);
00066
00067 void getGroupLinks(const std::string& group_name,
00068 std::vector<std::string>& group_links);
00069
00070 bool getInterpolatedIK(const std::string& arm_name,
00071 const tf::Transform& first_pose,
00072 const tf::Vector3& direction,
00073 const double& distance,
00074 const std::vector<double>& ik_solution,
00075 const bool& reverse,
00076 const bool& premultiply,
00077 trajectory_msgs::JointTrajectory& traj);
00078
00079 std::map<std::string, arm_kinematics_constraint_aware::ArmKinematicsSolverConstraintAware*> ik_solver_map_;
00080
00081
00082 double consistent_angle_;
00083 unsigned int num_points_;
00084 unsigned int redundancy_;
00085
00086 ros::Publisher vis_marker_array_publisher_;
00087 ros::Publisher vis_marker_publisher_;
00088
00089 planning_environment::CollisionModels* getCollisionModels();
00090 planning_models::KinematicState* getPlanningSceneState();
00091
00092 planning_environment::CollisionModels* cm_;
00093 planning_models::KinematicState* state_;
00094
00095 public:
00097 PlaceTesterFast(planning_environment::CollisionModels* cm = NULL,
00098 const std::string& plugin_name="pr2_arm_kinematics/PR2ArmKinematicsPlugin");
00099
00100 ~PlaceTesterFast();
00101
00102 void setPlanningSceneState(planning_models::KinematicState* state) {
00103 state_ = state;
00104 }
00105
00106 void testPlaces(const object_manipulation_msgs::PlaceGoal &place_goal,
00107 const std::vector<geometry_msgs::PoseStamped> &place_locations,
00108 std::vector<PlaceExecutionInfo> &execution_info,
00109 bool return_on_first_hit);
00110
00111 pluginlib::ClassLoader<kinematics::KinematicsBase> kinematics_loader_;
00112
00113 };
00114
00115 }
00116
00117 #endif