moveit2
The MoveIt Motion Planning Framework for ROS 2.
moveit_cpp.cpp
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 
37 #include <stdexcept>
38 
41 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
42 #include <geometry_msgs/msg/quaternion_stamped.hpp>
43 
44 namespace moveit_cpp
45 {
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros_planning_interface.moveit_cpp");
47 constexpr char PLANNING_PLUGIN_PARAM[] = "planning_plugin";
48 
49 MoveItCpp::MoveItCpp(const rclcpp::Node::SharedPtr& node) : MoveItCpp(node, Options(node))
50 {
51 }
52 
53 MoveItCpp::MoveItCpp(const rclcpp::Node::SharedPtr& node, const Options& options) : node_(node)
54 {
55  // Configure planning scene monitor
56  if (!loadPlanningSceneMonitor(options.planning_scene_monitor_options))
57  {
58  const std::string error = "Unable to configure planning scene monitor";
59  RCLCPP_FATAL_STREAM(LOGGER, error);
60  throw std::runtime_error(error);
61  }
62 
63  robot_model_ = planning_scene_monitor_->getRobotModel();
64  if (!robot_model_)
65  {
66  const std::string error = "Unable to construct robot model. Please make sure all needed information is on the "
67  "parameter server.";
68  RCLCPP_FATAL_STREAM(LOGGER, error);
69  throw std::runtime_error(error);
70  }
71 
72  bool load_planning_pipelines = true;
73  if (load_planning_pipelines && !loadPlanningPipelines(options.planning_pipeline_options))
74  {
75  const std::string error = "Failed to load planning pipelines from parameter server";
76  RCLCPP_FATAL_STREAM(LOGGER, error);
77  throw std::runtime_error(error);
78  }
79 
80  trajectory_execution_manager_ = std::make_shared<trajectory_execution_manager::TrajectoryExecutionManager>(
81  node_, robot_model_, planning_scene_monitor_->getStateMonitor());
82 
83  RCLCPP_DEBUG(LOGGER, "MoveItCpp running");
84 }
85 
87 {
88  RCLCPP_INFO(LOGGER, "Deleting MoveItCpp");
89  clearContents();
90 }
91 
92 bool MoveItCpp::loadPlanningSceneMonitor(const PlanningSceneMonitorOptions& options)
93 {
94  planning_scene_monitor_ =
95  std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node_, options.robot_description, options.name);
96  // Allows us to synchronize to Rviz and also publish collision objects to ourselves
97  RCLCPP_DEBUG(LOGGER, "Configuring Planning Scene Monitor");
98  if (planning_scene_monitor_->getPlanningScene())
99  {
100  // Start state and scene monitors
101  RCLCPP_INFO(LOGGER, "Listening to '%s' for joint states", options.joint_state_topic.c_str());
102  // Subscribe to JointState sensor messages
103  planning_scene_monitor_->startStateMonitor(options.joint_state_topic, options.attached_collision_object_topic);
104  // Publish planning scene updates to remote monitors like RViz
105  planning_scene_monitor_->startPublishingPlanningScene(planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE,
106  options.monitored_planning_scene_topic);
107  // Monitor and apply planning scene updates from remote publishers like the PlanningSceneInterface
108  planning_scene_monitor_->startSceneMonitor(options.publish_planning_scene_topic);
109  // Monitor requests for changes in the collision environment
110  planning_scene_monitor_->startWorldGeometryMonitor();
111  }
112  else
113  {
114  RCLCPP_ERROR(LOGGER, "Planning scene not configured");
115  return false;
116  }
117 
118  // Wait for complete state to be received
119  if (options.wait_for_initial_state_timeout > 0.0)
120  {
121  return planning_scene_monitor_->getStateMonitor()->waitForCurrentState(node_->now(),
122  options.wait_for_initial_state_timeout);
123  }
124 
125  return true;
126 }
127 
128 bool MoveItCpp::loadPlanningPipelines(const PlanningPipelineOptions& options)
129 {
130  // TODO(henningkayser): Use parent namespace for planning pipeline config lookup
131  // ros::NodeHandle node_handle(options.parent_namespace.empty() ? "~" : options.parent_namespace);
132  for (const auto& planning_pipeline_name : options.pipeline_names)
133  {
134  if (planning_pipelines_.count(planning_pipeline_name) > 0)
135  {
136  RCLCPP_WARN(LOGGER, "Skipping duplicate entry for planning pipeline '%s'.", planning_pipeline_name.c_str());
137  continue;
138  }
139  RCLCPP_INFO(LOGGER, "Loading planning pipeline '%s'", planning_pipeline_name.c_str());
140  planning_pipeline::PlanningPipelinePtr pipeline;
141  pipeline = std::make_shared<planning_pipeline::PlanningPipeline>(robot_model_, node_, planning_pipeline_name,
143 
144  if (!pipeline->getPlannerManager())
145  {
146  RCLCPP_ERROR(LOGGER, "Failed to initialize planning pipeline '%s'.", planning_pipeline_name.c_str());
147  continue;
148  }
149 
150  planning_pipelines_[planning_pipeline_name] = pipeline;
151  }
152 
153  if (planning_pipelines_.empty())
154  {
155  RCLCPP_ERROR(LOGGER, "Failed to load any planning pipelines.");
156  return false;
157  }
158 
159  // Retrieve group/pipeline mapping for faster lookup
160  std::vector<std::string> group_names = robot_model_->getJointModelGroupNames();
161  for (const auto& pipeline_entry : planning_pipelines_)
162  {
163  for (const auto& group_name : group_names)
164  {
165  const auto& pipeline = pipeline_entry.second;
166  for (const auto& planner_configuration : pipeline->getPlannerManager()->getPlannerConfigurations())
167  {
168  if (planner_configuration.second.group == group_name)
169  {
170  groups_pipelines_map_[group_name].insert(pipeline_entry.first);
171  }
172  }
173  }
174  }
175 
176  return true;
177 }
178 
179 moveit::core::RobotModelConstPtr MoveItCpp::getRobotModel() const
180 {
181  return robot_model_;
182 }
183 
184 const rclcpp::Node::SharedPtr& MoveItCpp::getNode() const
185 {
186  return node_;
187 }
188 
189 bool MoveItCpp::getCurrentState(moveit::core::RobotStatePtr& current_state, double wait_seconds)
190 {
191  if (wait_seconds > 0.0 && !planning_scene_monitor_->getStateMonitor()->waitForCurrentState(node_->now(), wait_seconds))
192  {
193  RCLCPP_ERROR(LOGGER, "Did not receive robot state");
194  return false;
195  }
196  { // Lock planning scene
197  planning_scene_monitor::LockedPlanningSceneRO scene(planning_scene_monitor_);
198  current_state = std::make_shared<moveit::core::RobotState>(scene->getCurrentState());
199  } // Unlock planning scene
200  return true;
201 }
202 
203 moveit::core::RobotStatePtr MoveItCpp::getCurrentState(double wait)
204 {
205  moveit::core::RobotStatePtr current_state;
206  getCurrentState(current_state, wait);
207  return current_state;
208 }
209 
210 const std::map<std::string, planning_pipeline::PlanningPipelinePtr>& MoveItCpp::getPlanningPipelines() const
211 {
212  return planning_pipelines_;
213 }
214 
215 std::set<std::string> MoveItCpp::getPlanningPipelineNames(const std::string& group_name) const
216 {
217  if (group_name.empty() || groups_pipelines_map_.count(group_name) == 0)
218  {
219  RCLCPP_ERROR(LOGGER, "No planning pipelines loaded for group '%s'. Check planning pipeline and controller setup.",
220  group_name.c_str());
221  return {}; // empty
222  }
223 
224  return groups_pipelines_map_.at(group_name);
225 }
226 
227 const planning_scene_monitor::PlanningSceneMonitorPtr& MoveItCpp::getPlanningSceneMonitor() const
228 {
229  return planning_scene_monitor_;
230 }
231 
232 planning_scene_monitor::PlanningSceneMonitorPtr MoveItCpp::getPlanningSceneMonitorNonConst()
233 {
234  return planning_scene_monitor_;
235 }
236 
237 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& MoveItCpp::getTrajectoryExecutionManager() const
238 {
239  return trajectory_execution_manager_;
240 }
241 
242 trajectory_execution_manager::TrajectoryExecutionManagerPtr MoveItCpp::getTrajectoryExecutionManagerNonConst()
243 {
244  return trajectory_execution_manager_;
245 }
246 
248 MoveItCpp::execute(const std::string& group_name, const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
249  bool blocking)
250 {
251  if (!robot_trajectory)
252  {
253  RCLCPP_ERROR(LOGGER, "Robot trajectory is undefined");
255  }
256 
257  // Check if there are controllers that can handle the execution
258  if (!trajectory_execution_manager_->ensureActiveControllersForGroup(group_name))
259  {
260  RCLCPP_ERROR(LOGGER, "Execution failed! No active controllers configured for group '%s'", group_name.c_str());
262  }
263 
264  // Execute trajectory
265  moveit_msgs::msg::RobotTrajectory robot_trajectory_msg;
266  robot_trajectory->getRobotTrajectoryMsg(robot_trajectory_msg);
267  if (blocking)
268  {
269  trajectory_execution_manager_->push(robot_trajectory_msg);
270  trajectory_execution_manager_->execute();
271  return trajectory_execution_manager_->waitForExecution();
272  }
273  trajectory_execution_manager_->pushAndExecute(robot_trajectory_msg);
275 }
276 
277 const std::shared_ptr<tf2_ros::Buffer>& MoveItCpp::getTFBuffer() const
278 {
279  return planning_scene_monitor_->getTFClient();
280 }
281 
282 void MoveItCpp::clearContents()
283 {
284  planning_scene_monitor_.reset();
285  robot_model_.reset();
286  planning_pipelines_.clear();
287 }
288 } // namespace moveit_cpp
const std::shared_ptr< tf2_ros::Buffer > & getTFBuffer() const
Definition: moveit_cpp.cpp:277
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
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
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 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
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
constexpr char PLANNING_PLUGIN_PARAM[]
Definition: moveit_cpp.cpp:47
scene
Definition: pick.py:52
const rclcpp::Logger LOGGER
Definition: async_test.h:31
Parameter container for initializing MoveItCpp.
Definition: moveit_cpp.h:99