moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_interface.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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/* Author: Ioan Sucan */
36
38#include <mutex>
39#include <rclcpp/logger.hpp>
40#include <rclcpp/logging.hpp>
41#include <set>
43
44namespace planning_interface
45{
46namespace
47{
48rclcpp::Logger getLogger()
49{
50 return moveit::getLogger("moveit.core.planning_interface");
51}
52} // namespace
53
54namespace
55{
56// keep track of currently active contexts
57struct ActiveContexts
58{
59 std::mutex mutex_;
60 std::set<PlanningContext*> contexts_;
61};
62
63ActiveContexts& getActiveContexts()
64{
65 static ActiveContexts s_ac;
66 return s_ac;
67}
68} // namespace
69
70PlanningContext::PlanningContext(const std::string& name, const std::string& group) : name_(name), group_(group)
71{
72 ActiveContexts& ac = getActiveContexts();
73 std::scoped_lock _(ac.mutex_);
74 ac.contexts_.insert(this);
75}
76
78{
79 ActiveContexts& ac = getActiveContexts();
80 std::scoped_lock _(ac.mutex_);
81 ac.contexts_.erase(this);
82}
83
84void PlanningContext::setPlanningScene(const planning_scene::PlanningSceneConstPtr& planning_scene)
85{
87}
88
90{
91 request_ = request;
92 if (request_.allowed_planning_time <= 0.0)
93 {
94 RCLCPP_INFO(getLogger(), "The timeout for planning must be positive (%lf specified). Assuming one second instead.",
95 request_.allowed_planning_time);
96 request_.allowed_planning_time = 1.0;
97 }
98 if (request_.num_planning_attempts < 0)
99 {
100 RCLCPP_ERROR(getLogger(), "The number of desired planning attempts should be positive. "
101 "Assuming one attempt.");
102 }
103 request_.num_planning_attempts = std::max(1, request_.num_planning_attempts);
104}
105
106bool PlannerManager::initialize(const moveit::core::RobotModelConstPtr& /*unused*/,
107 const rclcpp::Node::SharedPtr& /* unused */, const std::string& /* unused */)
108{
109 return true;
110}
111
113{
114 return "";
115}
116
117PlanningContextPtr PlannerManager::getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
118 const MotionPlanRequest& req) const
119{
120 moveit_msgs::msg::MoveItErrorCodes dummy;
121 return getPlanningContext(planning_scene, req, dummy);
122}
123
124void PlannerManager::getPlanningAlgorithms(std::vector<std::string>& algs) const
125{
126 // nothing by default
127 algs.clear();
128}
129
134
136{
137 ActiveContexts& ac = getActiveContexts();
138 std::scoped_lock _(ac.mutex_);
139 for (PlanningContext* context : ac.contexts_)
140 context->terminate();
141}
142
143} // end of namespace planning_interface
void terminate() const
Request termination, if a solve() function is currently computing plans.
virtual std::string getDescription() const =0
Get a short string that identifies the planning interface.
virtual void getPlanningAlgorithms(std::vector< std::string > &algs) const
Get the names of the known planning algorithms (values that can be filled as planner_id in the planni...
virtual void setPlannerConfigurations(const PlannerConfigurationMap &pcs)
Specify the settings to be used for specific algorithms.
virtual bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const =0
Construct a planning context given the current scene and a planning request. If a problem is encounte...
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
Representation of a particular planning context – the planning scene and the request are known,...
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
MotionPlanRequest request_
The planning request for this context.
void setMotionPlanRequest(const MotionPlanRequest &request)
Set the planning request for this context.
PlanningContext(const std::string &name, const std::string &group)
Construct a planning context named name for the group group.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
This namespace includes the base class for MoveIt planners.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
std::mutex mutex_
std::set< PlanningContext * > contexts_