moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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{
55template <typename GeneratorT>
57{
58public:
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
115protected:
116 GeneratorT generator_;
117};
118
119template <typename GeneratorT>
121{
122 if (terminated_)
123 {
124 RCLCPP_ERROR(rclcpp::get_logger("moveit.pilz_industrial_motion_planner.planning_context_base"),
125 "Using solve on a terminated planning context!");
126 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
127 return;
128 }
129 generator_.generate(getPlanningScene(), request_, res);
130}
131
132template <typename GeneratorT>
135{
136 // delegate to regular response
137 planning_interface::MotionPlanResponse undetailed_response;
138 solve(undetailed_response);
139
140 res.description.push_back("plan");
141 res.trajectory.push_back(undetailed_response.trajectory);
142 res.processing_time.push_back(undetailed_response.planning_time);
143
144 res.description.push_back("simplify");
145 res.trajectory.push_back(undetailed_response.trajectory);
146 res.processing_time.push_back(0);
147
148 res.description.push_back("interpolate");
149 res.trajectory.push_back(undetailed_response.trajectory);
150 res.processing_time.push_back(0);
151
152 res.error_code = undetailed_response.error_code;
153}
154
155template <typename GeneratorT>
157{
158 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("moveit.pilz_industrial_motion_planner.planning_context_base"),
159 "Terminate called");
160 terminated_ = true;
161 return true;
162}
163
164template <typename GeneratorT>
166{
167 // No structures that need cleaning
168 return;
169}
170
171} // namespace pilz_industrial_motion_planner
This class combines CartesianLimit and JointLimits into on single class.
PlanningContext for obtaining trajectories.
void solve(planning_interface::MotionPlanResponse &res) override
Calculates a trajectory for the request this context is currently set for.
pilz_industrial_motion_planner::LimitsContainer limits_
Joint limits to be used during planning.
void clear() override
Clear the data structures used by the planner.
void solve(planning_interface::MotionPlanDetailedResponse &res) override
Will return the same trajectory as solve(planning_interface::MotionPlanResponse& res) This function j...
moveit::core::RobotModelConstPtr model_
The robot model.
Representation of a particular planning context – the planning scene and the request are known,...
moveit_msgs::msg::MoveItErrorCodes error_code
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory