moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
40 #include <class_loader/class_loader.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
45 
47 {
48 rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.fix_start_state_path_constraints");
49 
51 {
52 public:
54  {
55  }
56 
57  void initialize(const rclcpp::Node::SharedPtr& /* node */, const std::string& /* parameter_namespace */) override
58  {
59  }
60 
61  std::string getDescription() const override
62  {
63  return "Fix Start State Path Constraints";
64  }
65 
66  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
68  std::vector<std::size_t>& added_path_index) const override
69  {
70  RCLCPP_DEBUG(LOGGER, "Running '%s'", getDescription().c_str());
71 
72  // get the specified start state
73  moveit::core::RobotState start_state = planning_scene->getCurrentState();
74  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
75 
76  // if the start state is otherwise valid but does not meet path constraints
77  if (planning_scene->isStateValid(start_state, req.group_name) &&
78  !planning_scene->isStateValid(start_state, req.path_constraints, req.group_name))
79  {
80  RCLCPP_INFO(LOGGER, "Path constraints not satisfied for start state...");
81  planning_scene->isStateValid(start_state, req.path_constraints, req.group_name, true);
82  RCLCPP_INFO(LOGGER, "Planning to path constraints...");
83 
85  req2.goal_constraints.resize(1);
86  req2.goal_constraints[0] = req.path_constraints;
87  req2.path_constraints = moveit_msgs::msg::Constraints();
89  // we call the planner for this additional request, but we do not want to include potential
90  // index information from that call
91  std::vector<std::size_t> added_path_index_temp;
92  added_path_index_temp.swap(added_path_index);
93  bool solved1 = planner(planning_scene, req2, res2);
94  added_path_index_temp.swap(added_path_index);
95 
96  if (solved1)
97  {
99  RCLCPP_INFO(LOGGER, "Planned to path constraints. Resuming original planning request.");
100 
101  // extract the last state of the computed motion plan and set it as the new start state
102  moveit::core::robotStateToRobotStateMsg(res2.trajectory_->getLastWayPoint(), req3.start_state);
103  bool solved2 = planner(planning_scene, req3, res);
104  res.planning_time_ += res2.planning_time_;
105 
106  if (solved2)
107  {
108  // since we add a prefix, we need to correct any existing index positions
109  for (std::size_t& added_index : added_path_index)
110  added_index += res2.trajectory_->getWayPointCount();
111 
112  // we mark the fact we insert a prefix path (we specify the index position we just added)
113  for (std::size_t i = 0; i < res2.trajectory_->getWayPointCount(); ++i)
114  added_path_index.push_back(i);
115 
116  // we need to append the solution paths.
117  res2.trajectory_->append(*res.trajectory_, 0.0);
118  res2.trajectory_->swap(*res.trajectory_);
119  return true;
120  }
121  else
122  return false;
123  }
124  else
125  {
126  RCLCPP_WARN(LOGGER, "Unable to plan to path constraints. Running usual motion plan.");
127  bool result = planner(planning_scene, req, res);
128  res.planning_time_ += res2.planning_time_;
129  return result;
130  }
131  }
132  else
133  {
134  RCLCPP_DEBUG(LOGGER, "Path constraints are OK. Running usual motion plan.");
135  return planner(planning_scene, req, res);
136  }
137  }
138 };
139 } // namespace default_planner_request_adapters
140 
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 override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
std::string getDescription() const override
Get a short string that identifies the planning request adapter.
void initialize(const rclcpp::Node::SharedPtr &, const std::string &) override
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Generic interface to adapting motion planning requests.
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
robot_trajectory::RobotTrajectoryPtr trajectory_
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)