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
00037 #include <moveit/planning_request_adapter/planning_request_adapter.h>
00038 #include <moveit/robot_state/conversions.h>
00039 #include <class_loader/class_loader.h>
00040 #include <moveit/trajectory_processing/trajectory_tools.h>
00041 #include <ros/ros.h>
00042
00043 namespace default_planner_request_adapters
00044 {
00045
00046 class FixStartStatePathConstraints : public planning_request_adapter::PlanningRequestAdapter
00047 {
00048 public:
00049
00050 FixStartStatePathConstraints() : planning_request_adapter::PlanningRequestAdapter()
00051 {
00052 }
00053
00054 virtual std::string getDescription() const { return "Fix Start State Path Constraints"; }
00055
00056
00057 virtual bool adaptAndPlan(const PlannerFn &planner,
00058 const planning_scene::PlanningSceneConstPtr& planning_scene,
00059 const planning_interface::MotionPlanRequest &req,
00060 planning_interface::MotionPlanResponse &res,
00061 std::vector<std::size_t> &added_path_index) const
00062 {
00063 ROS_DEBUG("Running '%s'", getDescription().c_str());
00064
00065
00066 robot_state::RobotState start_state = planning_scene->getCurrentState();
00067 robot_state::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
00068
00069
00070 if (planning_scene->isStateValid(start_state, req.group_name) &&
00071 !planning_scene->isStateValid(start_state, req.path_constraints, req.group_name))
00072 {
00073 ROS_INFO("Path constraints not satisfied for start state...");
00074 planning_scene->isStateValid(start_state, req.path_constraints, req.group_name, true);
00075 ROS_INFO("Planning to path constraints...");
00076
00077 planning_interface::MotionPlanRequest req2 = req;
00078 req2.goal_constraints.resize(1);
00079 req2.goal_constraints[0] = req.path_constraints;
00080 req2.path_constraints = moveit_msgs::Constraints();
00081 planning_interface::MotionPlanResponse res2;
00082 bool solved1 = planner(planning_scene, req2, res2);
00083
00084 if (solved1)
00085 {
00086 planning_interface::MotionPlanRequest req3 = req;
00087 ROS_INFO("Planned to path constraints. Resuming original planning request.");
00088
00089
00090 robot_state::robotStateToRobotStateMsg(res2.trajectory_->getLastWayPoint(), req3.start_state);
00091 bool solved2 = planner(planning_scene, req3, res);
00092 res.planning_time_ += res2.planning_time_;
00093
00094 if (solved2)
00095 {
00096
00097 res.trajectory_->append(*res2.trajectory_, 0.0);
00098 return true;
00099 }
00100 else
00101 return false;
00102 }
00103 else
00104 {
00105 ROS_WARN("Unable to plan to path constraints. Running usual motion plan.");
00106 bool result = planner(planning_scene, req, res);
00107 res.planning_time_ += res2.planning_time_;
00108 return result;
00109 }
00110 }
00111 else
00112 {
00113 ROS_DEBUG("Path constraints are OK. Running usual motion plan.");
00114 return planner(planning_scene, req, res);
00115 }
00116 }
00117
00118 };
00119
00120 }
00121
00122 CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStatePathConstraints,
00123 planning_request_adapter::PlanningRequestAdapter);