Go to the documentation of this file.00001
00026 #ifndef CONSTRAINED_IK_PLUGIN_H_
00027 #define CONSTRAINED_IK_PLUGIN_H_
00028
00029 #include "constrained_ik/basic_kin.h"
00030 #include "constrained_ik/constrained_ik.h"
00031
00032 #include <ros/ros.h>
00033 #include <moveit/robot_model_loader/robot_model_loader.h>
00034 #include <moveit/kinematics_base/kinematics_base.h>
00035 #include <moveit/planning_scene/planning_scene.h>
00036 #include <moveit_msgs/MoveItErrorCodes.h>
00037
00038 namespace constrained_ik
00039 {
00041 class ConstrainedIKPlugin: public kinematics::KinematicsBase
00042 {
00043 public:
00044 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00045
00046 ConstrainedIKPlugin();
00047
00052 virtual bool isActive() const;
00053
00055 bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00056 const std::vector<double> &ik_seed_state,
00057 std::vector<double> &solution,
00058 moveit_msgs::MoveItErrorCodes &error_code,
00059 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const override;
00060
00062 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00063 const std::vector<double> &ik_seed_state,
00064 double timeout,
00065 std::vector<double> &solution,
00066 moveit_msgs::MoveItErrorCodes &error_code,
00067 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const override;
00068
00070 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00071 const std::vector<double> &ik_seed_state,
00072 double timeout,
00073 const std::vector<double> &consistency_limits,
00074 std::vector<double> &solution,
00075 moveit_msgs::MoveItErrorCodes &error_code,
00076 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const override;
00077
00079 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00080 const std::vector<double> &ik_seed_state,
00081 double timeout,
00082 std::vector<double> &solution,
00083 const IKCallbackFn &solution_callback,
00084 moveit_msgs::MoveItErrorCodes &error_code,
00085 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const override;
00086
00088 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00089 const std::vector<double> &ik_seed_state,
00090 double timeout,
00091 const std::vector<double> &consistency_limits,
00092 std::vector<double> &solution,
00093 const IKCallbackFn &solution_callback,
00094 moveit_msgs::MoveItErrorCodes &error_code,
00095 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const override;
00096
00098 bool getPositionFK(const std::vector<std::string> &link_names,
00099 const std::vector<double> &joint_angles,
00100 std::vector<geometry_msgs::Pose> &poses) const override;
00101
00103 bool initialize(const std::string& robot_description,
00104 const std::string& group_name,
00105 const std::string& base_name,
00106 const std::string& tip_name,
00107 double search_discretization) override;
00108
00110 const std::vector<std::string>& getJointNames() const override;
00111
00113 const std::vector<std::string>& getLinkNames() const override;
00114
00115 protected:
00116
00117 bool active_;
00118 basic_kin::BasicKin kin_;
00119 int dimension_;
00120 std::vector<std::string> link_names_;
00121 std::vector<std::string> joint_names_;
00122 planning_scene::PlanningScenePtr planning_scene_;
00123 moveit::core::RobotStatePtr robot_state_;
00124 robot_model::RobotModelPtr robot_model_ptr_;
00125 boost::shared_ptr<Constrained_IK> solver_;
00126 };
00127
00128 }
00129
00130
00131 #endif