moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_execution_manager.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 
39 #include <geometric_shapes/check_isometry.h>
40 #include <tf2_eigen/tf2_eigen.hpp>
41 
43 {
44 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.trajectory_execution_manager");
45 
46 const std::string TrajectoryExecutionManager::EXECUTION_EVENT_TOPIC = "trajectory_execution_event";
47 
48 static const auto DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE = rclcpp::Duration::from_seconds(1);
49 static const double DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN = 0.5; // allow 0.5s more than the expected execution time
50  // before triggering a trajectory cancel (applied
51  // after scaling)
52 static const double DEFAULT_CONTROLLER_GOAL_DURATION_SCALING =
53  1.1; // allow the execution of a trajectory to take more time than expected (scaled by a value > 1)
54 
55 TrajectoryExecutionManager::TrajectoryExecutionManager(const rclcpp::Node::SharedPtr& node,
56  const moveit::core::RobotModelConstPtr& robot_model,
57  const planning_scene_monitor::CurrentStateMonitorPtr& csm)
58  : node_(node), robot_model_(robot_model), csm_(csm)
59 {
60  if (!node_->get_parameter("moveit_manage_controllers", manage_controllers_))
61  manage_controllers_ = false;
62  initialize();
63 }
64 
65 TrajectoryExecutionManager::TrajectoryExecutionManager(const rclcpp::Node::SharedPtr& node,
66  const moveit::core::RobotModelConstPtr& robot_model,
67  const planning_scene_monitor::CurrentStateMonitorPtr& csm,
68  bool manage_controllers)
69  : node_(node), robot_model_(robot_model), csm_(csm), manage_controllers_(manage_controllers)
70 {
71  initialize();
72 }
73 
75 {
76  run_continuous_execution_thread_ = false;
77  stopExecution(true);
78  private_executor_->cancel();
79  if (private_executor_thread_.joinable())
80  private_executor_thread_.join();
81  private_executor_.reset();
82 }
83 
84 void TrajectoryExecutionManager::initialize()
85 {
86  verbose_ = false;
87  execution_complete_ = true;
88  stop_continuous_execution_ = false;
89  current_context_ = -1;
91  run_continuous_execution_thread_ = true;
92  execution_duration_monitoring_ = true;
93  execution_velocity_scaling_ = 1.0;
94  allowed_start_tolerance_ = 0.01;
95  wait_for_trajectory_completion_ = true;
96 
97  allowed_execution_duration_scaling_ = DEFAULT_CONTROLLER_GOAL_DURATION_SCALING;
98  allowed_goal_duration_margin_ = DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN;
99 
100  // load the controller manager plugin
101  try
102  {
103  controller_manager_loader_ =
104  std::make_unique<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager>>(
105  "moveit_core", "moveit_controller_manager::MoveItControllerManager");
106  }
107  catch (pluginlib::PluginlibException& ex)
108  {
109  RCLCPP_FATAL_STREAM(LOGGER, "Exception while creating controller manager plugin loader: " << ex.what());
110  return;
111  }
112 
113  if (controller_manager_loader_)
114  {
115  std::string controller;
116 
117  if (!node_->get_parameter("moveit_controller_manager", controller))
118  {
119  const std::vector<std::string>& classes = controller_manager_loader_->getDeclaredClasses();
120  if (classes.size() == 1)
121  {
122  controller = classes[0];
123  RCLCPP_WARN(LOGGER,
124  "Parameter '~moveit_controller_manager' is not specified but only one "
125  "matching plugin was found: '%s'. Using that one.",
126  controller.c_str());
127  }
128  else
129  {
130  RCLCPP_FATAL(LOGGER, "Parameter '~moveit_controller_manager' not specified. This is needed to "
131  "identify the plugin to use for interacting with controllers. No paths can "
132  "be executed.");
133  }
134  }
135 
136  // Deprecation warnings, October 2022
137  if (controller == "moveit_ros_control_interface/MoveItControllerManager")
138  {
139  RCLCPP_WARN(LOGGER, "moveit_ros_control_interface/MoveItControllerManager is deprecated. Replace with "
140  "`moveit_ros_control_interface/MoveItControllerManager.`");
141  }
142  if (controller == "moveit_ros_control_interface/MoveItMultiControllerManager")
143  {
144  RCLCPP_WARN(LOGGER, "moveit_ros_control_interface/MoveItMultiControllerManager is deprecated. Replace with "
145  "`moveit_ros_control_interface/Ros2ControlMultiManager.`");
146  }
147 
148  if (!controller.empty())
149  try
150  {
151  // We make a node called moveit_simple_controller_manager so it's able to
152  // receive callbacks on another thread. We then copy parameters from the move_group node
153  // and then add it to the multithreadedexecutor
154  rclcpp::NodeOptions opt;
155  opt.allow_undeclared_parameters(true);
156  opt.automatically_declare_parameters_from_overrides(true);
157  controller_mgr_node_.reset(new rclcpp::Node("moveit_simple_controller_manager", opt));
158 
159  auto all_params = node_->get_node_parameters_interface()->get_parameter_overrides();
160  for (const auto& param : all_params)
161  controller_mgr_node_->set_parameter(rclcpp::Parameter(param.first, param.second));
162 
163  controller_manager_ = controller_manager_loader_->createUniqueInstance(controller);
164  controller_manager_->initialize(controller_mgr_node_);
165  private_executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
166  private_executor_->add_node(controller_mgr_node_);
167 
168  // start executor on a different thread now
169  private_executor_thread_ = std::thread([this]() { private_executor_->spin(); });
170  }
171  catch (pluginlib::PluginlibException& ex)
172  {
173  RCLCPP_FATAL_STREAM(LOGGER, "Exception while loading controller manager '" << controller << "': " << ex.what());
174  }
175  }
176 
177  // other configuration steps
178  reloadControllerInformation();
179 
180  // load controller-specific values for allowed_execution_duration_scaling and allowed_goal_duration_margin
181  loadControllerParams();
182 
183  // The default callback group for rclcpp::Node is MutuallyExclusive which means we cannot call
184  // receiveEvent while processing a different callback. To fix this we create a new callback group (the type is not
185  // important since we only use it to process one callback) and associate event_topic_subscriber_ with this callback group
186  auto callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
187  auto options = rclcpp::SubscriptionOptions();
188  options.callback_group = callback_group;
189  event_topic_subscriber_ = node_->create_subscription<std_msgs::msg::String>(
190  EXECUTION_EVENT_TOPIC, rclcpp::SystemDefaultsQoS(),
191  [this](const std_msgs::msg::String::ConstSharedPtr& event) { return receiveEvent(event); }, options);
192 
193  controller_mgr_node_->get_parameter("trajectory_execution.execution_duration_monitoring",
194  execution_duration_monitoring_);
195  controller_mgr_node_->get_parameter("trajectory_execution.allowed_execution_duration_scaling",
196  allowed_execution_duration_scaling_);
197  controller_mgr_node_->get_parameter("trajectory_execution.allowed_goal_duration_margin",
198  allowed_goal_duration_margin_);
199  controller_mgr_node_->get_parameter("trajectory_execution.allowed_start_tolerance", allowed_start_tolerance_);
200 
201  if (manage_controllers_)
202  RCLCPP_INFO(LOGGER, "Trajectory execution is managing controllers");
203  else
204  RCLCPP_INFO(LOGGER, "Trajectory execution is not managing controllers");
205 
206  auto controller_mgr_parameter_set_callback = [this](const std::vector<rclcpp::Parameter>& parameters) {
207  auto result = rcl_interfaces::msg::SetParametersResult();
208  result.successful = true;
209  for (const auto& parameter : parameters)
210  {
211  const std::string& name = parameter.get_name();
212  if (name == "trajectory_execution.execution_duration_monitoring")
213  enableExecutionDurationMonitoring(parameter.as_bool());
214  else if (name == "trajectory_execution.allowed_execution_duration_scaling")
215  setAllowedExecutionDurationScaling(parameter.as_double());
216  else if (name == "trajectory_execution.allowed_goal_duration_margin")
217  setAllowedGoalDurationMargin(parameter.as_double());
218  else if (name == "trajectory_execution.execution_velocity_scaling")
219  setExecutionVelocityScaling(parameter.as_double());
220  else if (name == "trajectory_execution.allowed_start_tolerance")
221  setAllowedStartTolerance(parameter.as_double());
222  else if (name == "trajectory_execution.wait_for_trajectory_completion")
223  setWaitForTrajectoryCompletion(parameter.as_bool());
224  else
225  result.successful = false;
226  }
227  return result;
228  };
229  callback_handler_ = controller_mgr_node_->add_on_set_parameters_callback(controller_mgr_parameter_set_callback);
230 }
231 
233 {
234  execution_duration_monitoring_ = flag;
235 }
236 
238 {
239  allowed_execution_duration_scaling_ = scaling;
240 }
241 
243 {
244  allowed_goal_duration_margin_ = margin;
245 }
246 
248 {
249  execution_velocity_scaling_ = scaling;
250 }
251 
253 {
254  allowed_start_tolerance_ = tolerance;
255 }
256 
258 {
259  wait_for_trajectory_completion_ = flag;
260 }
261 
263 {
264  return manage_controllers_;
265 }
266 
267 const moveit_controller_manager::MoveItControllerManagerPtr& TrajectoryExecutionManager::getControllerManager() const
268 {
269  return controller_manager_;
270 }
271 
272 void TrajectoryExecutionManager::processEvent(const std::string& event)
273 {
274  if (event == "stop")
275  stopExecution(true);
276  else
277  RCLCPP_WARN_STREAM(LOGGER, "Unknown event type: '" << event << "'");
278 }
279 
280 void TrajectoryExecutionManager::receiveEvent(const std_msgs::msg::String::ConstSharedPtr& event)
281 {
282  RCLCPP_INFO_STREAM(LOGGER, "Received event '" << event->data << "'");
283  processEvent(event->data);
284 }
285 
286 bool TrajectoryExecutionManager::push(const moveit_msgs::msg::RobotTrajectory& trajectory, const std::string& controller)
287 {
288  if (controller.empty())
289  return push(trajectory, std::vector<std::string>());
290  else
291  return push(trajectory, std::vector<std::string>(1, controller));
292 }
293 
294 bool TrajectoryExecutionManager::push(const trajectory_msgs::msg::JointTrajectory& trajectory,
295  const std::string& controller)
296 {
297  if (controller.empty())
298  return push(trajectory, std::vector<std::string>());
299  else
300  return push(trajectory, std::vector<std::string>(1, controller));
301 }
302 
303 bool TrajectoryExecutionManager::push(const trajectory_msgs::msg::JointTrajectory& trajectory,
304  const std::vector<std::string>& controllers)
305 {
306  moveit_msgs::msg::RobotTrajectory traj;
307  traj.joint_trajectory = trajectory;
308  return push(traj, controllers);
309 }
310 
311 bool TrajectoryExecutionManager::push(const moveit_msgs::msg::RobotTrajectory& trajectory,
312  const std::vector<std::string>& controllers)
313 {
314  if (!execution_complete_)
315  {
316  RCLCPP_ERROR(LOGGER, "Cannot push a new trajectory while another is being executed");
317  return false;
318  }
319 
321  if (configure(*context, trajectory, controllers))
322  {
323  if (verbose_)
324  {
325  std::stringstream ss;
326  ss << "Pushed trajectory for execution using controllers [ ";
327  for (const std::string& controller : context->controllers_)
328  ss << controller << " ";
329  ss << "]:" << '\n';
330  // TODO: Provide message serialization
331  // for (const moveit_msgs::msg::RobotTrajectory& trajectory_part : context->trajectory_parts_)
332  // ss << trajectory_part << '\n';
333  RCLCPP_INFO_STREAM(LOGGER, ss.str());
334  }
335  trajectories_.push_back(context);
336  return true;
337  }
338  else
339  {
340  delete context;
342  }
343 
344  return false;
345 }
346 
347 bool TrajectoryExecutionManager::pushAndExecute(const moveit_msgs::msg::RobotTrajectory& trajectory,
348  const std::string& controller)
349 {
350  if (controller.empty())
351  return pushAndExecute(trajectory, std::vector<std::string>());
352  else
353  return pushAndExecute(trajectory, std::vector<std::string>(1, controller));
354 }
355 
356 bool TrajectoryExecutionManager::pushAndExecute(const trajectory_msgs::msg::JointTrajectory& trajectory,
357  const std::string& controller)
358 {
359  if (controller.empty())
360  return pushAndExecute(trajectory, std::vector<std::string>());
361  else
362  return pushAndExecute(trajectory, std::vector<std::string>(1, controller));
363 }
364 
365 bool TrajectoryExecutionManager::pushAndExecute(const sensor_msgs::msg::JointState& state, const std::string& controller)
366 {
367  if (controller.empty())
368  return pushAndExecute(state, std::vector<std::string>());
369  else
370  return pushAndExecute(state, std::vector<std::string>(1, controller));
371 }
372 
373 bool TrajectoryExecutionManager::pushAndExecute(const trajectory_msgs::msg::JointTrajectory& trajectory,
374  const std::vector<std::string>& controllers)
375 {
376  moveit_msgs::msg::RobotTrajectory traj;
377  traj.joint_trajectory = trajectory;
378  return pushAndExecute(traj, controllers);
379 }
380 
381 bool TrajectoryExecutionManager::pushAndExecute(const sensor_msgs::msg::JointState& state,
382  const std::vector<std::string>& controllers)
383 {
384  moveit_msgs::msg::RobotTrajectory traj;
385  traj.joint_trajectory.header = state.header;
386  traj.joint_trajectory.joint_names = state.name;
387  traj.joint_trajectory.points.resize(1);
388  traj.joint_trajectory.points[0].positions = state.position;
389  traj.joint_trajectory.points[0].velocities = state.velocity;
390  traj.joint_trajectory.points[0].effort = state.effort;
391  traj.joint_trajectory.points[0].time_from_start = rclcpp::Duration(0, 0);
392  return pushAndExecute(traj, controllers);
393 }
394 
395 bool TrajectoryExecutionManager::pushAndExecute(const moveit_msgs::msg::RobotTrajectory& trajectory,
396  const std::vector<std::string>& controllers)
397 {
398  if (!execution_complete_)
399  {
400  RCLCPP_ERROR(LOGGER, "Cannot push & execute a new trajectory while another is being executed");
401  return false;
402  }
403 
405  if (configure(*context, trajectory, controllers))
406  {
407  {
408  std::scoped_lock slock(continuous_execution_mutex_);
409  continuous_execution_queue_.push_back(context);
410  if (!continuous_execution_thread_)
411  continuous_execution_thread_ = std::make_unique<std::thread>([this] { continuousExecutionThread(); });
412  }
414  continuous_execution_condition_.notify_all();
415  return true;
416  }
417  else
418  {
419  delete context;
421  return false;
422  }
423 }
424 
425 void TrajectoryExecutionManager::continuousExecutionThread()
426 {
427  std::set<moveit_controller_manager::MoveItControllerHandlePtr> used_handles;
428  while (run_continuous_execution_thread_)
429  {
430  if (!stop_continuous_execution_)
431  {
432  std::unique_lock<std::mutex> ulock(continuous_execution_mutex_);
433  while (continuous_execution_queue_.empty() && run_continuous_execution_thread_ && !stop_continuous_execution_)
434  continuous_execution_condition_.wait(ulock);
435  }
436 
437  if (stop_continuous_execution_ || !run_continuous_execution_thread_)
438  {
439  for (const moveit_controller_manager::MoveItControllerHandlePtr& used_handle : used_handles)
440  if (used_handle->getLastExecutionStatus() == moveit_controller_manager::ExecutionStatus::RUNNING)
441  used_handle->cancelExecution();
442  used_handles.clear();
443  while (!continuous_execution_queue_.empty())
444  {
445  TrajectoryExecutionContext* context = continuous_execution_queue_.front();
446  continuous_execution_queue_.pop_front();
447  delete context;
448  }
449  stop_continuous_execution_ = false;
450  continue;
451  }
452 
453  while (!continuous_execution_queue_.empty())
454  {
455  TrajectoryExecutionContext* context = nullptr;
456  {
457  std::scoped_lock slock(continuous_execution_mutex_);
458  if (continuous_execution_queue_.empty())
459  break;
460  context = continuous_execution_queue_.front();
461  continuous_execution_queue_.pop_front();
462  if (continuous_execution_queue_.empty())
463  continuous_execution_condition_.notify_all();
464  }
465 
466  // remove handles we no longer need
467  std::set<moveit_controller_manager::MoveItControllerHandlePtr>::iterator uit = used_handles.begin();
468  while (uit != used_handles.end())
469  if ((*uit)->getLastExecutionStatus() != moveit_controller_manager::ExecutionStatus::RUNNING)
470  {
471  std::set<moveit_controller_manager::MoveItControllerHandlePtr>::iterator to_erase = uit;
472  ++uit;
473  used_handles.erase(to_erase);
474  }
475  else
476  ++uit;
477 
478  // now send stuff to controllers
479 
480  // first make sure desired controllers are active
481  if (areControllersActive(context->controllers_))
482  {
483  // get the controller handles needed to execute the new trajectory
484  std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles(context->controllers_.size());
485  for (std::size_t i = 0; i < context->controllers_.size(); ++i)
486  {
487  moveit_controller_manager::MoveItControllerHandlePtr h;
488  try
489  {
490  h = controller_manager_->getControllerHandle(context->controllers_[i]);
491  }
492  catch (std::exception& ex)
493  {
494  RCLCPP_ERROR(LOGGER, "%s caught when retrieving controller handle", ex.what());
495  }
496  if (!h)
497  {
499  RCLCPP_ERROR(LOGGER, "No controller handle for controller '%s'. Aborting.",
500  context->controllers_[i].c_str());
501  handles.clear();
502  break;
503  }
504  handles[i] = h;
505  }
506 
507  if (stop_continuous_execution_ || !run_continuous_execution_thread_)
508  {
509  delete context;
510  break;
511  }
512 
513  // push all trajectories to all controllers simultaneously
514  if (!handles.empty())
515  for (std::size_t i = 0; i < context->trajectory_parts_.size(); ++i)
516  {
517  bool ok = false;
518  try
519  {
520  ok = handles[i]->sendTrajectory(context->trajectory_parts_[i]);
521  }
522  catch (std::exception& ex)
523  {
524  RCLCPP_ERROR(LOGGER, "Caught %s when sending trajectory to controller", ex.what());
525  }
526  if (!ok)
527  {
528  for (std::size_t j = 0; j < i; ++j)
529  try
530  {
531  handles[j]->cancelExecution();
532  }
533  catch (std::exception& ex)
534  {
535  RCLCPP_ERROR(LOGGER, "Caught %s when canceling execution", ex.what());
536  }
537  RCLCPP_ERROR(LOGGER, "Failed to send trajectory part %zu of %zu to controller %s", i + 1,
538  context->trajectory_parts_.size(), handles[i]->getName().c_str());
539  if (i > 0)
540  RCLCPP_ERROR(LOGGER, "Cancelling previously sent trajectory parts");
542  handles.clear();
543  break;
544  }
545  }
546  delete context;
547 
548  // remember which handles we used
549  for (const moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
550  used_handles.insert(handle);
551  }
552  else
553  {
554  RCLCPP_ERROR(LOGGER, "Not all needed controllers are active. Cannot push and execute. You can try "
555  "calling ensureActiveControllers() before pushAndExecute()");
557  delete context;
558  }
559  }
560  }
561 }
562 
563 void TrajectoryExecutionManager::reloadControllerInformation()
564 {
565  known_controllers_.clear();
566  if (controller_manager_)
567  {
568  std::vector<std::string> names;
569  controller_manager_->getControllersList(names);
570  for (const std::string& name : names)
571  {
572  std::vector<std::string> joints;
573  controller_manager_->getControllerJoints(name, joints);
574  ControllerInformation ci;
575  ci.name_ = name;
576  ci.joints_.insert(joints.begin(), joints.end());
577  known_controllers_[ci.name_] = ci;
578  }
579 
580  names.clear();
581  controller_manager_->getActiveControllers(names);
582  for (const auto& active_name : names)
583  {
584  auto found_it = std::find_if(known_controllers_.begin(), known_controllers_.end(),
585  [&](const auto& known_controller) { return known_controller.first == active_name; });
586  if (found_it != known_controllers_.end())
587  {
588  found_it->second.state_.active_ = true;
589  }
590  }
591 
592  for (std::map<std::string, ControllerInformation>::iterator it = known_controllers_.begin();
593  it != known_controllers_.end(); ++it)
594  for (std::map<std::string, ControllerInformation>::iterator jt = known_controllers_.begin();
595  jt != known_controllers_.end(); ++jt)
596  if (it != jt)
597  {
598  std::vector<std::string> intersect;
599  std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), jt->second.joints_.begin(),
600  jt->second.joints_.end(), std::back_inserter(intersect));
601  if (!intersect.empty())
602  {
603  it->second.overlapping_controllers_.insert(jt->first);
604  jt->second.overlapping_controllers_.insert(it->first);
605  }
606  }
607  }
608  else
609  {
610  RCLCPP_ERROR(LOGGER, "Failed to reload controllers: `controller_manager_` does not exist.");
611  }
612 }
613 
614 void TrajectoryExecutionManager::updateControllerState(const std::string& controller, const rclcpp::Duration& age)
615 {
616  std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
617  if (it != known_controllers_.end())
618  updateControllerState(it->second, age);
619  else
620  RCLCPP_ERROR(LOGGER, "Controller '%s' is not known.", controller.c_str());
621 }
622 
623 void TrajectoryExecutionManager::updateControllerState(ControllerInformation& ci, const rclcpp::Duration& age)
624 {
625  if (node_->now() - ci.last_update_ >= age)
626  {
627  if (controller_manager_)
628  {
629  if (verbose_)
630  RCLCPP_INFO(LOGGER, "Updating information for controller '%s'.", ci.name_.c_str());
631  ci.state_ = controller_manager_->getControllerState(ci.name_);
632  ci.last_update_ = node_->now();
633  }
634  }
635  else if (verbose_)
636  RCLCPP_INFO(LOGGER, "Information for controller '%s' is assumed to be up to date.", ci.name_.c_str());
637 }
638 
639 void TrajectoryExecutionManager::updateControllersState(const rclcpp::Duration& age)
640 {
641  for (std::pair<const std::string, ControllerInformation>& known_controller : known_controllers_)
642  updateControllerState(known_controller.second, age);
643 }
644 
645 bool TrajectoryExecutionManager::checkControllerCombination(std::vector<std::string>& selected,
646  const std::set<std::string>& actuated_joints)
647 {
648  std::set<std::string> combined_joints;
649  for (const std::string& controller : selected)
650  {
651  const ControllerInformation& ci = known_controllers_[controller];
652  combined_joints.insert(ci.joints_.begin(), ci.joints_.end());
653  }
654 
655  if (verbose_)
656  {
657  std::stringstream ss, saj, sac;
658  for (const std::string& controller : selected)
659  ss << controller << " ";
660  for (const std::string& actuated_joint : actuated_joints)
661  saj << actuated_joint << " ";
662  for (const std::string& combined_joint : combined_joints)
663  sac << combined_joint << " ";
664  RCLCPP_INFO(LOGGER, "Checking if controllers [ %s] operating on joints [ %s] cover joints [ %s]", ss.str().c_str(),
665  sac.str().c_str(), saj.str().c_str());
666  }
667 
668  return std::includes(combined_joints.begin(), combined_joints.end(), actuated_joints.begin(), actuated_joints.end());
669 }
670 
671 void TrajectoryExecutionManager::generateControllerCombination(std::size_t start_index, std::size_t controller_count,
672  const std::vector<std::string>& available_controllers,
673  std::vector<std::string>& selected_controllers,
674  std::vector<std::vector<std::string>>& selected_options,
675  const std::set<std::string>& actuated_joints)
676 {
677  if (selected_controllers.size() == controller_count)
678  {
679  if (checkControllerCombination(selected_controllers, actuated_joints))
680  selected_options.push_back(selected_controllers);
681  return;
682  }
683 
684  for (std::size_t i = start_index; i < available_controllers.size(); ++i)
685  {
686  bool overlap = false;
687  const ControllerInformation& ci = known_controllers_[available_controllers[i]];
688  for (std::size_t j = 0; j < selected_controllers.size() && !overlap; ++j)
689  {
690  if (ci.overlapping_controllers_.find(selected_controllers[j]) != ci.overlapping_controllers_.end())
691  overlap = true;
692  }
693  if (overlap)
694  continue;
695  selected_controllers.push_back(available_controllers[i]);
696  generateControllerCombination(i + 1, controller_count, available_controllers, selected_controllers,
697  selected_options, actuated_joints);
698  selected_controllers.pop_back();
699  }
700 }
701 
702 namespace
703 {
704 struct OrderPotentialControllerCombination
705 {
706  bool operator()(const std::size_t a, const std::size_t b) const
707  {
708  // preference is given to controllers marked as default
709  if (nrdefault[a] > nrdefault[b])
710  return true;
711  if (nrdefault[a] < nrdefault[b])
712  return false;
713 
714  // and then to ones that operate on fewer joints
715  if (nrjoints[a] < nrjoints[b])
716  return true;
717  if (nrjoints[a] > nrjoints[b])
718  return false;
719 
720  // and then to active ones
721  if (nractive[a] < nractive[b])
722  return true;
723  if (nractive[a] > nractive[b])
724  return false;
725 
726  return false;
727  }
728 
729  std::vector<std::vector<std::string>> selected_options;
730  std::vector<std::size_t> nrdefault;
731  std::vector<std::size_t> nrjoints;
732  std::vector<std::size_t> nractive;
733 };
734 } // namespace
735 
736 bool TrajectoryExecutionManager::findControllers(const std::set<std::string>& actuated_joints,
737  std::size_t controller_count,
738  const std::vector<std::string>& available_controllers,
739  std::vector<std::string>& selected_controllers)
740 {
741  // generate all combinations of controller_count controllers that operate on disjoint sets of joints
742  std::vector<std::string> work_area;
743  OrderPotentialControllerCombination order;
744  std::vector<std::vector<std::string>>& selected_options = order.selected_options;
745  generateControllerCombination(0, controller_count, available_controllers, work_area, selected_options,
746  actuated_joints);
747 
748  if (verbose_)
749  {
750  std::stringstream saj;
751  std::stringstream sac;
752  for (const std::string& available_controller : available_controllers)
753  sac << available_controller << " ";
754  for (const std::string& actuated_joint : actuated_joints)
755  saj << actuated_joint << " ";
756  RCLCPP_INFO(LOGGER, "Looking for %zu controllers among [ %s] that cover joints [ %s]. Found %zd options.",
757  controller_count, sac.str().c_str(), saj.str().c_str(), selected_options.size());
758  }
759 
760  // if none was found, this is a problem
761  if (selected_options.empty())
762  return false;
763 
764  // if only one was found, return it
765  if (selected_options.size() == 1)
766  {
767  selected_controllers.swap(selected_options[0]);
768  return true;
769  }
770 
771  // if more options were found, evaluate them all and return the best one
772 
773  // count how many default controllers are used in each reported option, and how many joints are actuated in total by
774  // the selected controllers,
775  // to use that in the ranking of the options
776  order.nrdefault.resize(selected_options.size(), 0);
777  order.nrjoints.resize(selected_options.size(), 0);
778  order.nractive.resize(selected_options.size(), 0);
779  for (std::size_t i = 0; i < selected_options.size(); ++i)
780  {
781  for (std::size_t k = 0; k < selected_options[i].size(); ++k)
782  {
783  updateControllerState(selected_options[i][k], DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
784  const ControllerInformation& ci = known_controllers_[selected_options[i][k]];
785 
786  if (ci.state_.default_)
787  order.nrdefault[i]++;
788  if (ci.state_.active_)
789  order.nractive[i]++;
790  order.nrjoints[i] += ci.joints_.size();
791  }
792  }
793 
794  // define a bijection to compute the raking of the found options
795  std::vector<std::size_t> bijection(selected_options.size(), 0);
796  for (std::size_t i = 0; i < selected_options.size(); ++i)
797  bijection[i] = i;
798 
799  // sort the options
800  std::sort(bijection.begin(), bijection.end(), order);
801 
802  // depending on whether we are allowed to load & unload controllers,
803  // we have different preference on deciding between options
804  if (!manage_controllers_)
805  {
806  // if we can't load different options at will, just choose one that is already loaded
807  for (std::size_t i = 0; i < selected_options.size(); ++i)
808  if (areControllersActive(selected_options[bijection[i]]))
809  {
810  selected_controllers.swap(selected_options[bijection[i]]);
811  return true;
812  }
813  }
814 
815  // otherwise, just use the first valid option
816  selected_controllers.swap(selected_options[bijection[0]]);
817  return true;
818 }
819 
820 bool TrajectoryExecutionManager::isControllerActive(const std::string& controller)
821 {
822  return areControllersActive(std::vector<std::string>(1, controller));
823 }
824 
825 bool TrajectoryExecutionManager::areControllersActive(const std::vector<std::string>& controllers)
826 {
827  for (const std::string& controller : controllers)
828  {
829  updateControllerState(controller, DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
830  std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
831  if (it == known_controllers_.end() || !it->second.state_.active_)
832  return false;
833  }
834  return true;
835 }
836 
837 bool TrajectoryExecutionManager::selectControllers(const std::set<std::string>& actuated_joints,
838  const std::vector<std::string>& available_controllers,
839  std::vector<std::string>& selected_controllers)
840 {
841  for (std::size_t i = 1; i <= available_controllers.size(); ++i)
842  if (findControllers(actuated_joints, i, available_controllers, selected_controllers))
843  {
844  // if we are not managing controllers, prefer to use active controllers even if there are more of them
845  if (!manage_controllers_ && !areControllersActive(selected_controllers))
846  {
847  std::vector<std::string> other_option;
848  for (std::size_t j = i + 1; j <= available_controllers.size(); ++j)
849  if (findControllers(actuated_joints, j, available_controllers, other_option))
850  {
851  if (areControllersActive(other_option))
852  {
853  selected_controllers = other_option;
854  break;
855  }
856  }
857  }
858  return true;
859  }
860  return false;
861 }
862 
863 bool TrajectoryExecutionManager::distributeTrajectory(const moveit_msgs::msg::RobotTrajectory& trajectory,
864  const std::vector<std::string>& controllers,
865  std::vector<moveit_msgs::msg::RobotTrajectory>& parts)
866 {
867  parts.clear();
868  parts.resize(controllers.size());
869 
870  std::set<std::string> actuated_joints_mdof;
871  actuated_joints_mdof.insert(trajectory.multi_dof_joint_trajectory.joint_names.begin(),
872  trajectory.multi_dof_joint_trajectory.joint_names.end());
873  std::set<std::string> actuated_joints_single;
874  for (const std::string& joint_name : trajectory.joint_trajectory.joint_names)
875  {
876  const moveit::core::JointModel* jm = robot_model_->getJointModel(joint_name);
877  if (jm)
878  {
879  if (jm->isPassive() || jm->getMimic() != nullptr || jm->getType() == moveit::core::JointModel::FIXED)
880  continue;
881  actuated_joints_single.insert(jm->getName());
882  }
883  }
884 
885  for (std::size_t i = 0; i < controllers.size(); ++i)
886  {
887  std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controllers[i]);
888  if (it == known_controllers_.end())
889  {
890  RCLCPP_ERROR_STREAM(LOGGER, "Controller " << controllers[i] << " not found.");
891  return false;
892  }
893  std::vector<std::string> intersect_mdof;
894  std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_mdof.begin(),
895  actuated_joints_mdof.end(), std::back_inserter(intersect_mdof));
896  std::vector<std::string> intersect_single;
897  std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_single.begin(),
898  actuated_joints_single.end(), std::back_inserter(intersect_single));
899  if (intersect_mdof.empty() && intersect_single.empty())
900  RCLCPP_WARN_STREAM(LOGGER, "No joints to be distributed for controller " << controllers[i]);
901  {
902  if (!intersect_mdof.empty())
903  {
904  std::vector<std::string>& jnames = parts[i].multi_dof_joint_trajectory.joint_names;
905  jnames.insert(jnames.end(), intersect_mdof.begin(), intersect_mdof.end());
906  std::map<std::string, std::size_t> index;
907  for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
908  index[trajectory.multi_dof_joint_trajectory.joint_names[j]] = j;
909  std::vector<std::size_t> bijection(jnames.size());
910  for (std::size_t j = 0; j < jnames.size(); ++j)
911  bijection[j] = index[jnames[j]];
912 
913  parts[i].multi_dof_joint_trajectory.header.frame_id = trajectory.multi_dof_joint_trajectory.header.frame_id;
914  parts[i].multi_dof_joint_trajectory.points.resize(trajectory.multi_dof_joint_trajectory.points.size());
915  for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.points.size(); ++j)
916  {
917  parts[i].multi_dof_joint_trajectory.points[j].time_from_start =
918  trajectory.multi_dof_joint_trajectory.points[j].time_from_start;
919  parts[i].multi_dof_joint_trajectory.points[j].transforms.resize(bijection.size());
920  for (std::size_t k = 0; k < bijection.size(); ++k)
921  {
922  parts[i].multi_dof_joint_trajectory.points[j].transforms[k] =
923  trajectory.multi_dof_joint_trajectory.points[j].transforms[bijection[k]];
924 
925  if (!trajectory.multi_dof_joint_trajectory.points[j].velocities.empty())
926  {
927  parts[i].multi_dof_joint_trajectory.points[j].velocities.resize(bijection.size());
928 
929  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.x =
930  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.x * execution_velocity_scaling_;
931 
932  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.y =
933  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.y * execution_velocity_scaling_;
934 
935  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.z =
936  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.z * execution_velocity_scaling_;
937 
938  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.x =
939  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.x * execution_velocity_scaling_;
940 
941  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.y =
942  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.y * execution_velocity_scaling_;
943 
944  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.z =
945  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.z * execution_velocity_scaling_;
946  }
947  }
948  }
949  }
950  if (!intersect_single.empty())
951  {
952  std::vector<std::string>& jnames = parts[i].joint_trajectory.joint_names;
953  jnames.insert(jnames.end(), intersect_single.begin(), intersect_single.end());
954  parts[i].joint_trajectory.header = trajectory.joint_trajectory.header;
955  std::map<std::string, std::size_t> index;
956  for (std::size_t j = 0; j < trajectory.joint_trajectory.joint_names.size(); ++j)
957  index[trajectory.joint_trajectory.joint_names[j]] = j;
958  std::vector<std::size_t> bijection(jnames.size());
959  for (std::size_t j = 0; j < jnames.size(); ++j)
960  bijection[j] = index[jnames[j]];
961  parts[i].joint_trajectory.points.resize(trajectory.joint_trajectory.points.size());
962  for (std::size_t j = 0; j < trajectory.joint_trajectory.points.size(); ++j)
963  {
964  parts[i].joint_trajectory.points[j].time_from_start = trajectory.joint_trajectory.points[j].time_from_start;
965  if (!trajectory.joint_trajectory.points[j].positions.empty())
966  {
967  parts[i].joint_trajectory.points[j].positions.resize(bijection.size());
968  for (std::size_t k = 0; k < bijection.size(); ++k)
969  parts[i].joint_trajectory.points[j].positions[k] =
970  trajectory.joint_trajectory.points[j].positions[bijection[k]];
971  }
972  if (!trajectory.joint_trajectory.points[j].velocities.empty())
973  {
974  parts[i].joint_trajectory.points[j].velocities.resize(bijection.size());
975  for (std::size_t k = 0; k < bijection.size(); ++k)
976  parts[i].joint_trajectory.points[j].velocities[k] =
977  trajectory.joint_trajectory.points[j].velocities[bijection[k]] * execution_velocity_scaling_;
978  }
979  if (!trajectory.joint_trajectory.points[j].accelerations.empty())
980  {
981  parts[i].joint_trajectory.points[j].accelerations.resize(bijection.size());
982  for (std::size_t k = 0; k < bijection.size(); ++k)
983  parts[i].joint_trajectory.points[j].accelerations[k] =
984  trajectory.joint_trajectory.points[j].accelerations[bijection[k]];
985  }
986  if (!trajectory.joint_trajectory.points[j].effort.empty())
987  {
988  parts[i].joint_trajectory.points[j].effort.resize(bijection.size());
989  for (std::size_t k = 0; k < bijection.size(); ++k)
990  parts[i].joint_trajectory.points[j].effort[k] =
991  trajectory.joint_trajectory.points[j].effort[bijection[k]];
992  }
993  }
994  }
995  }
996  }
997  return true;
998 }
999 
1000 bool TrajectoryExecutionManager::validate(const TrajectoryExecutionContext& context) const
1001 {
1002  if (allowed_start_tolerance_ == 0) // skip validation on this magic number
1003  return true;
1004 
1005  RCLCPP_INFO(LOGGER, "Validating trajectory with allowed_start_tolerance %g", allowed_start_tolerance_);
1006 
1007  moveit::core::RobotStatePtr current_state;
1008  if (!csm_->waitForCurrentState(node_->now()) || !(current_state = csm_->getCurrentState()))
1009  {
1010  RCLCPP_WARN(LOGGER, "Failed to validate trajectory: couldn't receive full current joint state within 1s");
1011  return false;
1012  }
1013 
1014  for (const auto& trajectory : context.trajectory_parts_)
1015  {
1016  if (!trajectory.joint_trajectory.points.empty())
1017  {
1018  // Check single-dof trajectory
1019  const std::vector<double>& positions = trajectory.joint_trajectory.points.front().positions;
1020  const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1021  if (positions.size() != joint_names.size())
1022  {
1023  RCLCPP_ERROR(LOGGER, "Wrong trajectory: #joints: %zu != #positions: %zu", joint_names.size(), positions.size());
1024  return false;
1025  }
1026 
1027  for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
1028  {
1029  const moveit::core::JointModel* jm = current_state->getJointModel(joint_names[i]);
1030  if (!jm)
1031  {
1032  RCLCPP_ERROR_STREAM(LOGGER, "Unknown joint in trajectory: " << joint_names[i]);
1033  return false;
1034  }
1035 
1036  double cur_position = current_state->getJointPositions(jm)[0];
1037  double traj_position = positions[i];
1038  // normalize positions and compare
1039  jm->enforcePositionBounds(&cur_position);
1040  jm->enforcePositionBounds(&traj_position);
1041  if (jm->distance(&cur_position, &traj_position) > allowed_start_tolerance_)
1042  {
1043  RCLCPP_ERROR(LOGGER,
1044  "\nInvalid Trajectory: start point deviates from current robot state more than %g"
1045  "\njoint '%s': expected: %g, current: %g",
1046  allowed_start_tolerance_, joint_names[i].c_str(), traj_position, cur_position);
1047  return false;
1048  }
1049  }
1050  }
1051  if (!trajectory.multi_dof_joint_trajectory.points.empty())
1052  {
1053  // Check multi-dof trajectory
1054  const std::vector<geometry_msgs::msg::Transform>& transforms =
1055  trajectory.multi_dof_joint_trajectory.points.front().transforms;
1056  const std::vector<std::string>& joint_names = trajectory.multi_dof_joint_trajectory.joint_names;
1057  if (transforms.size() != joint_names.size())
1058  {
1059  RCLCPP_ERROR(LOGGER, "Wrong trajectory: #joints: %zu != #transforms: %zu", joint_names.size(),
1060  transforms.size());
1061  return false;
1062  }
1063 
1064  for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
1065  {
1066  const moveit::core::JointModel* jm = current_state->getJointModel(joint_names[i]);
1067  if (!jm)
1068  {
1069  RCLCPP_ERROR_STREAM(LOGGER, "Unknown joint in trajectory: " << joint_names[i]);
1070  return false;
1071  }
1072 
1073  // compute difference (offset vector and rotation angle) between current transform
1074  // and start transform in trajectory
1075  Eigen::Isometry3d cur_transform, start_transform;
1076  // computeTransform() computes a valid isometry by contract
1077  jm->computeTransform(current_state->getJointPositions(jm), cur_transform);
1078  start_transform = tf2::transformToEigen(transforms[i]);
1079  ASSERT_ISOMETRY(start_transform) // unsanitized input, could contain a non-isometry
1080  Eigen::Vector3d offset = cur_transform.translation() - start_transform.translation();
1081  Eigen::AngleAxisd rotation;
1082  rotation.fromRotationMatrix(cur_transform.linear().transpose() * start_transform.linear());
1083  if ((offset.array() > allowed_start_tolerance_).any() || rotation.angle() > allowed_start_tolerance_)
1084  {
1085  RCLCPP_ERROR_STREAM(LOGGER, "\nInvalid Trajectory: start point deviates from current robot state more than "
1086  << allowed_start_tolerance_ << "\nmulti-dof joint '" << joint_names[i]
1087  << "': pos delta: " << offset.transpose()
1088  << " rot delta: " << rotation.angle());
1089  return false;
1090  }
1091  }
1092  }
1093  }
1094  return true;
1095 }
1096 
1097 bool TrajectoryExecutionManager::configure(TrajectoryExecutionContext& context,
1098  const moveit_msgs::msg::RobotTrajectory& trajectory,
1099  const std::vector<std::string>& controllers)
1100 {
1101  if (trajectory.multi_dof_joint_trajectory.points.empty() && trajectory.joint_trajectory.points.empty())
1102  {
1103  // empty trajectories don't need to configure anything
1104  return true;
1105  }
1106 
1107  reloadControllerInformation();
1108  std::set<std::string> actuated_joints;
1109 
1110  auto is_actuated = [this](const std::string& joint_name) -> bool {
1111  const moveit::core::JointModel* jm = robot_model_->getJointModel(joint_name);
1112  return (jm && !jm->isPassive() && !jm->getMimic() && jm->getType() != moveit::core::JointModel::FIXED);
1113  };
1114  for (const std::string& joint_name : trajectory.multi_dof_joint_trajectory.joint_names)
1115  if (is_actuated(joint_name))
1116  actuated_joints.insert(joint_name);
1117  for (const std::string& joint_name : trajectory.joint_trajectory.joint_names)
1118  if (is_actuated(joint_name))
1119  actuated_joints.insert(joint_name);
1120 
1121  if (actuated_joints.empty())
1122  {
1123  RCLCPP_WARN(LOGGER, "The trajectory to execute specifies no joints");
1124  return false;
1125  }
1126 
1127  if (controllers.empty())
1128  {
1129  bool retry = true;
1130  bool reloaded = false;
1131  while (retry)
1132  {
1133  retry = false;
1134  std::vector<std::string> all_controller_names;
1135  for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1136  it != known_controllers_.end(); ++it)
1137  all_controller_names.push_back(it->first);
1138  if (selectControllers(actuated_joints, all_controller_names, context.controllers_))
1139  {
1140  if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
1141  return true;
1142  }
1143  else
1144  {
1145  // maybe we failed because we did not have a complete list of controllers
1146  if (!reloaded)
1147  {
1148  reloadControllerInformation();
1149  reloaded = true;
1150  retry = true;
1151  }
1152  }
1153  }
1154  }
1155  else
1156  {
1157  // check if the specified controllers are valid names;
1158  // if they appear not to be, try to reload the controller information, just in case they are new in the system
1159  bool reloaded = false;
1160  for (const std::string& controller : controllers)
1161  if (known_controllers_.find(controller) == known_controllers_.end())
1162  {
1163  reloadControllerInformation();
1164  reloaded = true;
1165  break;
1166  }
1167  if (reloaded)
1168  for (const std::string& controller : controllers)
1169  if (known_controllers_.find(controller) == known_controllers_.end())
1170  {
1171  RCLCPP_ERROR(LOGGER, "Controller '%s' is not known", controller.c_str());
1172  return false;
1173  }
1174  if (selectControllers(actuated_joints, controllers, context.controllers_))
1175  {
1176  if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
1177  return true;
1178  }
1179  }
1180  std::stringstream ss;
1181  for (const std::string& actuated_joint : actuated_joints)
1182  ss << actuated_joint << " ";
1183  RCLCPP_ERROR(LOGGER, "Unable to identify any set of controllers that can actuate the specified joints: [ %s]",
1184  ss.str().c_str());
1185 
1186  std::stringstream ss2;
1187  std::map<std::string, ControllerInformation>::const_iterator mi;
1188  for (mi = known_controllers_.begin(); mi != known_controllers_.end(); ++mi)
1189  {
1190  ss2 << "controller '" << mi->second.name_ << "' controls joints:\n";
1191 
1192  std::set<std::string>::const_iterator ji;
1193  for (ji = mi->second.joints_.begin(); ji != mi->second.joints_.end(); ++ji)
1194  {
1195  ss2 << " " << *ji << '\n';
1196  }
1197  }
1198  RCLCPP_ERROR(LOGGER, "Known controllers and their joints:\n%s", ss2.str().c_str());
1199  return false;
1200 }
1201 
1203 {
1204  execute(ExecutionCompleteCallback(), auto_clear);
1205  return waitForExecution();
1206 }
1207 
1208 void TrajectoryExecutionManager::stopExecutionInternal()
1209 {
1210  // execution_state_mutex_ needs to have been locked by the caller
1211  for (moveit_controller_manager::MoveItControllerHandlePtr& active_handle : active_handles_)
1212  try
1213  {
1214  active_handle->cancelExecution();
1215  }
1216  catch (std::exception& ex)
1217  {
1218  RCLCPP_ERROR(LOGGER, "Caught %s when canceling execution.", ex.what());
1219  }
1220 }
1221 
1223 {
1224  stop_continuous_execution_ = true;
1225  continuous_execution_condition_.notify_all();
1226 
1227  if (!execution_complete_)
1228  {
1229  execution_state_mutex_.lock();
1230  if (!execution_complete_)
1231  {
1232  // we call cancel for all active handles; we know these are not being modified as we loop through them because of
1233  // the lock
1234  // we mark execution_complete_ as true ahead of time. Using this flag, executePart() will know that an external
1235  // trigger to stop has been received
1236  execution_complete_ = true;
1237  stopExecutionInternal();
1238 
1239  // we set the status here; executePart() will not set status when execution_complete_ is true ahead of time
1241  execution_state_mutex_.unlock();
1242  RCLCPP_INFO(LOGGER, "Stopped trajectory execution.");
1243 
1244  // wait for the execution thread to finish
1245  std::scoped_lock lock(execution_thread_mutex_);
1246  if (execution_thread_)
1247  {
1248  execution_thread_->join();
1249  execution_thread_.reset();
1250  }
1251 
1252  if (auto_clear)
1253  clear();
1254  }
1255  else
1256  execution_state_mutex_.unlock();
1257  }
1258  else if (execution_thread_) // just in case we have some thread waiting to be joined from some point in the past, we
1259  // join it now
1260  {
1261  std::scoped_lock lock(execution_thread_mutex_);
1262  if (execution_thread_)
1263  {
1264  execution_thread_->join();
1265  execution_thread_.reset();
1266  }
1267  }
1268 }
1269 
1271 {
1272  execute(callback, PathSegmentCompleteCallback(), auto_clear);
1273 }
1274 
1276  const PathSegmentCompleteCallback& part_callback, bool auto_clear)
1277 {
1278  stopExecution(false);
1279 
1280  // check whether first trajectory starts at current robot state
1281  if (!trajectories_.empty() && !validate(*trajectories_.front()))
1282  {
1283  last_execution_status_ = moveit_controller_manager::ExecutionStatus::ABORTED;
1284  if (auto_clear)
1285  clear();
1286  if (callback)
1287  callback(last_execution_status_);
1288  return;
1289  }
1290 
1291  // start the execution thread
1292  execution_complete_ = false;
1293  execution_thread_ = std::make_unique<std::thread>(&TrajectoryExecutionManager::executeThread, this, callback,
1294  part_callback, auto_clear);
1295 }
1296 
1298 {
1299  {
1300  std::unique_lock<std::mutex> ulock(execution_state_mutex_);
1301  while (!execution_complete_)
1302  execution_complete_condition_.wait(ulock);
1303  }
1304  {
1305  std::unique_lock<std::mutex> ulock(continuous_execution_mutex_);
1306  while (!continuous_execution_queue_.empty())
1307  continuous_execution_condition_.wait(ulock);
1308  }
1309 
1310  // this will join the thread for executing sequences of trajectories
1311  stopExecution(false);
1312 
1313  return last_execution_status_;
1314 }
1315 
1316 void TrajectoryExecutionManager::clear()
1317 {
1318  if (execution_complete_)
1319  {
1320  std::scoped_lock slock(execution_state_mutex_);
1321  for (TrajectoryExecutionContext* trajectory : trajectories_)
1322  delete trajectory;
1323  trajectories_.clear();
1324  {
1325  std::scoped_lock slock(continuous_execution_mutex_);
1326  while (!continuous_execution_queue_.empty())
1327  {
1328  delete continuous_execution_queue_.front();
1329  continuous_execution_queue_.pop_front();
1330  }
1331  }
1332  }
1333  else
1334  RCLCPP_FATAL(LOGGER, "Expecting execution_complete_ to be true!");
1335 }
1336 
1337 void TrajectoryExecutionManager::executeThread(const ExecutionCompleteCallback& callback,
1338  const PathSegmentCompleteCallback& part_callback, bool auto_clear)
1339 {
1340  // if we already got a stop request before we even started anything, we abort
1341  if (execution_complete_)
1342  {
1343  last_execution_status_ = moveit_controller_manager::ExecutionStatus::ABORTED;
1344  if (callback)
1345  callback(last_execution_status_);
1346  return;
1347  }
1348 
1349  RCLCPP_INFO(LOGGER, "Starting trajectory execution ...");
1350  // assume everything will be OK
1352 
1353  // execute each trajectory, one after the other (executePart() is blocking) or until one fails.
1354  // on failure, the status is set by executePart(). Otherwise, it will remain as set above (success)
1355  std::size_t i = 0;
1356  for (; i < trajectories_.size(); ++i)
1357  {
1358  bool epart = executePart(i);
1359  if (epart && part_callback)
1360  part_callback(i);
1361  if (!epart || execution_complete_)
1362  {
1363  ++i;
1364  break;
1365  }
1366  }
1367 
1368  // only report that execution finished successfully when the robot actually stopped moving
1369  if (last_execution_status_ == moveit_controller_manager::ExecutionStatus::SUCCEEDED)
1370  {
1371  std::scoped_lock slock(execution_state_mutex_);
1372  if (!execution_complete_)
1373  {
1374  waitForRobotToStop(*trajectories_[i - 1]);
1375  }
1376  }
1377 
1378  RCLCPP_INFO(LOGGER, "Completed trajectory execution with status %s ...", last_execution_status_.asString().c_str());
1379 
1380  // notify whoever is waiting for the event of trajectory completion
1381  execution_state_mutex_.lock();
1382  execution_complete_ = true;
1383  execution_state_mutex_.unlock();
1384  execution_complete_condition_.notify_all();
1385 
1386  // clear the paths just executed, if needed
1387  if (auto_clear)
1388  clear();
1389 
1390  // call user-specified callback
1391  if (callback)
1392  callback(last_execution_status_);
1393 }
1394 
1395 bool TrajectoryExecutionManager::executePart(std::size_t part_index)
1396 {
1397  TrajectoryExecutionContext& context = *trajectories_[part_index];
1398 
1399  // first make sure desired controllers are active
1400  if (ensureActiveControllers(context.controllers_))
1401  {
1402  // stop if we are already asked to do so
1403  if (execution_complete_)
1404  return false;
1405 
1406  std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles;
1407  {
1408  std::scoped_lock slock(execution_state_mutex_);
1409  if (!execution_complete_)
1410  {
1411  // time indexing uses this member too, so we lock this mutex as well
1412  time_index_mutex_.lock();
1413  current_context_ = part_index;
1414  time_index_mutex_.unlock();
1415  active_handles_.resize(context.controllers_.size());
1416  for (std::size_t i = 0; i < context.controllers_.size(); ++i)
1417  {
1418  moveit_controller_manager::MoveItControllerHandlePtr h;
1419  try
1420  {
1421  h = controller_manager_->getControllerHandle(context.controllers_[i]);
1422  }
1423  catch (std::exception& ex)
1424  {
1425  RCLCPP_ERROR(LOGGER, "Caught %s when retrieving controller handle", ex.what());
1426  }
1427  if (!h)
1428  {
1429  active_handles_.clear();
1430  current_context_ = -1;
1431  last_execution_status_ = moveit_controller_manager::ExecutionStatus::ABORTED;
1432  RCLCPP_ERROR(LOGGER, "No controller handle for controller '%s'. Aborting.", context.controllers_[i].c_str());
1433  return false;
1434  }
1435  active_handles_[i] = h;
1436  }
1437  handles = active_handles_; // keep a copy for later, to avoid thread safety issues
1438  for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1439  {
1440  bool ok = false;
1441  try
1442  {
1443  ok = active_handles_[i]->sendTrajectory(context.trajectory_parts_[i]);
1444  }
1445  catch (std::exception& ex)
1446  {
1447  RCLCPP_ERROR(LOGGER, "Caught %s when sending trajectory to controller", ex.what());
1448  }
1449  if (!ok)
1450  {
1451  for (std::size_t j = 0; j < i; ++j)
1452  try
1453  {
1454  active_handles_[j]->cancelExecution();
1455  }
1456  catch (std::exception& ex)
1457  {
1458  RCLCPP_ERROR(LOGGER, "Caught %s when canceling execution", ex.what());
1459  }
1460  RCLCPP_ERROR(LOGGER, "Failed to send trajectory part %zu of %zu to controller %s", i + 1,
1461  context.trajectory_parts_.size(), active_handles_[i]->getName().c_str());
1462  if (i > 0)
1463  RCLCPP_ERROR(LOGGER, "Cancelling previously sent trajectory parts");
1464  active_handles_.clear();
1465  current_context_ = -1;
1466  last_execution_status_ = moveit_controller_manager::ExecutionStatus::ABORTED;
1467  return false;
1468  }
1469  }
1470  }
1471  }
1472 
1473  // compute the expected duration of the trajectory and find the part of the trajectory that takes longest to execute
1474  rclcpp::Time current_time = node_->now();
1475  auto expected_trajectory_duration = rclcpp::Duration::from_seconds(0);
1476  int longest_part = -1;
1477  for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1478  {
1479  auto d = rclcpp::Duration::from_seconds(0);
1480  if (!(context.trajectory_parts_[i].joint_trajectory.points.empty() &&
1481  context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty()))
1482  {
1483  if (rclcpp::Time(context.trajectory_parts_[i].joint_trajectory.header.stamp) > current_time)
1484  d = rclcpp::Time(context.trajectory_parts_[i].joint_trajectory.header.stamp) - current_time;
1485  if (rclcpp::Time(context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp) > current_time)
1486  d = std::max(d, rclcpp::Time(context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp) -
1487  current_time);
1488  d = d +
1489  std::max(context.trajectory_parts_[i].joint_trajectory.points.empty() ?
1490  rclcpp::Duration::from_seconds(0) :
1491  rclcpp::Duration(context.trajectory_parts_[i].joint_trajectory.points.back().time_from_start),
1492  context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty() ?
1493  rclcpp::Duration::from_seconds(0) :
1494  rclcpp::Duration(
1495  context.trajectory_parts_[i].multi_dof_joint_trajectory.points.back().time_from_start));
1496 
1497  if (longest_part < 0 ||
1498  std::max(context.trajectory_parts_[i].joint_trajectory.points.size(),
1499  context.trajectory_parts_[i].multi_dof_joint_trajectory.points.size()) >
1500  std::max(context.trajectory_parts_[longest_part].joint_trajectory.points.size(),
1501  context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size()))
1502  longest_part = i;
1503  }
1504 
1505  // prefer controller-specific values over global ones if defined
1506  // TODO: the controller-specific parameters are static, but override
1507  // the global ones are configurable via dynamic reconfigure
1508  std::map<std::string, double>::const_iterator scaling_it =
1509  controller_allowed_execution_duration_scaling_.find(context.controllers_[i]);
1510  const double current_scaling = scaling_it != controller_allowed_execution_duration_scaling_.end() ?
1511  scaling_it->second :
1512  allowed_execution_duration_scaling_;
1513 
1514  std::map<std::string, double>::const_iterator margin_it =
1515  controller_allowed_goal_duration_margin_.find(context.controllers_[i]);
1516  const double current_margin = margin_it != controller_allowed_goal_duration_margin_.end() ?
1517  margin_it->second :
1518  allowed_goal_duration_margin_;
1519 
1520  // expected duration is the duration of the longest part
1521  expected_trajectory_duration =
1522  std::max(d * current_scaling + rclcpp::Duration::from_seconds(current_margin), expected_trajectory_duration);
1523  }
1524 
1525  // construct a map from expected time to state index, for easy access to expected state location
1526  if (longest_part >= 0)
1527  {
1528  std::scoped_lock slock(time_index_mutex_);
1529 
1530  if (context.trajectory_parts_[longest_part].joint_trajectory.points.size() >=
1531  context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size())
1532  {
1533  auto d = rclcpp::Duration::from_seconds(0);
1534  if (rclcpp::Time(context.trajectory_parts_[longest_part].joint_trajectory.header.stamp) > current_time)
1535  d = rclcpp::Time(context.trajectory_parts_[longest_part].joint_trajectory.header.stamp) - current_time;
1536  for (trajectory_msgs::msg::JointTrajectoryPoint& point :
1537  context.trajectory_parts_[longest_part].joint_trajectory.points)
1538  time_index_.push_back(current_time + d + rclcpp::Duration(point.time_from_start));
1539  }
1540  else
1541  {
1542  auto d = rclcpp::Duration::from_seconds(0);
1543  if (rclcpp::Time(context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp) > current_time)
1544  d = rclcpp::Time(context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp) -
1545  current_time;
1546  for (trajectory_msgs::msg::MultiDOFJointTrajectoryPoint& point :
1547  context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points)
1548  time_index_.push_back(current_time + d + rclcpp::Duration(point.time_from_start));
1549  }
1550  }
1551 
1552  bool result = true;
1553  for (moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
1554  {
1555  if (execution_duration_monitoring_)
1556  {
1557  if (!handle->waitForExecution(expected_trajectory_duration))
1558  if (!execution_complete_ && node_->now() - current_time > expected_trajectory_duration)
1559  {
1560  RCLCPP_ERROR(LOGGER,
1561  "Controller is taking too long to execute trajectory (the expected upper "
1562  "bound for the trajectory execution was %lf seconds). Stopping trajectory.",
1563  expected_trajectory_duration.seconds());
1564  {
1565  std::scoped_lock slock(execution_state_mutex_);
1566  stopExecutionInternal(); // this is really tricky. we can't call stopExecution() here, so we call the
1567  // internal function only
1568  }
1570  result = false;
1571  break;
1572  }
1573  }
1574  else
1575  handle->waitForExecution();
1576 
1577  // if something made the trajectory stop, we stop this thread too
1578  if (execution_complete_)
1579  {
1580  result = false;
1581  break;
1582  }
1583  else if (handle->getLastExecutionStatus() != moveit_controller_manager::ExecutionStatus::SUCCEEDED)
1584  {
1585  RCLCPP_WARN_STREAM(LOGGER, "Controller handle " << handle->getName() << " reports status "
1586  << handle->getLastExecutionStatus().asString());
1587  last_execution_status_ = handle->getLastExecutionStatus();
1588  result = false;
1589  }
1590  }
1591 
1592  // clear the active handles
1593  execution_state_mutex_.lock();
1594  active_handles_.clear();
1595 
1596  // clear the time index
1597  time_index_mutex_.lock();
1598  time_index_.clear();
1599  current_context_ = -1;
1600  time_index_mutex_.unlock();
1601 
1602  execution_state_mutex_.unlock();
1603  return result;
1604  }
1605  else
1606  {
1607  RCLCPP_ERROR(LOGGER, "Active status of required controllers can not be assured.");
1608  last_execution_status_ = moveit_controller_manager::ExecutionStatus::ABORTED;
1609  return false;
1610  }
1611 }
1612 
1613 bool TrajectoryExecutionManager::waitForRobotToStop(const TrajectoryExecutionContext& context, double wait_time)
1614 {
1615  // skip waiting for convergence?
1616  if (allowed_start_tolerance_ == 0 || !wait_for_trajectory_completion_)
1617  {
1618  RCLCPP_INFO(LOGGER, "Not waiting for trajectory completion");
1619  return true;
1620  }
1621 
1622  auto start = std::chrono::system_clock::now();
1623  double time_remaining = wait_time;
1624 
1625  moveit::core::RobotStatePtr prev_state, cur_state;
1626  prev_state = csm_->getCurrentState();
1627  prev_state->enforceBounds();
1628 
1629  // assume robot stopped when 3 consecutive checks yield the same robot state
1630  unsigned int no_motion_count = 0; // count iterations with no motion
1631  while (time_remaining > 0. && no_motion_count < 3)
1632  {
1633  if (!csm_->waitForCurrentState(node_->now(), time_remaining) || !(cur_state = csm_->getCurrentState()))
1634  {
1635  RCLCPP_WARN(LOGGER, "Failed to receive current joint state");
1636  return false;
1637  }
1638  cur_state->enforceBounds();
1639  std::chrono::duration<double> elapsed_seconds = std::chrono::system_clock::now() - start;
1640  time_remaining = wait_time - elapsed_seconds.count(); // remaining wait_time
1641 
1642  // check for motion in effected joints of execution context
1643  bool moved = false;
1644  for (const auto& trajectory : context.trajectory_parts_)
1645  {
1646  const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1647  const std::size_t n = joint_names.size();
1648 
1649  for (std::size_t i = 0; i < n && !moved; ++i)
1650  {
1651  const moveit::core::JointModel* jm = cur_state->getJointModel(joint_names[i]);
1652  if (!jm)
1653  continue; // joint vanished from robot state (shouldn't happen), but we don't care
1654 
1655  if (fabs(cur_state->getJointPositions(jm)[0] - prev_state->getJointPositions(jm)[0]) > allowed_start_tolerance_)
1656  {
1657  moved = true;
1658  no_motion_count = 0;
1659  break;
1660  }
1661  }
1662  }
1663 
1664  if (!moved)
1665  ++no_motion_count;
1666 
1667  std::swap(prev_state, cur_state);
1668  }
1669 
1670  return time_remaining > 0;
1671 }
1672 
1674 {
1675  std::scoped_lock slock(time_index_mutex_);
1676  if (current_context_ < 0)
1677  return std::make_pair(-1, -1);
1678  if (time_index_.empty())
1679  return std::make_pair(static_cast<int>(current_context_), -1);
1680  std::vector<rclcpp::Time>::const_iterator time_index_it =
1681  std::lower_bound(time_index_.begin(), time_index_.end(), node_->now());
1682  int pos = time_index_it - time_index_.begin();
1683  return std::make_pair(static_cast<int>(current_context_), pos);
1684 }
1685 
1686 const std::vector<TrajectoryExecutionManager::TrajectoryExecutionContext*>&
1688 {
1689  return trajectories_;
1690 }
1691 
1693 {
1694  return last_execution_status_;
1695 }
1696 
1698 {
1699  const moveit::core::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group);
1700  if (joint_model_group)
1701  return ensureActiveControllersForJoints(joint_model_group->getJointModelNames());
1702  else
1703  return false;
1704 }
1705 
1706 bool TrajectoryExecutionManager::ensureActiveControllersForJoints(const std::vector<std::string>& joints)
1707 {
1708  std::vector<std::string> all_controller_names;
1709  for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1710  it != known_controllers_.end(); ++it)
1711  all_controller_names.push_back(it->first);
1712  std::vector<std::string> selected_controllers;
1713  std::set<std::string> jset;
1714  for (const std::string& joint : joints)
1715  {
1716  const moveit::core::JointModel* jm = robot_model_->getJointModel(joint);
1717  if (jm)
1718  {
1719  if (jm->isPassive() || jm->getMimic() != nullptr || jm->getType() == moveit::core::JointModel::FIXED)
1720  continue;
1721  jset.insert(joint);
1722  }
1723  }
1724 
1725  if (selectControllers(jset, all_controller_names, selected_controllers))
1726  return ensureActiveControllers(selected_controllers);
1727  else
1728  return false;
1729 }
1730 
1731 bool TrajectoryExecutionManager::ensureActiveController(const std::string& controller)
1732 {
1733  return ensureActiveControllers(std::vector<std::string>(1, controller));
1734 }
1735 
1736 bool TrajectoryExecutionManager::ensureActiveControllers(const std::vector<std::string>& controllers)
1737 {
1738  reloadControllerInformation();
1739 
1740  updateControllersState(DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
1741 
1742  if (manage_controllers_)
1743  {
1744  std::vector<std::string> controllers_to_activate;
1745  std::vector<std::string> controllers_to_deactivate;
1746  std::set<std::string> joints_to_be_activated;
1747  std::set<std::string> joints_to_be_deactivated;
1748  for (const std::string& controller : controllers)
1749  {
1750  std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.find(controller);
1751  if (it == known_controllers_.end())
1752  {
1753  std::stringstream stream;
1754  for (const auto& controller : known_controllers_)
1755  {
1756  stream << " `" << controller.first << "`";
1757  }
1758  RCLCPP_WARN_STREAM(LOGGER, "Controller " << controller << " is not known. Known controllers: " << stream.str());
1759  return false;
1760  }
1761  if (!it->second.state_.active_)
1762  {
1763  RCLCPP_DEBUG_STREAM(LOGGER, "Need to activate " << controller);
1764  controllers_to_activate.push_back(controller);
1765  joints_to_be_activated.insert(it->second.joints_.begin(), it->second.joints_.end());
1766  for (const std::string& overlapping_controller : it->second.overlapping_controllers_)
1767  {
1768  const ControllerInformation& ci = known_controllers_[overlapping_controller];
1769  if (ci.state_.active_)
1770  {
1771  controllers_to_deactivate.push_back(overlapping_controller);
1772  joints_to_be_deactivated.insert(ci.joints_.begin(), ci.joints_.end());
1773  }
1774  }
1775  }
1776  else
1777  RCLCPP_DEBUG_STREAM(LOGGER, "Controller " << controller << " is already active");
1778  }
1779  std::set<std::string> diff;
1780  std::set_difference(joints_to_be_deactivated.begin(), joints_to_be_deactivated.end(),
1781  joints_to_be_activated.begin(), joints_to_be_activated.end(), std::inserter(diff, diff.end()));
1782  if (!diff.empty())
1783  {
1784  // find the set of controllers that do not overlap with the ones we want to activate so far
1785  std::vector<std::string> possible_additional_controllers;
1786  for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1787  it != known_controllers_.end(); ++it)
1788  {
1789  bool ok = true;
1790  for (const std::string& controller_to_activate : controllers_to_activate)
1791  if (it->second.overlapping_controllers_.find(controller_to_activate) !=
1792  it->second.overlapping_controllers_.end())
1793  {
1794  ok = false;
1795  break;
1796  }
1797  if (ok)
1798  possible_additional_controllers.push_back(it->first);
1799  }
1800 
1801  // out of the allowable controllers, try to find a subset of controllers that covers the joints to be actuated
1802  std::vector<std::string> additional_controllers;
1803  if (selectControllers(diff, possible_additional_controllers, additional_controllers))
1804  controllers_to_activate.insert(controllers_to_activate.end(), additional_controllers.begin(),
1805  additional_controllers.end());
1806  else
1807  return false;
1808  }
1809  if (!controllers_to_activate.empty() || !controllers_to_deactivate.empty())
1810  {
1811  if (controller_manager_)
1812  {
1813  // load controllers to be activated, if needed, and reset the state update cache
1814  for (const std::string& controller_to_activate : controllers_to_activate)
1815  {
1816  ControllerInformation& ci = known_controllers_[controller_to_activate];
1817  ci.last_update_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
1818  }
1819  // reset the state update cache
1820  for (const std::string& controller_to_activate : controllers_to_deactivate)
1821  known_controllers_[controller_to_activate].last_update_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
1822  return controller_manager_->switchControllers(controllers_to_activate, controllers_to_deactivate);
1823  }
1824  else
1825  return false;
1826  }
1827  else
1828  return true;
1829  }
1830  else
1831  {
1832  std::set<std::string> originally_active;
1833  for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1834  it != known_controllers_.end(); ++it)
1835  {
1836  if (it->second.state_.active_)
1837  {
1838  originally_active.insert(it->first);
1839  }
1840  }
1841  return std::includes(originally_active.begin(), originally_active.end(), controllers.begin(), controllers.end());
1842  }
1843 }
1844 
1845 void TrajectoryExecutionManager::loadControllerParams()
1846 {
1847  for (const auto& controller : known_controllers_)
1848  {
1849  const std::string& controller_name = controller.first;
1850  for (const auto& controller_manager_name : controller_manager_loader_->getDeclaredClasses())
1851  {
1852  const std::string parameter_prefix =
1853  controller_manager_loader_->getClassPackage(controller_manager_name) + "." + controller_name;
1854 
1855  double allowed_execution_duration_scaling;
1856  if (node_->get_parameter(parameter_prefix + ".allowed_execution_duration_scaling",
1857  allowed_execution_duration_scaling))
1858  controller_allowed_execution_duration_scaling_.insert({ controller_name, allowed_execution_duration_scaling });
1859 
1860  double allowed_goal_duration_margin;
1861  if (node_->get_parameter(parameter_prefix + ".allowed_goal_duration_margin", allowed_goal_duration_margin))
1862  controller_allowed_goal_duration_margin_.insert({ controller_name, allowed_goal_duration_margin });
1863  }
1864  }
1865 }
1866 } // namespace trajectory_execution_manager
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
virtual double distance(const double *value1, const double *value2) const =0
Compute the distance between two joint states of the same model (represented by the variable values)
bool isPassive() const
Check if this joint is passive.
Definition: joint_model.h:422
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
Definition: joint_model.h:292
JointType getType() const
Get the type of joint.
Definition: joint_model.h:151
const JointModel * getMimic() const
Get the joint this one is mimicking.
Definition: joint_model.h:372
TrajectoryExecutionManager(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &robot_model, const planning_scene_monitor::CurrentStateMonitorPtr &csm)
Load the controller manager plugin, start listening for events on a topic.
~TrajectoryExecutionManager()
Destructor. Cancels all running trajectories (if any)
void execute(const ExecutionCompleteCallback &callback=ExecutionCompleteCallback(), bool auto_clear=true)
Start the execution of pushed trajectories; this does not wait for completion, but calls a callback w...
void stopExecution(bool auto_clear=true)
Stop whatever executions are active, if any.
void setWaitForTrajectoryCompletion(bool flag)
Enable or disable waiting for trajectory completion.
bool ensureActiveControllersForGroup(const std::string &group)
Make sure the active controllers are such that trajectories that actuate joints in the specified grou...
const std::vector< TrajectoryExecutionContext * > & getTrajectories() const
Get the trajectories to be executed.
std::function< void(const moveit_controller_manager::ExecutionStatus &)> ExecutionCompleteCallback
bool ensureActiveController(const std::string &controller)
Make sure a particular controller is active.
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() const
Return the controller status for the last attempted execution.
bool pushAndExecute(const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &controller="")
bool push(const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &controller="")
bool isManagingControllers() const
If this function returns true, then this instance of the manager is allowed to load/unload/switch con...
bool isControllerActive(const std::string &controller)
Check if a controller is active.
moveit_controller_manager::ExecutionStatus executeAndWait(bool auto_clear=true)
void setAllowedStartTolerance(double tolerance)
Set joint-value tolerance for validating trajectory's start point against current robot state.
void processEvent(const std::string &event)
Execute a named event (e.g., 'stop')
bool areControllersActive(const std::vector< std::string > &controllers)
Check if a set of controllers are active.
bool ensureActiveControllersForJoints(const std::vector< std::string > &joints)
Make sure the active controllers are such that trajectories that actuate joints in the specified set ...
bool ensureActiveControllers(const std::vector< std::string > &controllers)
Make sure a particular set of controllers are active.
const moveit_controller_manager::MoveItControllerManagerPtr & getControllerManager() const
Get the instance of the controller manager used (this is the plugin instance loaded)
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
a
Definition: plan.py:54
d
Definition: setup.py:4
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31
std::string asString() const
Convert the execution status to a string.
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::size_t > nrjoints
std::vector< std::size_t > nrdefault
std::vector< std::size_t > nractive
std::vector< std::vector< std::string > > selected_options