moveit2
The MoveIt Motion Planning Framework for ROS 2.
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>
42 
43 namespace planning_interface
44 {
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_planning_interface.planning_interface");
46 
47 namespace
48 {
49 // keep track of currently active contexts
50 struct ActiveContexts
51 {
52  std::mutex mutex_;
53  std::set<PlanningContext*> contexts_;
54 };
55 
56 static ActiveContexts& getActiveContexts()
57 {
58  static ActiveContexts ac;
59  return ac;
60 }
61 } // namespace
62 
63 PlanningContext::PlanningContext(const std::string& name, const std::string& group) : name_(name), group_(group)
64 {
65  ActiveContexts& ac = getActiveContexts();
66  std::scoped_lock _(ac.mutex_);
67  ac.contexts_.insert(this);
68 }
69 
71 {
72  ActiveContexts& ac = getActiveContexts();
73  std::scoped_lock _(ac.mutex_);
74  ac.contexts_.erase(this);
75 }
76 
77 void PlanningContext::setPlanningScene(const planning_scene::PlanningSceneConstPtr& planning_scene)
78 {
80 }
81 
83 {
84  request_ = request;
85  if (request_.allowed_planning_time <= 0.0)
86  {
87  RCLCPP_INFO(LOGGER, "The timeout for planning must be positive (%lf specified). Assuming one second instead.",
88  request_.allowed_planning_time);
89  request_.allowed_planning_time = 1.0;
90  }
91  if (request_.num_planning_attempts < 0)
92  RCLCPP_ERROR(LOGGER, "The number of desired planning attempts should be positive. "
93  "Assuming one attempt.");
94  request_.num_planning_attempts = std::max(1, request_.num_planning_attempts);
95 }
96 
97 bool PlannerManager::initialize(const moveit::core::RobotModelConstPtr& /*unused*/,
98  const rclcpp::Node::SharedPtr& /* unused */, const std::string& /* unused */)
99 {
100  return true;
101 }
102 
104 {
105  return "";
106 }
107 
108 PlanningContextPtr PlannerManager::getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
109  const MotionPlanRequest& req) const
110 {
111  moveit_msgs::msg::MoveItErrorCodes dummy;
112  return getPlanningContext(planning_scene, req, dummy);
113 }
114 
115 void PlannerManager::getPlanningAlgorithms(std::vector<std::string>& algs) const
116 {
117  // nothing by default
118  algs.clear();
119 }
120 
122 {
123  config_settings_ = pcs;
124 }
125 
127 {
128  ActiveContexts& ac = getActiveContexts();
129  std::scoped_lock _(ac.mutex_);
130  for (PlanningContext* context : ac.contexts_)
131  context->terminate();
132 }
133 
134 } // end of namespace planning_interface
void terminate() const
Request termination, if a solve() function is currently computing plans.
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 std::string getDescription() const
Get.
virtual void setPlannerConfigurations(const PlannerConfigurationMap &pcs)=0
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.
virtual bool terminate()=0
If solve() is running, terminate the computation. Return false if termination not possible....
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.
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.
name
Definition: setup.py:7
std::mutex mutex_
std::set< PlanningContext * > contexts_