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 <moveit_ros_planning/TrajectoryExecutionDynamicReconfigureConfig.h>
41 #include <dynamic_reconfigure/server.h>
42 #include <tf2_eigen/tf2_eigen.h>
43 
44 // Name of this class for logging
45 static const std::string LOGNAME = "trajectory_execution_manager";
46 
48 {
49 const std::string TrajectoryExecutionManager::EXECUTION_EVENT_TOPIC = "trajectory_execution_event";
50 
52 static const double DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN = 0.5; // allow 0.5s more than the expected execution time
53  // before triggering a trajectory cancel (applied
54  // after scaling)
56  1.1; // allow the execution of a trajectory to take more time than expected (scaled by a value > 1)
57 
58 using namespace moveit_ros_planning;
59 
61 {
62 public:
64  : owner_(owner), dynamic_reconfigure_server_(ros::NodeHandle("~/trajectory_execution"))
65  {
66  dynamic_reconfigure_server_.setCallback(
67  [this](const auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
68  }
69 
70 private:
71  void dynamicReconfigureCallback(const TrajectoryExecutionDynamicReconfigureConfig& config, uint32_t /*level*/)
72  {
73  owner_->enableExecutionDurationMonitoring(config.execution_duration_monitoring);
74  owner_->setAllowedExecutionDurationScaling(config.allowed_execution_duration_scaling);
75  owner_->setAllowedGoalDurationMargin(config.allowed_goal_duration_margin);
76  owner_->setExecutionVelocityScaling(config.execution_velocity_scaling);
77  owner_->setAllowedStartTolerance(config.allowed_start_tolerance);
78  owner_->setWaitForTrajectoryCompletion(config.wait_for_trajectory_completion);
79  }
80 
82  dynamic_reconfigure::Server<TrajectoryExecutionDynamicReconfigureConfig> dynamic_reconfigure_server_;
83 };
84 
85 TrajectoryExecutionManager::TrajectoryExecutionManager(const moveit::core::RobotModelConstPtr& robot_model,
86  const planning_scene_monitor::CurrentStateMonitorPtr& csm)
87  : robot_model_(robot_model), csm_(csm), node_handle_("~")
88 {
89  if (!node_handle_.getParam("moveit_manage_controllers", manage_controllers_))
90  manage_controllers_ = false;
91 
92  initialize();
93 }
94 
95 TrajectoryExecutionManager::TrajectoryExecutionManager(const moveit::core::RobotModelConstPtr& robot_model,
96  const planning_scene_monitor::CurrentStateMonitorPtr& csm,
97  bool manage_controllers)
98  : robot_model_(robot_model), csm_(csm), node_handle_("~"), manage_controllers_(manage_controllers)
99 {
100  initialize();
101 }
102 
104 {
105  stopExecution(true);
106  delete reconfigure_impl_;
107 }
108 
110 {
111  reconfigure_impl_ = nullptr;
112  verbose_ = false;
113  execution_complete_ = true;
114  current_context_ = -1;
120 
123 
124  // load controller-specific values for allowed_execution_duration_scaling and allowed_goal_duration_margin
126 
127  // load the controller manager plugin
128  try
129  {
131  std::make_unique<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager>>(
132  "moveit_core", "moveit_controller_manager::MoveItControllerManager");
133  }
135  {
136  ROS_FATAL_STREAM_NAMED(LOGNAME, "Exception while creating controller manager plugin loader: " << ex.what());
137  return;
138  }
139 
141  {
142  std::string controller;
143  if (!node_handle_.getParam("moveit_controller_manager", controller))
144  {
145  const std::vector<std::string>& classes = controller_manager_loader_->getDeclaredClasses();
146  if (classes.size() == 1)
147  {
148  controller = classes[0];
150  "Parameter '~moveit_controller_manager' is not specified but only one "
151  "matching plugin was found: '%s'. Using that one.",
152  controller.c_str());
153  }
154  else
155  ROS_FATAL_NAMED(LOGNAME, "Parameter '~moveit_controller_manager' not specified. This is needed to "
156  "identify the plugin to use for interacting with controllers. No paths can "
157  "be executed.");
158  }
159 
160  if (!controller.empty())
161  try
162  {
163  controller_manager_ = controller_manager_loader_->createUniqueInstance(controller);
164  }
166  {
168  "Exception while loading controller manager '" << controller << "': " << ex.what());
169  }
170  }
171 
172  // other configuration steps
174 
177 
179 
181 
183  ROS_INFO_NAMED(LOGNAME, "Trajectory execution is managing controllers");
184  else
185  ROS_INFO_NAMED(LOGNAME, "Trajectory execution is not managing controllers");
186 }
187 
189 {
191 }
192 
194 {
196 }
197 
199 {
201 }
202 
204 {
205  execution_velocity_scaling_ = scaling;
206 }
207 
209 {
211 }
212 
214 {
216 }
217 
219 {
220  return manage_controllers_;
221 }
222 
223 const moveit_controller_manager::MoveItControllerManagerPtr& TrajectoryExecutionManager::getControllerManager() const
224 {
225  return controller_manager_;
226 }
227 
228 void TrajectoryExecutionManager::processEvent(const std::string& event)
229 {
230  if (event == "stop")
231  stopExecution(true);
232  else
233  ROS_WARN_STREAM_NAMED(LOGNAME, "Unknown event type: '" << event << "'");
234 }
235 
236 void TrajectoryExecutionManager::receiveEvent(const std_msgs::StringConstPtr& event)
237 {
238  ROS_INFO_STREAM_NAMED(LOGNAME, "Received event '" << event->data << "'");
239  processEvent(event->data);
240 }
241 
242 bool TrajectoryExecutionManager::push(const moveit_msgs::RobotTrajectory& trajectory, const std::string& controller)
243 {
244  if (controller.empty())
245  return push(trajectory, std::vector<std::string>());
246  else
247  return push(trajectory, std::vector<std::string>(1, controller));
248 }
249 
250 bool TrajectoryExecutionManager::push(const trajectory_msgs::JointTrajectory& trajectory, const std::string& controller)
251 {
252  if (controller.empty())
253  return push(trajectory, std::vector<std::string>());
254  else
255  return push(trajectory, std::vector<std::string>(1, controller));
256 }
257 
258 bool TrajectoryExecutionManager::push(const trajectory_msgs::JointTrajectory& trajectory,
259  const std::vector<std::string>& controllers)
260 {
261  moveit_msgs::RobotTrajectory traj;
262  traj.joint_trajectory = trajectory;
263  return push(traj, controllers);
264 }
265 
266 bool TrajectoryExecutionManager::push(const moveit_msgs::RobotTrajectory& trajectory,
267  const std::vector<std::string>& controllers)
268 {
269  if (!execution_complete_)
270  {
271  ROS_ERROR_NAMED(LOGNAME, "Cannot push a new trajectory while another is being executed");
272  return false;
273  }
274 
276  if (configure(*context, trajectory, controllers))
277  {
278  if (verbose_)
279  {
280  std::stringstream ss;
281  ss << "Pushed trajectory for execution using controllers [ ";
282  for (const std::string& controller : context->controllers_)
283  ss << controller << " ";
284  ss << "]:" << std::endl;
285  for (const moveit_msgs::RobotTrajectory& trajectory_part : context->trajectory_parts_)
286  ss << trajectory_part << std::endl;
287  ROS_INFO_NAMED(LOGNAME, "%s", ss.str().c_str());
288  }
289  trajectories_.push_back(context);
290  return true;
291  }
292  else
293  {
294  delete context;
296  }
297 
298  return false;
299 }
300 
302 {
303  known_controllers_.clear();
305  {
306  std::vector<std::string> names;
307  controller_manager_->getControllersList(names);
308  for (const std::string& name : names)
309  {
310  std::vector<std::string> joints;
311  controller_manager_->getControllerJoints(name, joints);
313  ci.name_ = name;
314  ci.joints_.insert(joints.begin(), joints.end());
315  known_controllers_[ci.name_] = ci;
316  }
317 
318  for (std::map<std::string, ControllerInformation>::iterator it = known_controllers_.begin();
319  it != known_controllers_.end(); ++it)
320  for (std::map<std::string, ControllerInformation>::iterator jt = known_controllers_.begin();
321  jt != known_controllers_.end(); ++jt)
322  if (it != jt)
323  {
324  std::vector<std::string> intersect;
325  std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), jt->second.joints_.begin(),
326  jt->second.joints_.end(), std::back_inserter(intersect));
327  if (!intersect.empty())
328  {
329  it->second.overlapping_controllers_.insert(jt->first);
330  jt->second.overlapping_controllers_.insert(it->first);
331  }
332  }
333  }
334 }
335 
336 void TrajectoryExecutionManager::updateControllerState(const std::string& controller, const ros::Duration& age)
337 {
338  std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
339  if (it != known_controllers_.end())
340  updateControllerState(it->second, age);
341  else
342  ROS_ERROR_NAMED(LOGNAME, "Controller '%s' is not known.", controller.c_str());
343 }
344 
346 {
347  if (ros::Time::now() - ci.last_update_ >= age)
348  {
350  {
351  if (verbose_)
352  ROS_INFO_NAMED(LOGNAME, "Updating information for controller '%s'.", ci.name_.c_str());
353  ci.state_ = controller_manager_->getControllerState(ci.name_);
355  }
356  }
357  else if (verbose_)
358  ROS_INFO_NAMED(LOGNAME, "Information for controller '%s' is assumed to be up to date.", ci.name_.c_str());
359 }
360 
362 {
363  for (std::pair<const std::string, ControllerInformation>& known_controller : known_controllers_)
364  updateControllerState(known_controller.second, age);
365 }
366 
367 bool TrajectoryExecutionManager::checkControllerCombination(std::vector<std::string>& selected,
368  const std::set<std::string>& actuated_joints)
369 {
370  std::set<std::string> combined_joints;
371  for (const std::string& controller : selected)
372  {
373  const ControllerInformation& ci = known_controllers_[controller];
374  combined_joints.insert(ci.joints_.begin(), ci.joints_.end());
375  }
376 
377  if (verbose_)
378  {
379  std::stringstream ss, saj, sac;
380  for (const std::string& controller : selected)
381  ss << controller << " ";
382  for (const std::string& actuated_joint : actuated_joints)
383  saj << actuated_joint << " ";
384  for (const std::string& combined_joint : combined_joints)
385  sac << combined_joint << " ";
386  ROS_INFO_NAMED(LOGNAME, "Checking if controllers [ %s] operating on joints [ %s] cover joints [ %s]",
387  ss.str().c_str(), sac.str().c_str(), saj.str().c_str());
388  }
389 
390  return std::includes(combined_joints.begin(), combined_joints.end(), actuated_joints.begin(), actuated_joints.end());
391 }
392 
393 void TrajectoryExecutionManager::generateControllerCombination(std::size_t start_index, std::size_t controller_count,
394  const std::vector<std::string>& available_controllers,
395  std::vector<std::string>& selected_controllers,
396  std::vector<std::vector<std::string>>& selected_options,
397  const std::set<std::string>& actuated_joints)
398 {
399  if (selected_controllers.size() == controller_count)
400  {
401  if (checkControllerCombination(selected_controllers, actuated_joints))
402  selected_options.push_back(selected_controllers);
403  return;
404  }
405 
406  for (std::size_t i = start_index; i < available_controllers.size(); ++i)
407  {
408  bool overlap = false;
409  const ControllerInformation& ci = known_controllers_[available_controllers[i]];
410  for (std::size_t j = 0; j < selected_controllers.size() && !overlap; ++j)
411  {
412  if (ci.overlapping_controllers_.find(selected_controllers[j]) != ci.overlapping_controllers_.end())
413  overlap = true;
414  }
415  if (overlap)
416  continue;
417  selected_controllers.push_back(available_controllers[i]);
418  generateControllerCombination(i + 1, controller_count, available_controllers, selected_controllers,
419  selected_options, actuated_joints);
420  selected_controllers.pop_back();
421  }
422 }
423 
424 namespace
425 {
426 struct OrderPotentialControllerCombination
427 {
428  bool operator()(const std::size_t a, const std::size_t b) const
429  {
430  // preference is given to controllers marked as default
431  if (nrdefault[a] > nrdefault[b])
432  return true;
433  if (nrdefault[a] < nrdefault[b])
434  return false;
435 
436  // and then to ones that operate on fewer joints
437  if (nrjoints[a] < nrjoints[b])
438  return true;
439  if (nrjoints[a] > nrjoints[b])
440  return false;
441 
442  // and then to active ones
443  if (nractive[a] < nractive[b])
444  return true;
445  if (nractive[a] > nractive[b])
446  return false;
447 
448  return false;
449  }
450 
451  std::vector<std::vector<std::string>> selected_options;
452  std::vector<std::size_t> nrdefault;
453  std::vector<std::size_t> nrjoints;
454  std::vector<std::size_t> nractive;
455 };
456 } // namespace
457 
458 bool TrajectoryExecutionManager::findControllers(const std::set<std::string>& actuated_joints,
459  std::size_t controller_count,
460  const std::vector<std::string>& available_controllers,
461  std::vector<std::string>& selected_controllers)
462 {
463  // generate all combinations of controller_count controllers that operate on disjoint sets of joints
464  std::vector<std::string> work_area;
465  OrderPotentialControllerCombination order;
466  std::vector<std::vector<std::string>>& selected_options = order.selected_options;
467  generateControllerCombination(0, controller_count, available_controllers, work_area, selected_options,
468  actuated_joints);
469 
470  if (verbose_)
471  {
472  std::stringstream saj;
473  std::stringstream sac;
474  for (const std::string& available_controller : available_controllers)
475  sac << available_controller << " ";
476  for (const std::string& actuated_joint : actuated_joints)
477  saj << actuated_joint << " ";
478  ROS_INFO_NAMED(LOGNAME, "Looking for %zu controllers among [ %s] that cover joints [ %s]. Found %zd options.",
479  controller_count, sac.str().c_str(), saj.str().c_str(), selected_options.size());
480  }
481 
482  // if none was found, this is a problem
483  if (selected_options.empty())
484  return false;
485 
486  // if only one was found, return it
487  if (selected_options.size() == 1)
488  {
489  selected_controllers.swap(selected_options[0]);
490  return true;
491  }
492 
493  // if more options were found, evaluate them all and return the best one
494 
495  // count how many default controllers are used in each reported option, and how many joints are actuated in total by
496  // the selected controllers,
497  // to use that in the ranking of the options
498  order.nrdefault.resize(selected_options.size(), 0);
499  order.nrjoints.resize(selected_options.size(), 0);
500  order.nractive.resize(selected_options.size(), 0);
501  for (std::size_t i = 0; i < selected_options.size(); ++i)
502  {
503  for (std::size_t k = 0; k < selected_options[i].size(); ++k)
504  {
507 
508  if (ci.state_.default_)
509  order.nrdefault[i]++;
510  if (ci.state_.active_)
511  order.nractive[i]++;
512  order.nrjoints[i] += ci.joints_.size();
513  }
514  }
515 
516  // define a bijection to compute the raking of the found options
517  std::vector<std::size_t> bijection(selected_options.size(), 0);
518  for (std::size_t i = 0; i < selected_options.size(); ++i)
519  bijection[i] = i;
520 
521  // sort the options
522  std::sort(bijection.begin(), bijection.end(), order);
523 
524  // depending on whether we are allowed to load & unload controllers,
525  // we have different preference on deciding between options
526  if (!manage_controllers_)
527  {
528  // if we can't load different options at will, just choose one that is already loaded
529  for (std::size_t i = 0; i < selected_options.size(); ++i)
530  if (areControllersActive(selected_options[bijection[i]]))
531  {
532  selected_controllers.swap(selected_options[bijection[i]]);
533  return true;
534  }
535  }
536 
537  // otherwise, just use the first valid option
538  selected_controllers.swap(selected_options[bijection[0]]);
539  return true;
540 }
541 
542 bool TrajectoryExecutionManager::isControllerActive(const std::string& controller)
543 {
544  return areControllersActive(std::vector<std::string>(1, controller));
545 }
546 
547 bool TrajectoryExecutionManager::areControllersActive(const std::vector<std::string>& controllers)
548 {
549  for (const std::string& controller : controllers)
550  {
552  std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
553  if (it == known_controllers_.end() || !it->second.state_.active_)
554  return false;
555  }
556  return true;
557 }
558 
559 bool TrajectoryExecutionManager::selectControllers(const std::set<std::string>& actuated_joints,
560  const std::vector<std::string>& available_controllers,
561  std::vector<std::string>& selected_controllers)
562 {
563  for (std::size_t i = 1; i <= available_controllers.size(); ++i)
564  if (findControllers(actuated_joints, i, available_controllers, selected_controllers))
565  {
566  // if we are not managing controllers, prefer to use active controllers even if there are more of them
567  if (!manage_controllers_ && !areControllersActive(selected_controllers))
568  {
569  std::vector<std::string> other_option;
570  for (std::size_t j = i + 1; j <= available_controllers.size(); ++j)
571  if (findControllers(actuated_joints, j, available_controllers, other_option))
572  {
573  if (areControllersActive(other_option))
574  {
575  selected_controllers = other_option;
576  break;
577  }
578  }
579  }
580  return true;
581  }
582  return false;
583 }
584 
585 bool TrajectoryExecutionManager::distributeTrajectory(const moveit_msgs::RobotTrajectory& trajectory,
586  const std::vector<std::string>& controllers,
587  std::vector<moveit_msgs::RobotTrajectory>& parts)
588 {
589  parts.clear();
590  parts.resize(controllers.size());
591 
592  std::set<std::string> actuated_joints_mdof;
593  actuated_joints_mdof.insert(trajectory.multi_dof_joint_trajectory.joint_names.begin(),
594  trajectory.multi_dof_joint_trajectory.joint_names.end());
595  std::set<std::string> actuated_joints_single;
596  for (const std::string& joint_name : trajectory.joint_trajectory.joint_names)
597  {
598  const moveit::core::JointModel* jm = robot_model_->getJointModel(joint_name);
599  if (jm)
600  {
601  if (jm->isPassive() || jm->getMimic() != nullptr || jm->getType() == moveit::core::JointModel::FIXED)
602  continue;
603  actuated_joints_single.insert(jm->getName());
604  }
605  }
606 
607  for (std::size_t i = 0; i < controllers.size(); ++i)
608  {
609  std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controllers[i]);
610  if (it == known_controllers_.end())
611  {
612  ROS_ERROR_STREAM_NAMED(LOGNAME, "Controller " << controllers[i] << " not found.");
613  return false;
614  }
615  std::vector<std::string> intersect_mdof;
616  std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_mdof.begin(),
617  actuated_joints_mdof.end(), std::back_inserter(intersect_mdof));
618  std::vector<std::string> intersect_single;
619  std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_single.begin(),
620  actuated_joints_single.end(), std::back_inserter(intersect_single));
621  if (intersect_mdof.empty() && intersect_single.empty())
622  ROS_WARN_STREAM_NAMED(LOGNAME, "No joints to be distributed for controller " << controllers[i]);
623  {
624  if (!intersect_mdof.empty())
625  {
626  std::vector<std::string>& jnames = parts[i].multi_dof_joint_trajectory.joint_names;
627  jnames.insert(jnames.end(), intersect_mdof.begin(), intersect_mdof.end());
628  std::map<std::string, std::size_t> index;
629  for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
630  index[trajectory.multi_dof_joint_trajectory.joint_names[j]] = j;
631  std::vector<std::size_t> bijection(jnames.size());
632  for (std::size_t j = 0; j < jnames.size(); ++j)
633  bijection[j] = index[jnames[j]];
634 
635  parts[i].multi_dof_joint_trajectory.points.resize(trajectory.multi_dof_joint_trajectory.points.size());
636  for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.points.size(); ++j)
637  {
638  parts[i].multi_dof_joint_trajectory.points[j].time_from_start =
639  trajectory.multi_dof_joint_trajectory.points[j].time_from_start;
640  parts[i].multi_dof_joint_trajectory.points[j].transforms.resize(bijection.size());
641  for (std::size_t k = 0; k < bijection.size(); ++k)
642  {
643  parts[i].multi_dof_joint_trajectory.points[j].transforms[k] =
644  trajectory.multi_dof_joint_trajectory.points[j].transforms[bijection[k]];
645 
646  if (!trajectory.multi_dof_joint_trajectory.points[j].velocities.empty())
647  {
648  parts[i].multi_dof_joint_trajectory.points[j].velocities.resize(bijection.size());
649 
650  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.x =
651  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.x * execution_velocity_scaling_;
652 
653  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.y =
654  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.y * execution_velocity_scaling_;
655 
656  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.z =
657  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.z * execution_velocity_scaling_;
658 
659  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.x =
660  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.x * execution_velocity_scaling_;
661 
662  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.y =
663  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.y * execution_velocity_scaling_;
664 
665  parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.z =
666  trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.z * execution_velocity_scaling_;
667  }
668  }
669  }
670  }
671  if (!intersect_single.empty())
672  {
673  std::vector<std::string>& jnames = parts[i].joint_trajectory.joint_names;
674  jnames.insert(jnames.end(), intersect_single.begin(), intersect_single.end());
675  parts[i].joint_trajectory.header = trajectory.joint_trajectory.header;
676  std::map<std::string, std::size_t> index;
677  for (std::size_t j = 0; j < trajectory.joint_trajectory.joint_names.size(); ++j)
678  index[trajectory.joint_trajectory.joint_names[j]] = j;
679  std::vector<std::size_t> bijection(jnames.size());
680  for (std::size_t j = 0; j < jnames.size(); ++j)
681  bijection[j] = index[jnames[j]];
682  parts[i].joint_trajectory.points.resize(trajectory.joint_trajectory.points.size());
683  for (std::size_t j = 0; j < trajectory.joint_trajectory.points.size(); ++j)
684  {
685  parts[i].joint_trajectory.points[j].time_from_start = trajectory.joint_trajectory.points[j].time_from_start;
686  if (!trajectory.joint_trajectory.points[j].positions.empty())
687  {
688  parts[i].joint_trajectory.points[j].positions.resize(bijection.size());
689  for (std::size_t k = 0; k < bijection.size(); ++k)
690  parts[i].joint_trajectory.points[j].positions[k] =
691  trajectory.joint_trajectory.points[j].positions[bijection[k]];
692  }
693  if (!trajectory.joint_trajectory.points[j].velocities.empty())
694  {
695  parts[i].joint_trajectory.points[j].velocities.resize(bijection.size());
696  for (std::size_t k = 0; k < bijection.size(); ++k)
697  parts[i].joint_trajectory.points[j].velocities[k] =
698  trajectory.joint_trajectory.points[j].velocities[bijection[k]] * execution_velocity_scaling_;
699  }
700  if (!trajectory.joint_trajectory.points[j].accelerations.empty())
701  {
702  parts[i].joint_trajectory.points[j].accelerations.resize(bijection.size());
703  for (std::size_t k = 0; k < bijection.size(); ++k)
704  parts[i].joint_trajectory.points[j].accelerations[k] =
705  trajectory.joint_trajectory.points[j].accelerations[bijection[k]];
706  }
707  if (!trajectory.joint_trajectory.points[j].effort.empty())
708  {
709  parts[i].joint_trajectory.points[j].effort.resize(bijection.size());
710  for (std::size_t k = 0; k < bijection.size(); ++k)
711  parts[i].joint_trajectory.points[j].effort[k] =
712  trajectory.joint_trajectory.points[j].effort[bijection[k]];
713  }
714  }
715  }
716  }
717  }
718  return true;
719 }
720 
722 {
723  if (allowed_start_tolerance_ == 0 && joints_allowed_start_tolerance_.empty()) // skip validation on this magic number
724  return true;
725 
726  ROS_DEBUG_NAMED(LOGNAME, "Validating trajectory with allowed_start_tolerance %g", allowed_start_tolerance_);
727 
728  moveit::core::RobotStatePtr current_state;
729  if (!csm_->waitForCurrentState(ros::Time::now()) || !(current_state = csm_->getCurrentState()))
730  {
731  ROS_WARN_NAMED(LOGNAME, "Failed to validate trajectory: couldn't receive full current joint state within 1s");
732  return false;
733  }
734 
735  for (const auto& trajectory : context.trajectory_parts_)
736  {
737  if (!trajectory.joint_trajectory.points.empty())
738  {
739  // Check single-dof trajectory
740  const std::vector<double>& positions = trajectory.joint_trajectory.points.front().positions;
741  const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
742  if (positions.size() != joint_names.size())
743  {
744  ROS_ERROR_NAMED(LOGNAME, "Wrong trajectory: #joints: %zu != #positions: %zu", joint_names.size(),
745  positions.size());
746  return false;
747  }
748 
749  for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
750  {
751  const moveit::core::JointModel* jm = current_state->getJointModel(joint_names[i]);
752  if (!jm)
753  {
754  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unknown joint in trajectory: " << joint_names[i]);
755  return false;
756  }
757 
758  double cur_position = current_state->getJointPositions(jm)[0];
759  double traj_position = positions[i];
760  double joint_start_tolerance = getJointAllowedStartTolerance(joint_names[i]);
761  // normalize positions and compare
762  jm->enforcePositionBounds(&cur_position);
763  jm->enforcePositionBounds(&traj_position);
764  if (joint_start_tolerance != 0 && jm->distance(&cur_position, &traj_position) > joint_start_tolerance)
765  {
767  "\nInvalid Trajectory: start point deviates from current robot state more than %g"
768  "\njoint '%s': expected: %g, current: %g",
769  joint_start_tolerance, joint_names[i].c_str(), traj_position, cur_position);
770  return false;
771  }
772  }
773  }
774  if (!trajectory.multi_dof_joint_trajectory.points.empty())
775  {
776  // Check multi-dof trajectory
777  const std::vector<geometry_msgs::Transform>& transforms =
778  trajectory.multi_dof_joint_trajectory.points.front().transforms;
779  const std::vector<std::string>& joint_names = trajectory.multi_dof_joint_trajectory.joint_names;
780  if (transforms.size() != joint_names.size())
781  {
782  ROS_ERROR_NAMED(LOGNAME, "Wrong trajectory: #joints: %zu != #transforms: %zu", joint_names.size(),
783  transforms.size());
784  return false;
785  }
786 
787  for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
788  {
789  const moveit::core::JointModel* jm = current_state->getJointModel(joint_names[i]);
790  if (!jm)
791  {
792  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unknown joint in trajectory: " << joint_names[i]);
793  return false;
794  }
795 
796  // compute difference (offset vector and rotation angle) between current transform
797  // and start transform in trajectory
798  Eigen::Isometry3d cur_transform, start_transform;
799  // computeTransform() computes a valid isometry by contract
800  jm->computeTransform(current_state->getJointPositions(jm), cur_transform);
801  start_transform = tf2::transformToEigen(transforms[i]);
802  ASSERT_ISOMETRY(start_transform) // unsanitized input, could contain a non-isometry
803  Eigen::Vector3d offset = cur_transform.translation() - start_transform.translation();
804  Eigen::AngleAxisd rotation;
805  rotation.fromRotationMatrix(cur_transform.linear().transpose() * start_transform.linear());
806  double joint_start_tolerance = getJointAllowedStartTolerance(joint_names[i]);
807  if (joint_start_tolerance != 0 &&
808  ((offset.array() > joint_start_tolerance).any() || rotation.angle() > joint_start_tolerance))
809  {
811  "\nInvalid Trajectory: start point deviates from current robot state more than "
812  << joint_start_tolerance << "\nmulti-dof joint '" << joint_names[i]
813  << "': pos delta: " << offset.transpose() << " rot delta: " << rotation.angle());
814  return false;
815  }
816  }
817  }
818  }
819  return true;
820 }
821 
823  const moveit_msgs::RobotTrajectory& trajectory,
824  const std::vector<std::string>& controllers)
825 {
826  // empty trajectories don't need to configure anything
827  if (trajectory.multi_dof_joint_trajectory.points.empty() && trajectory.joint_trajectory.points.empty())
828  return true;
829 
830  // zero-duration trajectory (start-time stamp + overall duration == 0) causes controller issues
831  if ((trajectory.joint_trajectory.header.stamp + trajectory.joint_trajectory.points.back().time_from_start).isZero())
832  {
833  // https://github.com/ros-planning/moveit/pull/3362
834  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Skipping zero-duration trajectory");
835  return true;
836  }
837 
838  std::set<std::string> actuated_joints;
839 
840  auto is_actuated = [this](const std::string& joint_name) -> bool {
841  const moveit::core::JointModel* jm = robot_model_->getJointModel(joint_name);
842  return (jm && !jm->isPassive() && !jm->getMimic() && jm->getType() != moveit::core::JointModel::FIXED);
843  };
844  for (const std::string& joint_name : trajectory.multi_dof_joint_trajectory.joint_names)
845  if (is_actuated(joint_name))
846  actuated_joints.insert(joint_name);
847  for (const std::string& joint_name : trajectory.joint_trajectory.joint_names)
848  if (is_actuated(joint_name))
849  actuated_joints.insert(joint_name);
850 
851  if (actuated_joints.empty())
852  {
853  ROS_WARN_NAMED(LOGNAME, "The trajectory to execute specifies no joints");
854  return false;
855  }
856 
857  if (controllers.empty())
858  {
859  bool retry = true;
860  bool reloaded = false;
861  while (retry)
862  {
863  retry = false;
864  std::vector<std::string> all_controller_names;
865  for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
866  it != known_controllers_.end(); ++it)
867  all_controller_names.push_back(it->first);
868  if (selectControllers(actuated_joints, all_controller_names, context.controllers_))
869  {
870  if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
871  return true;
872  }
873  else
874  {
875  // maybe we failed because we did not have a complete list of controllers
876  if (!reloaded)
877  {
879  reloaded = true;
880  retry = true;
881  }
882  }
883  }
884  }
885  else
886  {
887  // check if the specified controllers are valid names;
888  // if they appear not to be, try to reload the controller information, just in case they are new in the system
889  bool reloaded = false;
890  for (const std::string& controller : controllers)
891  if (known_controllers_.find(controller) == known_controllers_.end())
892  {
894  reloaded = true;
895  break;
896  }
897  if (reloaded)
898  for (const std::string& controller : controllers)
899  if (known_controllers_.find(controller) == known_controllers_.end())
900  {
901  ROS_ERROR_NAMED(LOGNAME, "Controller '%s' is not known", controller.c_str());
902  return false;
903  }
904  if (selectControllers(actuated_joints, controllers, context.controllers_))
905  {
906  if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
907  return true;
908  }
909  }
910  std::stringstream ss;
911  for (const std::string& actuated_joint : actuated_joints)
912  ss << actuated_joint << " ";
913  ROS_ERROR_NAMED(LOGNAME, "Unable to identify any set of controllers that can actuate the specified joints: [ %s]",
914  ss.str().c_str());
915 
916  std::stringstream ss2;
917  std::map<std::string, ControllerInformation>::const_iterator mi;
918  for (mi = known_controllers_.begin(); mi != known_controllers_.end(); mi++)
919  {
920  ss2 << "controller '" << mi->second.name_ << "' controls joints:\n";
921 
922  std::set<std::string>::const_iterator ji;
923  for (ji = mi->second.joints_.begin(); ji != mi->second.joints_.end(); ji++)
924  {
925  ss2 << " " << *ji << std::endl;
926  }
927  }
928  ROS_ERROR_NAMED(LOGNAME, "Known controllers and their joints:\n%s", ss2.str().c_str());
929  return false;
930 }
931 
933 {
934  execute(ExecutionCompleteCallback(), auto_clear);
935  return waitForExecution();
936 }
937 
939 {
940  // execution_state_mutex_ needs to have been locked by the caller
941  for (moveit_controller_manager::MoveItControllerHandlePtr& active_handle : active_handles_)
942  try
943  {
944  active_handle->cancelExecution();
945  }
946  catch (std::exception& ex)
947  {
948  ROS_ERROR_NAMED(LOGNAME, "Caught %s when canceling execution.", ex.what());
949  }
950 }
951 
953 {
954  if (!execution_complete_)
955  {
956  execution_state_mutex_.lock();
957  if (!execution_complete_)
958  {
959  // we call cancel for all active handles; we know these are not being modified as we loop through them because of
960  // the lock
961  // we mark execution_complete_ as true ahead of time. Using this flag, executePart() will know that an external
962  // trigger to stop has been received
963  execution_complete_ = true;
965 
966  // we set the status here; executePart() will not set status when execution_complete_ is true ahead of time
968  execution_state_mutex_.unlock();
969  ROS_INFO_NAMED(LOGNAME, "Stopped trajectory execution.");
970 
971  // wait for the execution thread to finish
972  boost::mutex::scoped_lock lock(execution_thread_mutex_);
973  if (execution_thread_)
974  {
975  execution_thread_->join();
976  execution_thread_.reset();
977  }
978 
979  if (auto_clear)
980  clear();
981  }
982  else
983  execution_state_mutex_.unlock();
984  }
985  else if (execution_thread_) // just in case we have some thread waiting to be joined from some point in the past, we
986  // join it now
987  {
988  boost::mutex::scoped_lock lock(execution_thread_mutex_);
989  if (execution_thread_)
990  {
991  execution_thread_->join();
992  execution_thread_.reset();
993  }
994  }
995 }
996 
998 {
999  execute(callback, PathSegmentCompleteCallback(), auto_clear);
1000 }
1001 
1003  const PathSegmentCompleteCallback& part_callback, bool auto_clear)
1004 {
1005  // skip execution if no trajectory have been pushed
1006  // it crashes otherwise
1007  if (trajectories_.empty())
1008  return;
1009 
1010  stopExecution(false);
1011 
1013 
1014  // check whether first trajectory starts at current robot state
1015  if (!trajectories_.empty() && !validate(*trajectories_.front()))
1016  {
1018  if (auto_clear)
1019  clear();
1020  if (callback)
1021  callback(last_execution_status_);
1022  return;
1023  }
1024 
1025  // start the execution thread
1026  execution_complete_ = false;
1027  execution_thread_ = std::make_unique<boost::thread>(&TrajectoryExecutionManager::executeThread, this, callback,
1028  part_callback, auto_clear);
1029 }
1030 
1032 {
1033  {
1034  boost::unique_lock<boost::mutex> ulock(execution_state_mutex_);
1035  while (!execution_complete_)
1036  execution_complete_condition_.wait(ulock);
1037  }
1038 
1039  // this will join the thread for executing sequences of trajectories
1040  stopExecution(false);
1041 
1042  return last_execution_status_;
1043 }
1044 
1046 {
1047  if (execution_complete_)
1048  {
1049  for (TrajectoryExecutionContext* trajectory : trajectories_)
1050  delete trajectory;
1051  trajectories_.clear();
1052  }
1053  else
1054  ROS_ERROR_NAMED(LOGNAME, "Cannot push a new trajectory while another is being executed");
1055 }
1056 
1058  const PathSegmentCompleteCallback& part_callback, bool auto_clear)
1059 {
1060  // if we already got a stop request before we even started anything, we abort
1061  if (execution_complete_)
1062  {
1064  if (callback)
1065  callback(last_execution_status_);
1066  return;
1067  }
1068 
1069  ROS_DEBUG_NAMED(LOGNAME, "Starting trajectory execution ...");
1070  // assume everything will be OK
1072 
1073  // execute each trajectory, one after the other (executePart() is blocking) or until one fails.
1074  // on failure, the status is set by executePart(). Otherwise, it will remain as set above (success)
1075  std::size_t i = 0;
1076  for (; i < trajectories_.size(); ++i)
1077  {
1078  bool epart = executePart(i);
1079  if (epart && part_callback)
1080  part_callback(i);
1081  if (!epart || execution_complete_)
1082  {
1083  ++i;
1084  break;
1085  }
1086  }
1087 
1088  // only report that execution finished successfully when the robot actually stopped moving
1091 
1092  ROS_INFO_NAMED(LOGNAME, "Completed trajectory execution with status %s ...",
1093  last_execution_status_.asString().c_str());
1094 
1095  // notify whoever is waiting for the event of trajectory completion
1096  execution_state_mutex_.lock();
1097  execution_complete_ = true;
1098  execution_state_mutex_.unlock();
1099  execution_complete_condition_.notify_all();
1100 
1101  // clear the paths just executed, if needed
1102  if (auto_clear)
1103  clear();
1104 
1105  // call user-specified callback
1106  if (callback)
1107  callback(last_execution_status_);
1108 }
1109 
1110 bool TrajectoryExecutionManager::executePart(std::size_t part_index)
1111 {
1112  TrajectoryExecutionContext& context = *trajectories_[part_index];
1113 
1114  // first make sure desired controllers are active
1116  {
1117  // stop if we are already asked to do so
1118  if (execution_complete_)
1119  return false;
1120 
1121  std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles;
1122  {
1123  boost::mutex::scoped_lock slock(execution_state_mutex_);
1124  if (!execution_complete_)
1125  {
1126  // time indexing uses this member too, so we lock this mutex as well
1127  time_index_mutex_.lock();
1128  current_context_ = part_index;
1129  time_index_mutex_.unlock();
1130  active_handles_.resize(context.controllers_.size());
1131  for (std::size_t i = 0; i < context.controllers_.size(); ++i)
1132  {
1133  moveit_controller_manager::MoveItControllerHandlePtr h;
1134  try
1135  {
1136  h = controller_manager_->getControllerHandle(context.controllers_[i]);
1137  }
1138  catch (std::exception& ex)
1139  {
1140  ROS_ERROR_NAMED(LOGNAME, "Caught %s when retrieving controller handle", ex.what());
1141  }
1142  if (!h)
1143  {
1144  active_handles_.clear();
1145  current_context_ = -1;
1147  ROS_ERROR_NAMED(LOGNAME, "No controller handle for controller '%s'. Aborting.",
1148  context.controllers_[i].c_str());
1149  return false;
1150  }
1151  active_handles_[i] = h;
1152  }
1153  handles = active_handles_; // keep a copy for later, to avoid thread safety issues
1154  for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1155  {
1156  bool ok = false;
1157  try
1158  {
1159  ok = active_handles_[i]->sendTrajectory(context.trajectory_parts_[i]);
1160  }
1161  catch (std::exception& ex)
1162  {
1163  ROS_ERROR_NAMED(LOGNAME, "Caught %s when sending trajectory to controller", ex.what());
1164  }
1165  if (!ok)
1166  {
1167  for (std::size_t j = 0; j < i; ++j)
1168  try
1169  {
1170  active_handles_[j]->cancelExecution();
1171  }
1172  catch (std::exception& ex)
1173  {
1174  ROS_ERROR_NAMED(LOGNAME, "Caught %s when canceling execution", ex.what());
1175  }
1176  ROS_ERROR_NAMED(LOGNAME, "Failed to send trajectory part %zu of %zu to controller %s", i + 1,
1177  context.trajectory_parts_.size(), active_handles_[i]->getName().c_str());
1178  if (i > 0)
1179  ROS_ERROR_NAMED(LOGNAME, "Cancelling previously sent trajectory parts");
1180  active_handles_.clear();
1181  current_context_ = -1;
1183  return false;
1184  }
1185  }
1186  }
1187  }
1188 
1189  // compute the expected duration of the trajectory and find the part of the trajectory that takes longest to execute
1190  ros::Time current_time = ros::Time::now();
1191  ros::Duration expected_trajectory_duration(0.0);
1192  int longest_part = -1;
1193  for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1194  {
1195  ros::Duration d(0.0);
1196  if (!(context.trajectory_parts_[i].joint_trajectory.points.empty() &&
1197  context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty()))
1198  {
1199  if (context.trajectory_parts_[i].joint_trajectory.header.stamp > current_time)
1200  d = context.trajectory_parts_[i].joint_trajectory.header.stamp - current_time;
1201  if (context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp > current_time)
1202  d = std::max(d, context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp - current_time);
1203  d += std::max(context.trajectory_parts_[i].joint_trajectory.points.empty() ?
1204  ros::Duration(0.0) :
1205  context.trajectory_parts_[i].joint_trajectory.points.back().time_from_start,
1206  context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty() ?
1207  ros::Duration(0.0) :
1208  context.trajectory_parts_[i].multi_dof_joint_trajectory.points.back().time_from_start);
1209 
1210  if (longest_part < 0 ||
1211  std::max(context.trajectory_parts_[i].joint_trajectory.points.size(),
1212  context.trajectory_parts_[i].multi_dof_joint_trajectory.points.size()) >
1213  std::max(context.trajectory_parts_[longest_part].joint_trajectory.points.size(),
1214  context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size()))
1215  longest_part = i;
1216  }
1217 
1218  // prefer controller-specific values over global ones if defined
1219  // TODO: the controller-specific parameters are static, but override
1220  // the global ones are configurable via dynamic reconfigure
1221  std::map<std::string, double>::const_iterator scaling_it =
1223  const double current_scaling = scaling_it != controller_allowed_execution_duration_scaling_.end() ?
1224  scaling_it->second :
1226 
1227  std::map<std::string, double>::const_iterator margin_it =
1229  const double current_margin = margin_it != controller_allowed_goal_duration_margin_.end() ?
1230  margin_it->second :
1232 
1233  // expected duration is the duration of the longest part
1234  expected_trajectory_duration =
1235  std::max(d * current_scaling + ros::Duration(current_margin), expected_trajectory_duration);
1236  }
1237 
1238  // construct a map from expected time to state index, for easy access to expected state location
1239  if (longest_part >= 0)
1240  {
1241  boost::mutex::scoped_lock slock(time_index_mutex_);
1242 
1243  if (context.trajectory_parts_[longest_part].joint_trajectory.points.size() >=
1244  context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size())
1245  {
1246  ros::Duration d(0.0);
1247  if (context.trajectory_parts_[longest_part].joint_trajectory.header.stamp > current_time)
1248  d = context.trajectory_parts_[longest_part].joint_trajectory.header.stamp - current_time;
1249  for (trajectory_msgs::JointTrajectoryPoint& point :
1250  context.trajectory_parts_[longest_part].joint_trajectory.points)
1251  time_index_.push_back(current_time + d + point.time_from_start);
1252  }
1253  else
1254  {
1255  ros::Duration d(0.0);
1256  if (context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp > current_time)
1257  d = context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp - current_time;
1258  for (trajectory_msgs::MultiDOFJointTrajectoryPoint& point :
1259  context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points)
1260  time_index_.push_back(current_time + d + point.time_from_start);
1261  }
1262  }
1263 
1264  bool result = true;
1265  for (moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
1266  {
1268  {
1269  if (!handle->waitForExecution(expected_trajectory_duration))
1270  if (!execution_complete_ && ros::Time::now() - current_time > expected_trajectory_duration)
1271  {
1273  "Controller is taking too long to execute trajectory (the expected upper "
1274  "bound for the trajectory execution was %lf seconds). Stopping trajectory.",
1275  expected_trajectory_duration.toSec());
1276  {
1277  boost::mutex::scoped_lock slock(execution_state_mutex_);
1278  stopExecutionInternal(); // this is really tricky. we can't call stopExecution() here, so we call the
1279  // internal function only
1280  }
1282  result = false;
1283  break;
1284  }
1285  }
1286  else
1287  handle->waitForExecution();
1288 
1289  // if something made the trajectory stop, we stop this thread too
1290  if (execution_complete_)
1291  {
1292  result = false;
1293  break;
1294  }
1295  else if (handle->getLastExecutionStatus() != moveit_controller_manager::ExecutionStatus::SUCCEEDED)
1296  {
1297  ROS_WARN_STREAM_NAMED(LOGNAME, "Controller handle " << handle->getName() << " reports status "
1298  << handle->getLastExecutionStatus().asString());
1299  last_execution_status_ = handle->getLastExecutionStatus();
1300  result = false;
1301  }
1302  }
1303 
1304  // clear the active handles
1305  execution_state_mutex_.lock();
1306  active_handles_.clear();
1307 
1308  // clear the time index
1309  time_index_mutex_.lock();
1310  time_index_.clear();
1311  current_context_ = -1;
1312  time_index_mutex_.unlock();
1313 
1314  execution_state_mutex_.unlock();
1315  return result;
1316  }
1317  else
1318  {
1320  return false;
1321  }
1322 }
1323 
1325 {
1326  // skip waiting for convergence?
1328  {
1329  ROS_DEBUG_NAMED(LOGNAME, "Not waiting for trajectory completion");
1330  return true;
1331  }
1332 
1334  double time_remaining = wait_time;
1335 
1336  moveit::core::RobotStatePtr prev_state, cur_state;
1337  prev_state = csm_->getCurrentState();
1338  prev_state->enforceBounds();
1339 
1340  // assume robot stopped when 3 consecutive checks yield the same robot state
1341  unsigned int no_motion_count = 0; // count iterations with no motion
1342  while (time_remaining > 0. && no_motion_count < 3)
1343  {
1344  if (!csm_->waitForCurrentState(ros::Time::now(), time_remaining) || !(cur_state = csm_->getCurrentState()))
1345  {
1346  ROS_WARN_NAMED(LOGNAME, "Failed to receive current joint state");
1347  return false;
1348  }
1349  cur_state->enforceBounds();
1350  time_remaining = wait_time - (ros::WallTime::now() - start).toSec(); // remaining wait_time
1351 
1352  // check for motion in effected joints of execution context
1353  bool moved = false;
1354  for (const auto& trajectory : context.trajectory_parts_)
1355  {
1356  const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1357  const std::size_t n = joint_names.size();
1358 
1359  for (std::size_t i = 0; i < n && !moved; ++i)
1360  {
1361  const moveit::core::JointModel* jm = cur_state->getJointModel(joint_names[i]);
1362  if (!jm)
1363  continue; // joint vanished from robot state (shouldn't happen), but we don't care
1364 
1365  double joint_tolerance = getJointAllowedStartTolerance(joint_names[i]);
1366  if (fabs(cur_state->getJointPositions(jm)[0] - prev_state->getJointPositions(jm)[0]) > joint_tolerance)
1367  {
1368  moved = true;
1369  no_motion_count = 0;
1370  break;
1371  }
1372  }
1373  }
1374 
1375  if (!moved)
1376  ++no_motion_count;
1377 
1378  std::swap(prev_state, cur_state);
1379  }
1380 
1381  return time_remaining > 0;
1382 }
1383 
1385 {
1386  boost::mutex::scoped_lock slock(time_index_mutex_);
1387  if (current_context_ < 0)
1388  return std::make_pair(-1, -1);
1389  if (time_index_.empty())
1390  return std::make_pair((int)current_context_, -1);
1391  std::vector<ros::Time>::const_iterator time_index_it =
1392  std::lower_bound(time_index_.begin(), time_index_.end(), ros::Time::now());
1393  int pos = time_index_it - time_index_.begin();
1394  return std::make_pair((int)current_context_, pos);
1395 }
1396 
1397 const std::vector<TrajectoryExecutionManager::TrajectoryExecutionContext*>&
1399 {
1400  return trajectories_;
1401 }
1402 
1404 {
1405  return last_execution_status_;
1406 }
1407 
1409 {
1410  const moveit::core::JointModelGroup* joint_model_group = robot_model_->getJointModelGroup(group);
1411  if (joint_model_group)
1412  return ensureActiveControllersForJoints(joint_model_group->getJointModelNames());
1413  else
1414  return false;
1415 }
1416 
1417 bool TrajectoryExecutionManager::ensureActiveControllersForJoints(const std::vector<std::string>& joints)
1418 {
1419  std::vector<std::string> all_controller_names;
1420  for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1421  it != known_controllers_.end(); ++it)
1422  all_controller_names.push_back(it->first);
1423  std::vector<std::string> selected_controllers;
1424  std::set<std::string> jset;
1425  for (const std::string& joint : joints)
1426  {
1427  const moveit::core::JointModel* jm = robot_model_->getJointModel(joint);
1428  if (jm)
1429  {
1430  if (jm->isPassive() || jm->getMimic() != nullptr || jm->getType() == moveit::core::JointModel::FIXED)
1431  continue;
1432  jset.insert(joint);
1433  }
1434  }
1435 
1436  if (selectControllers(jset, all_controller_names, selected_controllers))
1437  return ensureActiveControllers(selected_controllers);
1438  else
1439  return false;
1440 }
1441 
1442 bool TrajectoryExecutionManager::ensureActiveController(const std::string& controller)
1443 {
1444  return ensureActiveControllers(std::vector<std::string>(1, controller));
1445 }
1446 
1447 bool TrajectoryExecutionManager::ensureActiveControllers(const std::vector<std::string>& controllers)
1448 {
1450 
1451  if (manage_controllers_)
1452  {
1453  std::vector<std::string> controllers_to_activate;
1454  std::vector<std::string> controllers_to_deactivate;
1455  std::set<std::string> joints_to_be_activated;
1456  std::set<std::string> joints_to_be_deactivated;
1457  for (const std::string& controller : controllers)
1458  {
1459  std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.find(controller);
1460  if (it == known_controllers_.end())
1461  {
1462  ROS_ERROR_STREAM_NAMED(LOGNAME, "Controller " << controller << " is not known");
1463  return false;
1464  }
1465  if (!it->second.state_.active_)
1466  {
1467  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Need to activate " << controller);
1468  controllers_to_activate.push_back(controller);
1469  joints_to_be_activated.insert(it->second.joints_.begin(), it->second.joints_.end());
1470  for (const std::string& overlapping_controller : it->second.overlapping_controllers_)
1471  {
1472  const ControllerInformation& ci = known_controllers_[overlapping_controller];
1473  if (ci.state_.active_)
1474  {
1475  controllers_to_deactivate.push_back(overlapping_controller);
1476  joints_to_be_deactivated.insert(ci.joints_.begin(), ci.joints_.end());
1477  }
1478  }
1479  }
1480  else
1481  ROS_DEBUG_STREAM_NAMED(LOGNAME, "Controller " << controller << " is already active");
1482  }
1483  std::set<std::string> diff;
1484  std::set_difference(joints_to_be_deactivated.begin(), joints_to_be_deactivated.end(),
1485  joints_to_be_activated.begin(), joints_to_be_activated.end(), std::inserter(diff, diff.end()));
1486  if (!diff.empty())
1487  {
1488  // find the set of controllers that do not overlap with the ones we want to activate so far
1489  std::vector<std::string> possible_additional_controllers;
1490  for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1491  it != known_controllers_.end(); ++it)
1492  {
1493  bool ok = true;
1494  for (const std::string& controller_to_activate : controllers_to_activate)
1495  if (it->second.overlapping_controllers_.find(controller_to_activate) !=
1496  it->second.overlapping_controllers_.end())
1497  {
1498  ok = false;
1499  break;
1500  }
1501  if (ok)
1502  possible_additional_controllers.push_back(it->first);
1503  }
1504 
1505  // out of the allowable controllers, try to find a subset of controllers that covers the joints to be actuated
1506  std::vector<std::string> additional_controllers;
1507  if (selectControllers(diff, possible_additional_controllers, additional_controllers))
1508  controllers_to_activate.insert(controllers_to_activate.end(), additional_controllers.begin(),
1509  additional_controllers.end());
1510  else
1511  return false;
1512  }
1513  if (!controllers_to_activate.empty() || !controllers_to_deactivate.empty())
1514  {
1515  if (controller_manager_)
1516  {
1517  // load controllers to be activated, if needed, and reset the state update cache
1518  for (const std::string& controller_to_activate : controllers_to_activate)
1519  {
1520  ControllerInformation& ci = known_controllers_[controller_to_activate];
1521  ci.last_update_ = ros::Time();
1522  }
1523  // reset the state update cache
1524  for (const std::string& controller_to_activate : controllers_to_deactivate)
1525  known_controllers_[controller_to_activate].last_update_ = ros::Time();
1526  return controller_manager_->switchControllers(controllers_to_activate, controllers_to_deactivate);
1527  }
1528  else
1529  return false;
1530  }
1531  else
1532  return true;
1533  }
1534  else
1535  {
1536  std::set<std::string> originally_active;
1537  for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1538  it != known_controllers_.end(); ++it)
1539  if (it->second.state_.active_)
1540  originally_active.insert(it->first);
1541  return std::includes(originally_active.begin(), originally_active.end(), controllers.begin(), controllers.end());
1542  }
1543 }
1544 
1546 {
1547  XmlRpc::XmlRpcValue controller_list;
1548  if (node_handle_.getParam("controller_list", controller_list) &&
1549  controller_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
1550  {
1551  for (int i = 0; i < controller_list.size(); ++i) // NOLINT(modernize-loop-convert)
1552  {
1553  XmlRpc::XmlRpcValue& controller = controller_list[i];
1554  if (controller.hasMember("name"))
1555  {
1556  if (controller.hasMember("allowed_execution_duration_scaling"))
1557  controller_allowed_execution_duration_scaling_[std::string(controller["name"])] =
1558  controller["allowed_execution_duration_scaling"];
1559  if (controller.hasMember("allowed_goal_duration_margin"))
1560  controller_allowed_goal_duration_margin_[std::string(controller["name"])] =
1561  controller["allowed_goal_duration_margin"];
1562  }
1563  }
1564  }
1565 }
1566 
1567 double TrajectoryExecutionManager::getJointAllowedStartTolerance(std::string const& jointName) const
1568 {
1569  auto start_tolerance_it = joints_allowed_start_tolerance_.find(jointName);
1570  return start_tolerance_it != joints_allowed_start_tolerance_.end() ? start_tolerance_it->second :
1572 }
1573 
1575 {
1577  node_handle_.getParam("trajectory_execution/joints_allowed_start_tolerance", joints_allowed_start_tolerance_);
1578 
1579  // remove negative values
1580  for (auto it = joints_allowed_start_tolerance_.begin(); it != joints_allowed_start_tolerance_.end();)
1581  {
1582  if (it->second < 0)
1583  it = joints_allowed_start_tolerance_.erase(it);
1584  else
1585  ++it;
1586  }
1587 }
1588 
1589 } // namespace trajectory_execution_manager
XmlRpc::XmlRpcValue::size
int size() const
trajectory_execution_manager::TrajectoryExecutionManager::time_index_
std::vector< ros::Time > time_index_
Definition: trajectory_execution_manager.h:324
trajectory_execution_manager::TrajectoryExecutionManager::validate
bool validate(const TrajectoryExecutionContext &context) const
Validate first point of trajectory matches current robot state.
Definition: trajectory_execution_manager.cpp:721
moveit::core::JointModel::enforcePositionBounds
bool enforcePositionBounds(double *values) const
trajectory_execution_manager::TrajectoryExecutionManager::verbose_
bool verbose_
Definition: trajectory_execution_manager.h:333
trajectory_execution_manager::TrajectoryExecutionManager::ExecutionCompleteCallback
boost::function< void(const moveit_controller_manager::ExecutionStatus &)> ExecutionCompleteCallback
Definition: trajectory_execution_manager.h:98
trajectory_execution_manager::TrajectoryExecutionManager::execution_velocity_scaling_
double execution_velocity_scaling_
Definition: trajectory_execution_manager.h:350
trajectory_execution_manager::TrajectoryExecutionManager::execution_complete_condition_
boost::condition_variable execution_complete_condition_
Definition: trajectory_execution_manager.h:319
trajectory_execution_manager::DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE
static const ros::Duration DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE(1.0)
trajectory_execution_manager::TrajectoryExecutionManager
Definition: trajectory_execution_manager.h:91
trajectory_execution_manager::TrajectoryExecutionManager::executeAndWait
moveit_controller_manager::ExecutionStatus executeAndWait(bool auto_clear=true)
Definition: trajectory_execution_manager.cpp:932
moveit_controller_manager::ExecutionStatus::PREEMPTED
PREEMPTED
nrjoints
std::vector< std::size_t > nrjoints
Definition: trajectory_execution_manager.cpp:453
trajectory_execution_manager::TrajectoryExecutionManager::controller_manager_loader_
std::unique_ptr< pluginlib::ClassLoader< moveit_controller_manager::MoveItControllerManager > > controller_manager_loader_
Definition: trajectory_execution_manager.h:330
trajectory_execution_manager::TrajectoryExecutionManager::stopExecution
void stopExecution(bool auto_clear=true)
Stop whatever executions are active, if any.
Definition: trajectory_execution_manager.cpp:952
tf2_eigen.h
moveit_controller_manager::ExecutionStatus::ABORTED
ABORTED
trajectory_execution_manager::TrajectoryExecutionManager::setWaitForTrajectoryCompletion
void setWaitForTrajectoryCompletion(bool flag)
Enable or disable waiting for trajectory completion.
Definition: trajectory_execution_manager.cpp:213
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
trajectory_execution_manager::TrajectoryExecutionManager::manage_controllers_
bool manage_controllers_
Definition: trajectory_execution_manager.h:310
check_isometry.h
trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveController
bool ensureActiveController(const std::string &controller)
Make sure a particular controller is active.
Definition: trajectory_execution_manager.cpp:1442
trajectory_execution_manager::TrajectoryExecutionManager::selectControllers
bool selectControllers(const std::set< std::string > &actuated_joints, const std::vector< std::string > &available_controllers, std::vector< std::string > &selected_controllers)
Definition: trajectory_execution_manager.cpp:559
trajectory_execution_manager::TrajectoryExecutionManager::execution_complete_
bool execution_complete_
Definition: trajectory_execution_manager.h:326
trajectory_execution_manager::TrajectoryExecutionManager::setExecutionVelocityScaling
void setExecutionVelocityScaling(double scaling)
Definition: trajectory_execution_manager.cpp:203
moveit::core::JointModel::getName
const std::string & getName() const
trajectory_execution_manager::TrajectoryExecutionManager::csm_
planning_scene_monitor::CurrentStateMonitorPtr csm_
Definition: trajectory_execution_manager.h:304
moveit_controller_manager::MoveItControllerManager::ControllerState::active_
bool active_
moveit_controller_manager::ExecutionStatus::TIMED_OUT
TIMED_OUT
trajectory_execution_manager::TrajectoryExecutionManager::node_handle_
ros::NodeHandle node_handle_
Definition: trajectory_execution_manager.h:305
trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveControllersForJoints
bool ensureActiveControllersForJoints(const std::vector< std::string > &joints)
Make sure the active controllers are such that trajectories that actuate joints in the specified set ...
Definition: trajectory_execution_manager.cpp:1417
trajectory_execution_manager::TrajectoryExecutionManager::current_context_
int current_context_
Definition: trajectory_execution_manager.h:323
trajectory_execution_manager::TrajectoryExecutionManager::getLastExecutionStatus
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() const
Return the controller status for the last attempted execution.
Definition: trajectory_execution_manager.cpp:1403
trajectory_execution_manager::TrajectoryExecutionManager::isControllerActive
bool isControllerActive(const std::string &controller)
Check if a controller is active.
Definition: trajectory_execution_manager.cpp:542
nractive
std::vector< std::size_t > nractive
Definition: trajectory_execution_manager.cpp:454
trajectory_execution_manager::TrajectoryExecutionManager::last_execution_status_
moveit_controller_manager::ExecutionStatus last_execution_status_
Definition: trajectory_execution_manager.h:321
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
robot_state.h
trajectory_execution_manager::TrajectoryExecutionManager::initialize
void initialize()
Definition: trajectory_execution_manager.cpp:109
trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveControllers
bool ensureActiveControllers(const std::vector< std::string > &controllers)
Make sure a particular set of controllers are active.
Definition: trajectory_execution_manager.cpp:1447
trajectory_execution_manager::TrajectoryExecutionManager::checkControllerCombination
bool checkControllerCombination(std::vector< std::string > &controllers, const std::set< std::string > &actuated_joints)
Definition: trajectory_execution_manager.cpp:367
trajectory_execution_manager::TrajectoryExecutionManager::setAllowedExecutionDurationScaling
void setAllowedExecutionDurationScaling(double scaling)
Definition: trajectory_execution_manager.cpp:193
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
trajectory_execution_manager::TrajectoryExecutionManager::controller_allowed_goal_duration_margin_
std::map< std::string, double > controller_allowed_goal_duration_margin_
Definition: trajectory_execution_manager.h:345
overlap
bool overlap(S a1, S a2, S b1, S b2)
trajectory_execution_manager::TrajectoryExecutionManager::receiveEvent
void receiveEvent(const std_msgs::StringConstPtr &event)
Definition: trajectory_execution_manager.cpp:236
ok
ROSCPP_DECL bool ok()
trajectory_execution_manager::TrajectoryExecutionManager::getTrajectories
const std::vector< TrajectoryExecutionContext * > & getTrajectories() const
Get the trajectories to be executed.
Definition: trajectory_execution_manager.cpp:1398
trajectory_execution_manager::TrajectoryExecutionManager::DynamicReconfigureImpl::dynamicReconfigureCallback
void dynamicReconfigureCallback(const TrajectoryExecutionDynamicReconfigureConfig &config, uint32_t)
Definition: trajectory_execution_manager.cpp:71
trajectory_execution_manager::TrajectoryExecutionManager::controller_manager_
moveit_controller_manager::MoveItControllerManagerPtr controller_manager_
Definition: trajectory_execution_manager.h:331
trajectory_execution_manager::TrajectoryExecutionManager::execution_duration_monitoring_
bool execution_duration_monitoring_
Definition: trajectory_execution_manager.h:338
trajectory_execution_manager::TrajectoryExecutionManager::stopExecutionInternal
void stopExecutionInternal()
Definition: trajectory_execution_manager.cpp:938
moveit::core::JointModel::getType
JointType getType() const
trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionContext::trajectory_parts_
std::vector< moveit_msgs::RobotTrajectory > trajectory_parts_
Definition: trajectory_execution_manager.h:112
LOGNAME
static const std::string LOGNAME
Definition: trajectory_execution_manager.cpp:45
pluginlib::PluginlibException
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::name_
std::string name_
Definition: trajectory_execution_manager.h:246
trajectory_execution_manager::TrajectoryExecutionManager::reconfigure_impl_
DynamicReconfigureImpl * reconfigure_impl_
Definition: trajectory_execution_manager.h:335
trajectory_execution_manager::TrajectoryExecutionManager::root_node_handle_
ros::NodeHandle root_node_handle_
Definition: trajectory_execution_manager.h:306
trajectory_execution_manager::TrajectoryExecutionManager::executePart
bool executePart(std::size_t part_index)
Definition: trajectory_execution_manager.cpp:1110
trajectory_execution_manager::TrajectoryExecutionManager::allowed_start_tolerance_
double allowed_start_tolerance_
Definition: trajectory_execution_manager.h:347
trajectory_execution_manager::TrajectoryExecutionManager::generateControllerCombination
void generateControllerCombination(std::size_t start_index, std::size_t controller_count, const std::vector< std::string > &available_controllers, std::vector< std::string > &selected_controllers, std::vector< std::vector< std::string > > &selected_options, const std::set< std::string > &actuated_joints)
Definition: trajectory_execution_manager.cpp:393
name
std::string name
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation
Definition: trajectory_execution_manager.h:244
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
trajectory_execution_manager::TrajectoryExecutionManager::DynamicReconfigureImpl
Definition: trajectory_execution_manager.cpp:60
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
moveit_controller_manager::ExecutionStatus::SUCCEEDED
SUCCEEDED
ros::WallTime::now
static WallTime now()
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
moveit::core::JointModelGroup::getJointModelNames
const std::vector< std::string > & getJointModelNames() const
ASSERT_ISOMETRY
#define ASSERT_ISOMETRY(transform)
trajectory_execution_manager::TrajectoryExecutionManager::execute
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...
Definition: trajectory_execution_manager.cpp:997
trajectory_execution_manager::TrajectoryExecutionManager::trajectories_
std::vector< TrajectoryExecutionContext * > trajectories_
Definition: trajectory_execution_manager.h:328
trajectory_execution_manager
Definition: trajectory_execution_manager.h:52
trajectory_execution_manager::TrajectoryExecutionManager::DynamicReconfigureImpl::dynamic_reconfigure_server_
dynamic_reconfigure::Server< TrajectoryExecutionDynamicReconfigureConfig > dynamic_reconfigure_server_
Definition: trajectory_execution_manager.cpp:82
trajectory_execution_manager::TrajectoryExecutionManager::areControllersActive
bool areControllersActive(const std::vector< std::string > &controllers)
Check if a set of controllers are active.
Definition: trajectory_execution_manager.cpp:547
nrdefault
std::vector< std::size_t > nrdefault
Definition: trajectory_execution_manager.cpp:452
trajectory_execution_manager::TrajectoryExecutionManager::active_handles_
std::vector< moveit_controller_manager::MoveItControllerHandlePtr > active_handles_
Definition: trajectory_execution_manager.h:322
d
d
trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionContext::controllers_
std::vector< std::string > controllers_
The controllers to use for executing the different trajectory parts;.
Definition: trajectory_execution_manager.h:108
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
trajectory_execution_manager::TrajectoryExecutionManager::EXECUTION_EVENT_TOPIC
static const std::string EXECUTION_EVENT_TOPIC
Definition: trajectory_execution_manager.h:94
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::overlapping_controllers_
std::set< std::string > overlapping_controllers_
Definition: trajectory_execution_manager.h:248
ros::WallTime
trajectory_execution_manager::TrajectoryExecutionManager::getControllerManager
const moveit_controller_manager::MoveItControllerManagerPtr & getControllerManager() const
Get the instance of the controller manager used (this is the plugin instance loaded)
Definition: trajectory_execution_manager.cpp:223
trajectory_execution_manager::TrajectoryExecutionManager::processEvent
void processEvent(const std::string &event)
Execute a named event (e.g., 'stop')
Definition: trajectory_execution_manager.cpp:228
trajectory_execution_manager::DEFAULT_CONTROLLER_GOAL_DURATION_SCALING
static const double DEFAULT_CONTROLLER_GOAL_DURATION_SCALING
Definition: trajectory_execution_manager.cpp:55
trajectory_execution_manager::TrajectoryExecutionManager::setAllowedGoalDurationMargin
void setAllowedGoalDurationMargin(double margin)
Definition: trajectory_execution_manager.cpp:198
XmlRpc::XmlRpcValue::getType
const Type & getType() const
trajectory_execution_manager::TrajectoryExecutionManager::updateJointsAllowedStartTolerance
void updateJointsAllowedStartTolerance()
Definition: trajectory_execution_manager.cpp:1574
tf2::transformToEigen
Eigen::Isometry3d transformToEigen(const geometry_msgs::Transform &t)
trajectory_execution_manager::TrajectoryExecutionManager::findControllers
bool findControllers(const std::set< std::string > &actuated_joints, std::size_t controller_count, const std::vector< std::string > &available_controllers, std::vector< std::string > &selected_controllers)
Definition: trajectory_execution_manager.cpp:458
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::state_
moveit_controller_manager::MoveItControllerManager::ControllerState state_
Definition: trajectory_execution_manager.h:249
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
point
std::chrono::system_clock::time_point point
XmlRpc::XmlRpcValue::TypeArray
TypeArray
trajectory_execution_manager::TrajectoryExecutionManager::execution_thread_mutex_
boost::mutex execution_thread_mutex_
Definition: trajectory_execution_manager.h:316
trajectory_execution_manager::TrajectoryExecutionManager::updateControllerState
void updateControllerState(const std::string &controller, const ros::Duration &age)
Definition: trajectory_execution_manager.cpp:336
start
ROSCPP_DECL void start()
trajectory_execution_manager::TrajectoryExecutionManager::reloadControllerInformation
void reloadControllerInformation()
Definition: trajectory_execution_manager.cpp:301
XmlRpc::XmlRpcValue::hasMember
bool hasMember(const std::string &name) const
trajectory_execution_manager::TrajectoryExecutionManager::updateControllersState
void updateControllersState(const ros::Duration &age)
Definition: trajectory_execution_manager.cpp:361
moveit::core::JointModel::computeTransform
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const=0
trajectory_execution_manager::TrajectoryExecutionManager::getCurrentExpectedTrajectoryIndex
std::pair< int, int > getCurrentExpectedTrajectoryIndex() const
Definition: trajectory_execution_manager.cpp:1384
ros::Time
moveit::core::JointModel::getMimic
const JointModel * getMimic() const
selected_options
std::vector< std::vector< std::string > > selected_options
Definition: trajectory_execution_manager.cpp:451
trajectory_execution_manager::DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN
static const double DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN
Definition: trajectory_execution_manager.cpp:52
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::joints_
std::set< std::string > joints_
Definition: trajectory_execution_manager.h:247
trajectory_execution_manager.h
trajectory_execution_manager::TrajectoryExecutionManager::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: trajectory_execution_manager.h:303
trajectory_execution_manager::TrajectoryExecutionManager::executeThread
void executeThread(const ExecutionCompleteCallback &callback, const PathSegmentCompleteCallback &part_callback, bool auto_clear)
Definition: trajectory_execution_manager.cpp:1057
trajectory_execution_manager::TrajectoryExecutionManager::waitForExecution
moveit_controller_manager::ExecutionStatus waitForExecution()
Definition: trajectory_execution_manager.cpp:1031
trajectory_execution_manager::TrajectoryExecutionManager::~TrajectoryExecutionManager
~TrajectoryExecutionManager()
Destructor. Cancels all running trajectories (if any)
Definition: trajectory_execution_manager.cpp:103
moveit::core::JointModel::distance
virtual double distance(const double *value1, const double *value2) const=0
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
moveit::core::JointModelGroup
index
unsigned int index
trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionManager
TrajectoryExecutionManager(const moveit::core::RobotModelConstPtr &robot_model, const planning_scene_monitor::CurrentStateMonitorPtr &csm)
Load the controller manager plugin, start listening for events on a topic.
Definition: trajectory_execution_manager.cpp:85
tolerance
S tolerance()
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
trajectory_execution_manager::TrajectoryExecutionManager::configure
bool configure(TrajectoryExecutionContext &context, const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers)
Definition: trajectory_execution_manager.cpp:822
trajectory_execution_manager::TrajectoryExecutionManager::ensureActiveControllersForGroup
bool ensureActiveControllersForGroup(const std::string &group)
Make sure the active controllers are such that trajectories that actuate joints in the specified grou...
Definition: trajectory_execution_manager.cpp:1408
trajectory_execution_manager::TrajectoryExecutionManager::joints_allowed_start_tolerance_
std::map< std::string, double > joints_allowed_start_tolerance_
Definition: trajectory_execution_manager.h:349
trajectory_execution_manager::TrajectoryExecutionManager::wait_for_trajectory_completion_
bool wait_for_trajectory_completion_
Definition: trajectory_execution_manager.h:351
trajectory_execution_manager::TrajectoryExecutionManager::ControllerInformation::last_update_
ros::Time last_update_
Definition: trajectory_execution_manager.h:250
DurationBase< Duration >::toSec
double toSec() const
trajectory_execution_manager::TrajectoryExecutionManager::DynamicReconfigureImpl::DynamicReconfigureImpl
DynamicReconfigureImpl(TrajectoryExecutionManager *owner)
Definition: trajectory_execution_manager.cpp:63
trajectory_execution_manager::TrajectoryExecutionManager::allowed_goal_duration_margin_
double allowed_goal_duration_margin_
Definition: trajectory_execution_manager.h:341
trajectory_execution_manager::TrajectoryExecutionManager::distributeTrajectory
bool distributeTrajectory(const moveit_msgs::RobotTrajectory &trajectory, const std::vector< std::string > &controllers, std::vector< moveit_msgs::RobotTrajectory > &parts)
Definition: trajectory_execution_manager.cpp:585
trajectory_execution_manager::TrajectoryExecutionManager::clear
void clear()
Clear the trajectories to execute.
Definition: trajectory_execution_manager.cpp:1045
trajectory_execution_manager::TrajectoryExecutionManager::execution_state_mutex_
boost::mutex execution_state_mutex_
Definition: trajectory_execution_manager.h:315
trajectory_execution_manager::TrajectoryExecutionManager::push
bool push(const moveit_msgs::RobotTrajectory &trajectory, const std::string &controller="")
Definition: trajectory_execution_manager.cpp:242
trajectory_execution_manager::TrajectoryExecutionManager::execution_thread_
std::unique_ptr< boost::thread > execution_thread_
Definition: trajectory_execution_manager.h:313
trajectory_execution_manager::TrajectoryExecutionManager::time_index_mutex_
boost::mutex time_index_mutex_
Definition: trajectory_execution_manager.h:325
trajectory_execution_manager::TrajectoryExecutionManager::getJointAllowedStartTolerance
double getJointAllowedStartTolerance(std::string const &jointName) const
Definition: trajectory_execution_manager.cpp:1567
trajectory_execution_manager::TrajectoryExecutionManager::controller_allowed_execution_duration_scaling_
std::map< std::string, double > controller_allowed_execution_duration_scaling_
Definition: trajectory_execution_manager.h:344
moveit::core::JointModel::FIXED
FIXED
trajectory_execution_manager::TrajectoryExecutionManager::isManagingControllers
bool isManagingControllers() const
If this function returns true, then this instance of the manager is allowed to load/unload/switch con...
Definition: trajectory_execution_manager.cpp:218
trajectory_execution_manager::TrajectoryExecutionManager::event_topic_subscriber_
ros::Subscriber event_topic_subscriber_
Definition: trajectory_execution_manager.h:307
trajectory_execution_manager::TrajectoryExecutionManager::allowed_execution_duration_scaling_
double allowed_execution_duration_scaling_
Definition: trajectory_execution_manager.h:340
trajectory_execution_manager::TrajectoryExecutionManager::enableExecutionDurationMonitoring
void enableExecutionDurationMonitoring(bool flag)
Definition: trajectory_execution_manager.cpp:188
ros::Duration
trajectory_execution_manager::TrajectoryExecutionManager::waitForRobotToStop
bool waitForRobotToStop(const TrajectoryExecutionContext &context, double wait_time=1.0)
Definition: trajectory_execution_manager.cpp:1324
trajectory_execution_manager::TrajectoryExecutionManager::TrajectoryExecutionContext
Data structure that represents information necessary to execute a trajectory.
Definition: trajectory_execution_manager.h:105
moveit_controller_manager::ExecutionStatus
moveit::core::JointModel::isPassive
bool isPassive() const
trajectory_execution_manager::TrajectoryExecutionManager::PathSegmentCompleteCallback
boost::function< void(std::size_t)> PathSegmentCompleteCallback
Definition: trajectory_execution_manager.h:102
moveit::core::JointModel
XmlRpc::XmlRpcValue
trajectory_execution_manager::TrajectoryExecutionManager::known_controllers_
std::map< std::string, ControllerInformation > known_controllers_
Definition: trajectory_execution_manager.h:309
trajectory_execution_manager::TrajectoryExecutionManager::setAllowedStartTolerance
void setAllowedStartTolerance(double tolerance)
Set joint-value tolerance for validating trajectory's start point against current robot state.
Definition: trajectory_execution_manager.cpp:208
trajectory_execution_manager::TrajectoryExecutionManager::loadControllerParams
void loadControllerParams()
Definition: trajectory_execution_manager.cpp:1545
trajectory_execution_manager::TrajectoryExecutionManager::DynamicReconfigureImpl::owner_
TrajectoryExecutionManager * owner_
Definition: trajectory_execution_manager.cpp:81
ros::Time::now
static Time now()
moveit_controller_manager::ExecutionStatus::asString
std::string asString() const
moveit_controller_manager::MoveItControllerManager::ControllerState::default_
bool default_


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:04