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 #include <planning_interface/planning_interface.h>
00036 #include <planning_scene/planning_scene.h>
00037 #include <planning_models/robot_model.h>
00038 #include <moveit_msgs/GetMotionPlan.h>
00039 #include <chomp_interface_ros/chomp_interface_ros.h>
00040
00041 #include <boost/shared_ptr.hpp>
00042
00043 #include <pluginlib/class_list_macros.h>
00044
00045 namespace chomp_interface_ros
00046 {
00047
00048 class CHOMPPlanner : public planning_interface::Planner
00049 {
00050 public:
00051 void init(const planning_models::RobotModelConstPtr& model)
00052 {
00053 chomp_interface_.reset(new CHOMPInterfaceROS(model));
00054 }
00055
00056 bool canServiceRequest(const moveit_msgs::GetMotionPlan::Request &req,
00057 planning_interface::PlannerCapability &capabilities) const
00058 {
00059
00060
00061 return true;
00062 }
00063
00064 bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
00065 const moveit_msgs::GetMotionPlan::Request &req,
00066 moveit_msgs::GetMotionPlan::Response &res) const
00067 {
00068 return chomp_interface_->solve(planning_scene, req,
00069 chomp_interface_->getParams(),res);
00070 }
00071
00072 bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
00073 const moveit_msgs::GetMotionPlan::Request &req,
00074 moveit_msgs::MotionPlanDetailedResponse &res) const
00075 {
00076 moveit_msgs::GetMotionPlan::Response res2;
00077 if (chomp_interface_->solve(planning_scene, req,
00078 chomp_interface_->getParams(),res2))
00079 {
00080 res.trajectory_start = res2.trajectory_start;
00081 res.trajectory.push_back(res2.trajectory);
00082 res.description.push_back("plan");
00083 res.processing_time.push_back(res2.planning_time);
00084 return true;
00085 }
00086 else
00087 return false;
00088 }
00089
00090 std::string getDescription() const { return "CHOMP"; }
00091
00092 void getPlanningAlgorithms(std::vector<std::string> &algs) const
00093 {
00094 algs.resize(1);
00095 algs[0] = "CHOMP";
00096 }
00097
00098 void terminate() const
00099 {
00100
00101 }
00102
00103 private:
00104 boost::shared_ptr<CHOMPInterfaceROS> chomp_interface_;
00105 };
00106
00107 }
00108
00109 PLUGINLIB_EXPORT_CLASS( chomp_interface_ros::CHOMPPlanner, planning_interface::Planner);