moveit2
The MoveIt Motion Planning Framework for ROS 2.
moveit_cpp.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, PickNik 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 PickNik Inc. 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: Henning Kayser
36  Desc: A high level interface that does not require the use of ROS Actions, Services, and Messages to access the
37  core MoveIt functionality
38 */
39 
40 #pragma once
41 
42 #include <rclcpp/rclcpp.hpp>
48 #include <tf2_ros/buffer.h>
49 
50 namespace moveit_cpp
51 {
52 MOVEIT_CLASS_FORWARD(MoveItCpp); // Defines MoveItCppPtr, ConstPtr, WeakPtr... etc
53 
54 class MoveItCpp
55 {
56 public:
59  {
60  void load(const rclcpp::Node::SharedPtr& node)
61  {
62  const std::string ns = "planning_scene_monitor_options";
63  node->get_parameter_or(ns + ".name", name, std::string("planning_scene_monitor"));
64  node->get_parameter_or(ns + ".robot_description", robot_description, std::string("robot_description"));
65  node->get_parameter_or(ns + ".joint_state_topic", joint_state_topic,
67  node->get_parameter_or(ns + ".attached_collision_object_topic", attached_collision_object_topic,
69  node->get_parameter_or(ns + ".monitored_planning_scene_topic", monitored_planning_scene_topic,
71  node->get_parameter_or(ns + ".publish_planning_scene_topic", publish_planning_scene_topic,
73  node->get_parameter_or(ns + ".wait_for_initial_state_timeout", wait_for_initial_state_timeout, 0.0);
74  }
75  std::string name;
76  std::string robot_description;
77  std::string joint_state_topic;
82  };
83 
86  {
87  void load(const rclcpp::Node::SharedPtr& node)
88  {
89  const std::string ns = "planning_pipelines.";
90  node->get_parameter(ns + "pipeline_names", pipeline_names);
91  node->get_parameter(ns + "namespace", parent_namespace);
92  }
93  std::vector<std::string> pipeline_names;
94  std::string parent_namespace;
95  };
96 
98  struct Options
99  {
100  Options(const rclcpp::Node::SharedPtr& node)
101  {
104  }
105 
108  };
109 
111  [[deprecated("Passing tf2_ros::Buffer to MoveItCpp's constructor is deprecated")]] MoveItCpp(
112  const rclcpp::Node::SharedPtr& node, const std::shared_ptr<tf2_ros::Buffer>& /* unused */)
113  : MoveItCpp(node)
114  {
115  }
116  MoveItCpp(const rclcpp::Node::SharedPtr& node);
117  [[deprecated("Passing tf2_ros::Buffer to MoveItCpp's constructor is deprecated")]] MoveItCpp(
118  const rclcpp::Node::SharedPtr& node, const Options& options, const std::shared_ptr<tf2_ros::Buffer>& /* unused */)
119  : MoveItCpp(node, options)
120  {
121  }
122  MoveItCpp(const rclcpp::Node::SharedPtr& node, const Options& options);
123 
129  MoveItCpp(const MoveItCpp&) = delete;
130  MoveItCpp& operator=(const MoveItCpp&) = delete;
131 
132  MoveItCpp(MoveItCpp&& other) = default;
133  MoveItCpp& operator=(MoveItCpp&& other) = default;
134 
136  ~MoveItCpp();
137 
139  moveit::core::RobotModelConstPtr getRobotModel() const;
140 
142  const rclcpp::Node::SharedPtr& getNode() const;
143 
146  bool getCurrentState(moveit::core::RobotStatePtr& current_state, double wait_seconds);
147 
150  moveit::core::RobotStatePtr getCurrentState(double wait_seconds = 0.0);
151 
153  const std::map<std::string, planning_pipeline::PlanningPipelinePtr>& getPlanningPipelines() const;
154 
157  std::set<std::string> getPlanningPipelineNames(const std::string& group_name = "") const;
158 
160  const planning_scene_monitor::PlanningSceneMonitorPtr& getPlanningSceneMonitor() const;
161  planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitorNonConst();
162 
163  const std::shared_ptr<tf2_ros::Buffer>& getTFBuffer() const;
164 
166  const trajectory_execution_manager::TrajectoryExecutionManagerPtr& getTrajectoryExecutionManager() const;
167  trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst();
168 
171  moveit_controller_manager::ExecutionStatus execute(const std::string& group_name,
172  const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
173  bool blocking = true);
174 
175 private:
176  // Core properties and instances
177  rclcpp::Node::SharedPtr node_;
178  moveit::core::RobotModelConstPtr robot_model_;
179  planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
180 
181  // Planning
182  std::map<std::string, planning_pipeline::PlanningPipelinePtr> planning_pipelines_;
183  std::map<std::string, std::set<std::string>> groups_pipelines_map_;
184  std::map<std::string, std::set<std::string>> groups_algorithms_map_;
185 
186  // Execution
187  trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_;
188 
190  void clearContents();
191 
193  bool loadPlanningSceneMonitor(const PlanningSceneMonitorOptions& options);
194 
196  bool loadPlanningPipelines(const PlanningPipelineOptions& options);
197 };
198 } // namespace moveit_cpp
199 
200 namespace moveit
201 {
203 {
204 using MoveItCpp [[deprecated("use moveit_cpp")]] = moveit_cpp::MoveItCpp;
205 [[deprecated("use moveit_cpp")]] MOVEIT_DECLARE_PTR(MoveItCpp, moveit_cpp::MoveItCpp);
206 } // namespace planning_interface
207 } // namespace moveit
MoveItCpp(MoveItCpp &&other)=default
const std::shared_ptr< tf2_ros::Buffer > & getTFBuffer() const
Definition: moveit_cpp.cpp:277
MoveItCpp & operator=(MoveItCpp &&other)=default
moveit::core::RobotModelConstPtr getRobotModel() const
Get the RobotModel object.
Definition: moveit_cpp.cpp:179
moveit_controller_manager::ExecutionStatus execute(const std::string &group_name, const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, bool blocking=true)
Execute a trajectory on the planning group specified by group_name using the trajectory execution man...
Definition: moveit_cpp.cpp:248
MoveItCpp & operator=(const MoveItCpp &)=delete
std::set< std::string > getPlanningPipelineNames(const std::string &group_name="") const
Get the names of all loaded planning pipelines. Specify group_name to filter the results by planning ...
Definition: moveit_cpp.cpp:215
const std::map< std::string, planning_pipeline::PlanningPipelinePtr > & getPlanningPipelines() const
Get all loaded planning pipeline instances mapped to their reference names.
Definition: moveit_cpp.cpp:210
~MoveItCpp()
Destructor.
Definition: moveit_cpp.cpp:86
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager() const
Get the stored instance of the trajectory execution manager.
Definition: moveit_cpp.cpp:237
MoveItCpp(const rclcpp::Node::SharedPtr &node, const Options &options, const std::shared_ptr< tf2_ros::Buffer > &)
Definition: moveit_cpp.h:117
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor() const
Get the stored instance of the planning scene monitor.
Definition: moveit_cpp.cpp:227
bool getCurrentState(moveit::core::RobotStatePtr &current_state, double wait_seconds)
Get the current state queried from the current state monitor.
Definition: moveit_cpp.cpp:189
planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitorNonConst()
Definition: moveit_cpp.cpp:232
const rclcpp::Node::SharedPtr & getNode() const
Get the ROS node this instance operates on.
Definition: moveit_cpp.cpp:184
MoveItCpp(const MoveItCpp &)=delete
This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy....
MoveItCpp(const rclcpp::Node::SharedPtr &node, const std::shared_ptr< tf2_ros::Buffer > &)
Constructor.
Definition: moveit_cpp.h:111
trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst()
Definition: moveit_cpp.cpp:242
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
The name of the topic used by default for receiving full planning scenes or planning scene diffs.
static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC
The name of the topic used by default for attached collision objects.
static const std::string DEFAULT_JOINT_STATES_TOPIC
The name of the topic used by default for receiving joint states.
moveit_cpp::MoveItCpp MoveItCpp
Definition: moveit_cpp.h:204
MOVEIT_DECLARE_PTR(MoveItCpp, moveit_cpp::MoveItCpp)
MOVEIT_CLASS_FORWARD(MoveItCpp)
Main namespace for MoveIt.
Definition: exceptions.h:43
This namespace includes the base class for MoveIt planners.
Parameter container for initializing MoveItCpp.
Definition: moveit_cpp.h:99
PlanningPipelineOptions planning_pipeline_options
Definition: moveit_cpp.h:107
Options(const rclcpp::Node::SharedPtr &node)
Definition: moveit_cpp.h:100
PlanningSceneMonitorOptions planning_scene_monitor_options
Definition: moveit_cpp.h:106
struct contains the the variables used for loading the planning pipeline
Definition: moveit_cpp.h:86
void load(const rclcpp::Node::SharedPtr &node)
Definition: moveit_cpp.h:87
std::vector< std::string > pipeline_names
Definition: moveit_cpp.h:93
Specification of options to use when constructing the MoveItCpp class.
Definition: moveit_cpp.h:59
void load(const rclcpp::Node::SharedPtr &node)
Definition: moveit_cpp.h:60