moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_execution_manager.h
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 
37 #pragma once
38 
42 #include <moveit_msgs/msg/robot_trajectory.hpp>
43 #include <sensor_msgs/msg/joint_state.hpp>
44 #include <std_msgs/msg/string.hpp>
45 #include <rclcpp/rclcpp.hpp>
47 #include <pluginlib/class_loader.hpp>
48 
49 #include <memory>
50 #include <deque>
51 #include <thread>
52 
53 #include <moveit_trajectory_execution_manager_export.h>
54 
56 {
57 MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager); // Defines TrajectoryExecutionManagerPtr, ConstPtr, WeakPtr... etc
58 
59 // Two modes:
60 // Managed controllers
61 // Unmanaged controllers: given the trajectory,
62 class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager
63 {
64 public:
65  static const std::string EXECUTION_EVENT_TOPIC;
66 
70 
73  using PathSegmentCompleteCallback = std::function<void(std::size_t)>;
74 
77  {
79  std::vector<std::string> controllers_;
80 
81  // The trajectory to execute, split in different parts (by joints), each set of joints corresponding to one
82  // controller
83  std::vector<moveit_msgs::msg::RobotTrajectory> trajectory_parts_;
84  };
85 
87  TrajectoryExecutionManager(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModelConstPtr& robot_model,
88  const planning_scene_monitor::CurrentStateMonitorPtr& csm);
89 
91  TrajectoryExecutionManager(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModelConstPtr& robot_model,
92  const planning_scene_monitor::CurrentStateMonitorPtr& csm, bool manage_controllers);
93 
96 
98  bool isManagingControllers() const;
99 
101  const moveit_controller_manager::MoveItControllerManagerPtr& getControllerManager() const;
102 
104  void processEvent(const std::string& event);
105 
110  bool ensureActiveControllersForGroup(const std::string& group);
111 
116  bool ensureActiveControllersForJoints(const std::vector<std::string>& joints);
117 
121  bool ensureActiveController(const std::string& controller);
122 
126  bool ensureActiveControllers(const std::vector<std::string>& controllers);
127 
129  bool isControllerActive(const std::string& controller);
130 
132  bool areControllersActive(const std::vector<std::string>& controllers);
133 
136  bool push(const moveit_msgs::msg::RobotTrajectory& trajectory, const std::string& controller = "");
137 
140  bool push(const trajectory_msgs::msg::JointTrajectory& trajectory, const std::string& controller = "");
141 
147  bool push(const trajectory_msgs::msg::JointTrajectory& trajectory, const std::vector<std::string>& controllers);
148 
154  bool push(const moveit_msgs::msg::RobotTrajectory& trajectory, const std::vector<std::string>& controllers);
155 
157  const std::vector<TrajectoryExecutionContext*>& getTrajectories() const;
158 
160  void execute(const ExecutionCompleteCallback& callback = ExecutionCompleteCallback(), bool auto_clear = true);
161 
164  void execute(const ExecutionCompleteCallback& callback, const PathSegmentCompleteCallback& part_callback,
165  bool auto_clear = true);
166 
169  moveit_controller_manager::ExecutionStatus executeAndWait(bool auto_clear = true);
170 
173  bool pushAndExecute(const moveit_msgs::msg::RobotTrajectory& trajectory, const std::string& controller = "");
174 
177  bool pushAndExecute(const trajectory_msgs::msg::JointTrajectory& trajectory, const std::string& controller = "");
178 
182  bool pushAndExecute(const sensor_msgs::msg::JointState& state, const std::string& controller = "");
183 
189  bool pushAndExecute(const trajectory_msgs::msg::JointTrajectory& trajectory,
190  const std::vector<std::string>& controllers);
191 
197  bool pushAndExecute(const moveit_msgs::msg::RobotTrajectory& trajectory, const std::vector<std::string>& controllers);
198 
204  bool pushAndExecute(const sensor_msgs::msg::JointState& state, const std::vector<std::string>& controllers);
205 
209 
216  std::pair<int, int> getCurrentExpectedTrajectoryIndex() const;
217 
219  moveit_controller_manager::ExecutionStatus getLastExecutionStatus() const;
220 
222  void stopExecution(bool auto_clear = true);
223 
225  void clear();
226 
229  void enableExecutionDurationMonitoring(bool flag);
230 
233  void setAllowedExecutionDurationScaling(double scaling);
234 
237  void setAllowedGoalDurationMargin(double margin);
238 
241  void setExecutionVelocityScaling(double scaling);
242 
244  void setAllowedStartTolerance(double tolerance);
245 
247  void setWaitForTrajectoryCompletion(bool flag);
248 
249  rclcpp::Node::SharedPtr getControllerManagerNode()
250  {
251  return controller_mgr_node_;
252  }
253 
254 private:
255  struct ControllerInformation
256  {
257  std::string name_;
258  std::set<std::string> joints_;
259  std::set<std::string> overlapping_controllers_;
261  rclcpp::Time last_update_{ 0, 0, RCL_ROS_TIME };
262 
263  bool operator<(ControllerInformation& other) const
264  {
265  if (joints_.size() != other.joints_.size())
266  return joints_.size() < other.joints_.size();
267  return name_ < other.name_;
268  }
269  };
270 
271  void initialize();
272 
273  void reloadControllerInformation();
274 
276  bool validate(const TrajectoryExecutionContext& context) const;
277  bool configure(TrajectoryExecutionContext& context, const moveit_msgs::msg::RobotTrajectory& trajectory,
278  const std::vector<std::string>& controllers);
279 
280  void updateControllersState(const rclcpp::Duration& age);
281  void updateControllerState(const std::string& controller, const rclcpp::Duration& age);
282  void updateControllerState(ControllerInformation& ci, const rclcpp::Duration& age);
283 
284  bool distributeTrajectory(const moveit_msgs::msg::RobotTrajectory& trajectory,
285  const std::vector<std::string>& controllers,
286  std::vector<moveit_msgs::msg::RobotTrajectory>& parts);
287 
288  bool findControllers(const std::set<std::string>& actuated_joints, std::size_t controller_count,
289  const std::vector<std::string>& available_controllers,
290  std::vector<std::string>& selected_controllers);
291  bool checkControllerCombination(std::vector<std::string>& controllers, const std::set<std::string>& actuated_joints);
292  void generateControllerCombination(std::size_t start_index, std::size_t controller_count,
293  const std::vector<std::string>& available_controllers,
294  std::vector<std::string>& selected_controllers,
295  std::vector<std::vector<std::string> >& selected_options,
296  const std::set<std::string>& actuated_joints);
297  bool selectControllers(const std::set<std::string>& actuated_joints,
298  const std::vector<std::string>& available_controllers,
299  std::vector<std::string>& selected_controllers);
300 
301  void executeThread(const ExecutionCompleteCallback& callback, const PathSegmentCompleteCallback& part_callback,
302  bool auto_clear);
303  bool executePart(std::size_t part_index);
304  bool waitForRobotToStop(const TrajectoryExecutionContext& context, double wait_time = 1.0);
305  void continuousExecutionThread();
306 
307  void stopExecutionInternal();
308 
309  void receiveEvent(const std_msgs::msg::String::ConstSharedPtr& event);
310 
311  void loadControllerParams();
312 
313  // Name of this class for logging
314  const std::string name_ = "trajectory_execution_manager";
315 
316  rclcpp::Node::SharedPtr node_;
317  rclcpp::Node::SharedPtr controller_mgr_node_;
318  std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> private_executor_;
319  std::thread private_executor_thread_;
320  moveit::core::RobotModelConstPtr robot_model_;
321  planning_scene_monitor::CurrentStateMonitorPtr csm_;
322  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr event_topic_subscriber_;
323  std::map<std::string, ControllerInformation> known_controllers_;
324  bool manage_controllers_;
325 
326  // thread used to execute trajectories using the execute() command
327  std::unique_ptr<std::thread> execution_thread_;
328 
329  // thread used to execute trajectories using pushAndExecute()
330  std::unique_ptr<std::thread> continuous_execution_thread_;
331 
332  std::mutex execution_state_mutex_;
333  std::mutex continuous_execution_mutex_;
334  std::mutex execution_thread_mutex_;
335 
336  std::condition_variable continuous_execution_condition_;
337 
338  // this condition is used to notify the completion of execution for given trajectories
339  std::condition_variable execution_complete_condition_;
340 
341  moveit_controller_manager::ExecutionStatus last_execution_status_;
342  std::vector<moveit_controller_manager::MoveItControllerHandlePtr> active_handles_;
343  int current_context_;
344  std::vector<rclcpp::Time> time_index_; // used to find current expected trajectory location
345  mutable std::mutex time_index_mutex_;
346  bool execution_complete_;
347 
348  bool stop_continuous_execution_;
349  bool run_continuous_execution_thread_;
350  std::vector<TrajectoryExecutionContext*> trajectories_;
351  std::deque<TrajectoryExecutionContext*> continuous_execution_queue_;
352 
353  std::unique_ptr<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager> > controller_manager_loader_;
354  moveit_controller_manager::MoveItControllerManagerPtr controller_manager_;
355 
356  bool verbose_;
357 
358  bool execution_duration_monitoring_;
359  // 'global' values
360  double allowed_execution_duration_scaling_;
361  double allowed_goal_duration_margin_;
362  // controller-specific values
363  // override the 'global' values
364  std::map<std::string, double> controller_allowed_execution_duration_scaling_;
365  std::map<std::string, double> controller_allowed_goal_duration_margin_;
366 
367  double allowed_start_tolerance_; // joint tolerance for validate(): radians for revolute joints
368  double execution_velocity_scaling_;
369  bool wait_for_trajectory_completion_;
370 
371  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr callback_handler_;
372 };
373 } // namespace trajectory_execution_manager
std::function< void(const moveit_controller_manager::ExecutionStatus &)> ExecutionCompleteCallback
MOVEIT_CLASS_FORWARD(TrajectoryExecutionManager)
Each controller known to MoveIt has a state. This structure describes that controller's state.
Data structure that represents information necessary to execute a trajectory.
std::vector< std::string > controllers_
The controllers to use for executing the different trajectory parts;.
std::vector< std::vector< std::string > > selected_options