fix_start_state_path_constraints.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan */
37 
42 #include <ros/ros.h>
43 
45 {
47 {
48 public:
50  {
51  }
52 
53  virtual std::string getDescription() const
54  {
55  return "Fix Start State Path Constraints";
56  }
57 
58  virtual bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
61  std::vector<std::size_t>& added_path_index) const
62  {
63  ROS_DEBUG("Running '%s'", getDescription().c_str());
64 
65  // get the specified start state
66  robot_state::RobotState start_state = planning_scene->getCurrentState();
67  robot_state::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
68 
69  // if the start state is otherwise valid but does not meet path constraints
70  if (planning_scene->isStateValid(start_state, req.group_name) &&
71  !planning_scene->isStateValid(start_state, req.path_constraints, req.group_name))
72  {
73  ROS_INFO("Path constraints not satisfied for start state...");
74  planning_scene->isStateValid(start_state, req.path_constraints, req.group_name, true);
75  ROS_INFO("Planning to path constraints...");
76 
78  req2.goal_constraints.resize(1);
79  req2.goal_constraints[0] = req.path_constraints;
80  req2.path_constraints = moveit_msgs::Constraints();
82  // we call the planner for this additional request, but we do not want to include potential
83  // index information from that call
84  std::vector<std::size_t> added_path_index_temp;
85  added_path_index_temp.swap(added_path_index);
86  bool solved1 = planner(planning_scene, req2, res2);
87  added_path_index_temp.swap(added_path_index);
88 
89  if (solved1)
90  {
92  ROS_INFO("Planned to path constraints. Resuming original planning request.");
93 
94  // extract the last state of the computed motion plan and set it as the new start state
95  robot_state::robotStateToRobotStateMsg(res2.trajectory_->getLastWayPoint(), req3.start_state);
96  bool solved2 = planner(planning_scene, req3, res);
97  res.planning_time_ += res2.planning_time_;
98 
99  if (solved2)
100  {
101  // since we add a prefix, we need to correct any existing index positions
102  for (std::size_t i = 0; i < added_path_index.size(); ++i)
103  added_path_index[i] += res2.trajectory_->getWayPointCount();
104 
105  // we mark the fact we insert a prefix path (we specify the index position we just added)
106  for (std::size_t i = 0; i < res2.trajectory_->getWayPointCount(); ++i)
107  added_path_index.push_back(i);
108 
109  // we need to append the solution paths.
110  res2.trajectory_->append(*res.trajectory_, 0.0);
111  res2.trajectory_->swap(*res.trajectory_);
112  return true;
113  }
114  else
115  return false;
116  }
117  else
118  {
119  ROS_WARN("Unable to plan to path constraints. Running usual motion plan.");
120  bool result = planner(planning_scene, req, res);
121  res.planning_time_ += res2.planning_time_;
122  return result;
123  }
124  }
125  else
126  {
127  ROS_DEBUG("Path constraints are OK. Running usual motion plan.");
128  return planner(planning_scene, req, res);
129  }
130  }
131 };
132 }
133 
robot_trajectory::RobotTrajectoryPtr trajectory_
#define ROS_WARN(...)
#define ROS_INFO(...)
virtual bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const
moveit_msgs::MotionPlanRequest MotionPlanRequest
boost::function< bool(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res)> PlannerFn
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStatePathConstraints, planning_request_adapter::PlanningRequestAdapter)
#define ROS_DEBUG(...)


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:17:33