moveit2
The MoveIt Motion Planning Framework for ROS 2.
pilz_industrial_motion_planner.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 
37 #include <rclcpp/rclcpp.hpp>
38 
41 
44 
45 #include <pluginlib/class_loader.hpp>
46 #include <memory>
47 
49 {
59 {
60 public:
61  ~CommandPlanner() override
62  {
63  }
64 
74  bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
75  const std::string& ns) override;
76 
78  std::string getDescription() const override;
79 
86  void getPlanningAlgorithms(std::vector<std::string>& algs) const override;
87 
97  planning_interface::PlanningContextPtr
98  getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
100  moveit_msgs::msg::MoveItErrorCodes& error_code) const override;
101 
108  bool canServiceRequest(const planning_interface::MotionPlanRequest& req) const override;
109 
117 
123 
124 private:
126  std::unique_ptr<pluginlib::ClassLoader<PlanningContextLoader>> planner_context_loader;
127 
129  std::map<std::string, pilz_industrial_motion_planner::PlanningContextLoaderPtr> context_loader_map_;
130 
132  moveit::core::RobotModelConstPtr model_;
133 
135  std::string namespace_;
136 
138  pilz_industrial_motion_planner::JointLimitsContainer aggregated_limit_active_joints_;
139 
142 };
143 
145 
146 } // namespace pilz_industrial_motion_planner
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
MoveIt Plugin for Planning with Standard Robot Commands This planner is dedicated to return a instanc...
bool canServiceRequest(const planning_interface::MotionPlanRequest &req) const override
Checks if the request can be handled.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pcs) override
Specify the settings to be used for an algorithms.
planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const override
Returns a PlanningContext that can be used to solve(calculate) the trajectory that corresponds to com...
void getPlanningAlgorithms(std::vector< std::string > &algs) const override
Returns the available planning commands.
bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &ns) override
Initializes the planner Upon initialization this planner will look for plugins implementing pilz_indu...
void registerContextLoader(const pilz_industrial_motion_planner::PlanningContextLoaderPtr &planning_context_loader)
Register a PlanningContextLoader to be used by the CommandPlanner.
std::string getDescription() const override
Description of the planner.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
Base class for a MoveIt planner.
MOVEIT_CLASS_FORWARD(CommandPlanner)
std::shared_ptr< PlanningContextLoader > PlanningContextLoaderPtr
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.