moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_context_base.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #pragma once
36 
39 
40 #include <rclcpp/rclcpp.hpp>
41 
46 
47 #include <atomic>
48 #include <thread>
49 
51 {
55 template <typename GeneratorT>
57 {
58 public:
59  PlanningContextBase<GeneratorT>(const std::string& name, const std::string& group,
60  const moveit::core::RobotModelConstPtr& model,
63  , terminated_(false)
64  , model_(model)
65  , limits_(limits)
66  , generator_(model, limits_, group)
67  {
68  }
69 
71  {
72  }
73 
82 
93 
99  bool terminate() override;
100 
104  void clear() override;
105 
107  std::atomic_bool terminated_;
108 
110  moveit::core::RobotModelConstPtr model_;
111 
114 
115 protected:
116  GeneratorT generator_;
117 };
118 
119 template <typename GeneratorT>
121 {
122  if (!terminated_)
123  {
124  // Use current state as start state if not set
125  if (request_.start_state.joint_state.name.empty())
126  {
127  moveit_msgs::msg::RobotState current_state;
128  moveit::core::robotStateToRobotStateMsg(getPlanningScene()->getCurrentState(), current_state);
129  request_.start_state = current_state;
130  }
131  bool result = generator_.generate(getPlanningScene(), request_, res);
132  return result;
133  // res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
134  // return false; // TODO
135  }
136 
137  RCLCPP_ERROR(rclcpp::get_logger("moveit.pilz_industrial_motion_planner.planning_context_base"),
138  "Using solve on a terminated planning context!");
139  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
140  return false;
141 }
142 
143 template <typename GeneratorT>
146 {
147  // delegate to regular response
148  planning_interface::MotionPlanResponse undetailed_response;
149  bool result = solve(undetailed_response);
150 
151  res.description_.push_back("plan");
152  res.trajectory_.push_back(undetailed_response.trajectory_);
153  res.processing_time_.push_back(undetailed_response.planning_time_);
154 
155  res.description_.push_back("simplify");
156  res.trajectory_.push_back(undetailed_response.trajectory_);
157  res.processing_time_.push_back(0);
158 
159  res.description_.push_back("interpolate");
160  res.trajectory_.push_back(undetailed_response.trajectory_);
161  res.processing_time_.push_back(0);
162 
163  res.error_code_ = undetailed_response.error_code_;
164  return result;
165 }
166 
167 template <typename GeneratorT>
169 {
170  RCLCPP_DEBUG_STREAM(rclcpp::get_logger("moveit.pilz_industrial_motion_planner.planning_context_base"),
171  "Terminate called");
172  terminated_ = true;
173  return true;
174 }
175 
176 template <typename GeneratorT>
178 {
179  // No structures that need cleaning
180  return;
181 }
182 
183 } // namespace pilz_industrial_motion_planner
This class combines CartesianLimit and JointLimits into on single class.
PlanningContext for obtaining trajectories.
pilz_industrial_motion_planner::LimitsContainer limits_
Joint limits to be used during planning.
bool solve(planning_interface::MotionPlanResponse &res) override
Calculates a trajectory for the request this context is currently set for.
bool solve(planning_interface::MotionPlanDetailedResponse &res) override
Will return the same trajectory as solve(planning_interface::MotionPlanResponse& res) This function j...
void clear() override
Clear the data structures used by the planner.
moveit::core::RobotModelConstPtr model_
The robot model.
Representation of a particular planning context – the planning scene and the request are known,...
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.
name
Definition: setup.py:7
moveit_msgs::msg::MoveItErrorCodes error_code_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
moveit_msgs::msg::MoveItErrorCodes error_code_