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 {
46 class FixStartStatePathConstraints : public planning_request_adapter::PlanningRequestAdapter
47 {
48 public:
50  {
51  }
52 
53  void initialize(const ros::NodeHandle& /*nh*/) override
54  {
55  }
56 
57  std::string getDescription() const override
58  {
59  return "Fix Start State Path Constraints";
60  }
61 
62  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
64  std::vector<std::size_t>& added_path_index) const override
65  {
66  ROS_DEBUG("Running '%s'", getDescription().c_str());
67 
68  // get the specified start state
69  moveit::core::RobotState start_state = planning_scene->getCurrentState();
70  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
71 
72  // if the start state is otherwise valid but does not meet path constraints
73  if (planning_scene->isStateValid(start_state, req.group_name) &&
74  !planning_scene->isStateValid(start_state, req.path_constraints, req.group_name))
75  {
76  ROS_INFO("Path constraints not satisfied for start state...");
77  planning_scene->isStateValid(start_state, req.path_constraints, req.group_name, true);
78  ROS_INFO("Planning to path constraints...");
79 
81  req2.goal_constraints.resize(1);
82  req2.goal_constraints[0] = req.path_constraints;
83  req2.path_constraints = moveit_msgs::Constraints();
85  // we call the planner for this additional request, but we do not want to include potential
86  // index information from that call
87  std::vector<std::size_t> added_path_index_temp;
88  added_path_index_temp.swap(added_path_index);
89  bool solved1 = planner(planning_scene, req2, res2);
90  added_path_index_temp.swap(added_path_index);
91 
92  if (solved1)
93  {
95  ROS_INFO("Planned to path constraints. Resuming original planning request.");
96 
97  // extract the last state of the computed motion plan and set it as the new start state
98  moveit::core::robotStateToRobotStateMsg(res2.trajectory_->getLastWayPoint(), req3.start_state);
99  bool solved2 = planner(planning_scene, req3, res);
100  res.planning_time_ += res2.planning_time_;
101 
102  if (solved2)
103  {
104  // since we add a prefix, we need to correct any existing index positions
105  for (std::size_t& added_index : added_path_index)
106  added_index += res2.trajectory_->getWayPointCount();
107 
108  // we mark the fact we insert a prefix path (we specify the index position we just added)
109  for (std::size_t i = 0; i < res2.trajectory_->getWayPointCount(); ++i)
110  added_path_index.push_back(i);
111 
112  // we need to append the solution paths.
113  res2.trajectory_->append(*res.trajectory_, 0.0);
114  res2.trajectory_->swap(*res.trajectory_);
115  return true;
116  }
117  else
118  return false;
119  }
120  else
121  {
122  ROS_WARN("Unable to plan to path constraints.");
123  res.error_code_.val = moveit_msgs::MoveItErrorCodes::START_STATE_VIOLATES_PATH_CONSTRAINTS;
124  res.planning_time_ = res2.planning_time_;
125  return false;
126  }
127  }
128  else
129  {
130  ROS_DEBUG("Path constraints are OK. Running usual motion plan.");
131  return planner(planning_scene, req, res);
132  }
133  }
134 };
135 } // namespace default_planner_request_adapters
136 
default_planner_request_adapters::FixStartStatePathConstraints::initialize
void initialize(const ros::NodeHandle &) override
Definition: fix_start_state_path_constraints.cpp:119
default_planner_request_adapters::FixStartStatePathConstraints::FixStartStatePathConstraints
FixStartStatePathConstraints()
Definition: fix_start_state_path_constraints.cpp:115
planning_interface::MotionPlanResponse
CLASS_LOADER_REGISTER_CLASS
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStatePathConstraints, planning_request_adapter::PlanningRequestAdapter)
planning_request_adapter.h
ros.h
planning_interface::MotionPlanResponse::error_code_
moveit::core::MoveItErrorCode error_code_
ROS_DEBUG
#define ROS_DEBUG(...)
moveit::core::RobotState
planning_request_adapter::PlanningRequestAdapter
planning_interface::MotionPlanResponse::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
ROS_WARN
#define ROS_WARN(...)
class_loader.hpp
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
default_planner_request_adapters::FixStartStatePathConstraints
Definition: fix_start_state_path_constraints.cpp:79
planning_request_adapter::PlanningRequestAdapter::PlanningRequestAdapter
PlanningRequestAdapter()
default_planner_request_adapters::FixStartStatePathConstraints::adaptAndPlan
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
Definition: fix_start_state_path_constraints.cpp:128
default_planner_request_adapters
Definition: add_iterative_spline_parameterization.cpp:43
planning_request_adapter::PlanningRequestAdapter::PlannerFn
boost::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
planning_request_adapter
default_planner_request_adapters::FixStartStatePathConstraints::getDescription
std::string getDescription() const override
Definition: fix_start_state_path_constraints.cpp:123
conversions.h
trajectory_tools.h
planning_interface::MotionPlanResponse::planning_time_
double planning_time_
ROS_INFO
#define ROS_INFO(...)
planning_scene
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
ros::NodeHandle
moveit::core::robotStateMsgToRobotState
bool robotStateMsgToRobotState(const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:03