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