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