39 #include <geometric_shapes/check_isometry.h>
40 #include <tf2_eigen/tf2_eigen.hpp>
44 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.trajectory_execution_manager");
48 static const auto DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE = rclcpp::Duration::from_seconds(1);
49 static const double DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN = 0.5;
52 static const double DEFAULT_CONTROLLER_GOAL_DURATION_SCALING =
56 const moveit::core::RobotModelConstPtr& robot_model,
57 const planning_scene_monitor::CurrentStateMonitorPtr& csm)
58 : node_(node), robot_model_(robot_model), csm_(csm)
60 if (!node_->get_parameter(
"moveit_manage_controllers", manage_controllers_))
61 manage_controllers_ =
false;
66 const moveit::core::RobotModelConstPtr& robot_model,
67 const planning_scene_monitor::CurrentStateMonitorPtr& csm,
68 bool manage_controllers)
69 : node_(node), robot_model_(robot_model), csm_(csm), manage_controllers_(manage_controllers)
76 run_continuous_execution_thread_ =
false;
78 private_executor_->cancel();
79 if (private_executor_thread_.joinable())
80 private_executor_thread_.join();
81 private_executor_.reset();
84 void TrajectoryExecutionManager::initialize()
87 execution_complete_ =
true;
88 stop_continuous_execution_ =
false;
89 current_context_ = -1;
91 run_continuous_execution_thread_ =
true;
92 execution_duration_monitoring_ =
true;
93 execution_velocity_scaling_ = 1.0;
94 allowed_start_tolerance_ = 0.01;
95 wait_for_trajectory_completion_ =
true;
97 allowed_execution_duration_scaling_ = DEFAULT_CONTROLLER_GOAL_DURATION_SCALING;
98 allowed_goal_duration_margin_ = DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN;
101 loadControllerParams();
106 controller_manager_loader_ =
107 std::make_unique<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager>>(
108 "moveit_core",
"moveit_controller_manager::MoveItControllerManager");
110 catch (pluginlib::PluginlibException& ex)
112 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while creating controller manager plugin loader: " << ex.what());
116 if (controller_manager_loader_)
118 std::string controller;
120 if (!node_->get_parameter(
"moveit_controller_manager", controller))
122 const std::vector<std::string>& classes = controller_manager_loader_->getDeclaredClasses();
123 if (classes.size() == 1)
125 controller = classes[0];
127 "Parameter '~moveit_controller_manager' is not specified but only one "
128 "matching plugin was found: '%s'. Using that one.",
133 RCLCPP_FATAL(LOGGER,
"Parameter '~moveit_controller_manager' not specified. This is needed to "
134 "identify the plugin to use for interacting with controllers. No paths can "
140 if (controller ==
"moveit_ros_control_interface/MoveItControllerManager")
142 RCLCPP_WARN(LOGGER,
"moveit_ros_control_interface/MoveItControllerManager is deprecated. Replace with "
143 "`moveit_ros_control_interface/MoveItControllerManager.`");
145 if (controller ==
"moveit_ros_control_interface/MoveItMultiControllerManager")
147 RCLCPP_WARN(LOGGER,
"moveit_ros_control_interface/MoveItMultiControllerManager is deprecated. Replace with "
148 "`moveit_ros_control_interface/Ros2ControlMultiManager.`");
151 if (!controller.empty())
157 rclcpp::NodeOptions
opt;
158 opt.allow_undeclared_parameters(
true);
159 opt.automatically_declare_parameters_from_overrides(
true);
160 controller_mgr_node_.reset(
new rclcpp::Node(
"moveit_simple_controller_manager",
opt));
162 auto all_params = node_->get_node_parameters_interface()->get_parameter_overrides();
163 for (
const auto& param : all_params)
164 controller_mgr_node_->set_parameter(rclcpp::Parameter(param.first, param.second));
166 controller_manager_ = controller_manager_loader_->createUniqueInstance(controller);
167 controller_manager_->initialize(controller_mgr_node_);
168 private_executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
169 private_executor_->add_node(controller_mgr_node_);
172 private_executor_thread_ = std::thread([
this]() { private_executor_->spin(); });
174 catch (pluginlib::PluginlibException& ex)
176 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while loading controller manager '" << controller <<
"': " << ex.what());
181 reloadControllerInformation();
185 auto callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
186 auto options = rclcpp::SubscriptionOptions();
187 options.callback_group = callback_group;
188 event_topic_subscriber_ = node_->create_subscription<std_msgs::msg::String>(
190 [
this](
const std_msgs::msg::String::ConstSharedPtr& event) {
return receiveEvent(event); },
options);
192 controller_mgr_node_->get_parameter(
"trajectory_execution.execution_duration_monitoring",
193 execution_duration_monitoring_);
194 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_execution_duration_scaling",
195 allowed_execution_duration_scaling_);
196 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_goal_duration_margin",
197 allowed_goal_duration_margin_);
198 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_start_tolerance", allowed_start_tolerance_);
200 if (manage_controllers_)
201 RCLCPP_INFO(LOGGER,
"Trajectory execution is managing controllers");
203 RCLCPP_INFO(LOGGER,
"Trajectory execution is not managing controllers");
205 auto controller_mgr_parameter_set_callback = [
this](
const std::vector<rclcpp::Parameter>& parameters) {
206 auto result = rcl_interfaces::msg::SetParametersResult();
207 result.successful =
true;
208 for (
const auto& parameter : parameters)
210 const std::string&
name = parameter.get_name();
211 if (
name ==
"trajectory_execution.execution_duration_monitoring")
213 else if (
name ==
"trajectory_execution.allowed_execution_duration_scaling")
215 else if (
name ==
"trajectory_execution.allowed_goal_duration_margin")
217 else if (
name ==
"trajectory_execution.execution_velocity_scaling")
219 else if (
name ==
"trajectory_execution.allowed_start_tolerance")
221 else if (
name ==
"trajectory_execution.wait_for_trajectory_completion")
224 result.successful =
false;
228 callback_handler_ = controller_mgr_node_->add_on_set_parameters_callback(controller_mgr_parameter_set_callback);
233 execution_duration_monitoring_ = flag;
238 allowed_execution_duration_scaling_ = scaling;
243 allowed_goal_duration_margin_ = margin;
248 execution_velocity_scaling_ = scaling;
253 allowed_start_tolerance_ = tolerance;
258 wait_for_trajectory_completion_ = flag;
263 return manage_controllers_;
268 return controller_manager_;
276 RCLCPP_WARN_STREAM(LOGGER,
"Unknown event type: '" << event <<
"'");
279 void TrajectoryExecutionManager::receiveEvent(
const std_msgs::msg::String::ConstSharedPtr& event)
281 RCLCPP_INFO_STREAM(LOGGER,
"Received event '" << event->data <<
"'");
287 if (controller.empty())
288 return push(trajectory, std::vector<std::string>());
290 return push(trajectory, std::vector<std::string>(1, controller));
294 const std::string& controller)
296 if (controller.empty())
297 return push(trajectory, std::vector<std::string>());
299 return push(trajectory, std::vector<std::string>(1, controller));
303 const std::vector<std::string>& controllers)
305 moveit_msgs::msg::RobotTrajectory traj;
306 traj.joint_trajectory = trajectory;
307 return push(traj, controllers);
311 const std::vector<std::string>& controllers)
313 if (!execution_complete_)
315 RCLCPP_ERROR(LOGGER,
"Cannot push a new trajectory while another is being executed");
320 if (configure(*context, trajectory, controllers))
324 std::stringstream ss;
325 ss <<
"Pushed trajectory for execution using controllers [ ";
326 for (
const std::string& controller : context->
controllers_)
327 ss << controller <<
" ";
332 RCLCPP_INFO_STREAM(LOGGER, ss.str());
334 trajectories_.push_back(context);
347 const std::string& controller)
349 if (controller.empty())
352 return pushAndExecute(trajectory, std::vector<std::string>(1, controller));
356 const std::string& controller)
358 if (controller.empty())
361 return pushAndExecute(trajectory, std::vector<std::string>(1, controller));
366 if (controller.empty())
369 return pushAndExecute(state, std::vector<std::string>(1, controller));
373 const std::vector<std::string>& controllers)
375 moveit_msgs::msg::RobotTrajectory traj;
376 traj.joint_trajectory = trajectory;
381 const std::vector<std::string>& controllers)
383 moveit_msgs::msg::RobotTrajectory traj;
384 traj.joint_trajectory.header = state.header;
385 traj.joint_trajectory.joint_names = state.name;
386 traj.joint_trajectory.points.resize(1);
387 traj.joint_trajectory.points[0].positions = state.position;
388 traj.joint_trajectory.points[0].velocities = state.velocity;
389 traj.joint_trajectory.points[0].effort = state.effort;
390 traj.joint_trajectory.points[0].time_from_start = rclcpp::Duration(0, 0);
395 const std::vector<std::string>& controllers)
397 if (!execution_complete_)
399 RCLCPP_ERROR(LOGGER,
"Cannot push & execute a new trajectory while another is being executed");
404 if (configure(*context, trajectory, controllers))
407 std::scoped_lock slock(continuous_execution_mutex_);
408 continuous_execution_queue_.push_back(context);
409 if (!continuous_execution_thread_)
410 continuous_execution_thread_ = std::make_unique<std::thread>([
this] { continuousExecutionThread(); });
413 continuous_execution_condition_.notify_all();
424 void TrajectoryExecutionManager::continuousExecutionThread()
426 std::set<moveit_controller_manager::MoveItControllerHandlePtr> used_handles;
427 while (run_continuous_execution_thread_)
429 if (!stop_continuous_execution_)
431 std::unique_lock<std::mutex> ulock(continuous_execution_mutex_);
432 while (continuous_execution_queue_.empty() && run_continuous_execution_thread_ && !stop_continuous_execution_)
433 continuous_execution_condition_.wait(ulock);
436 if (stop_continuous_execution_ || !run_continuous_execution_thread_)
438 for (
const moveit_controller_manager::MoveItControllerHandlePtr& used_handle : used_handles)
440 used_handle->cancelExecution();
441 used_handles.clear();
442 while (!continuous_execution_queue_.empty())
444 TrajectoryExecutionContext* context = continuous_execution_queue_.front();
445 continuous_execution_queue_.pop_front();
448 stop_continuous_execution_ =
false;
452 while (!continuous_execution_queue_.empty())
454 TrajectoryExecutionContext* context =
nullptr;
456 std::scoped_lock slock(continuous_execution_mutex_);
457 if (continuous_execution_queue_.empty())
459 context = continuous_execution_queue_.front();
460 continuous_execution_queue_.pop_front();
461 if (continuous_execution_queue_.empty())
462 continuous_execution_condition_.notify_all();
466 std::set<moveit_controller_manager::MoveItControllerHandlePtr>::iterator uit = used_handles.begin();
467 while (uit != used_handles.end())
470 std::set<moveit_controller_manager::MoveItControllerHandlePtr>::iterator to_erase = uit;
472 used_handles.erase(to_erase);
483 std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles(context->controllers_.size());
484 for (std::size_t i = 0; i < context->controllers_.size(); ++i)
486 moveit_controller_manager::MoveItControllerHandlePtr h;
489 h = controller_manager_->getControllerHandle(context->controllers_[i]);
491 catch (std::exception& ex)
493 RCLCPP_ERROR(LOGGER,
"%s caught when retrieving controller handle", ex.what());
498 RCLCPP_ERROR(LOGGER,
"No controller handle for controller '%s'. Aborting.",
499 context->controllers_[i].c_str());
506 if (stop_continuous_execution_ || !run_continuous_execution_thread_)
513 if (!handles.empty())
514 for (std::size_t i = 0; i < context->trajectory_parts_.size(); ++i)
519 ok = handles[i]->sendTrajectory(context->trajectory_parts_[i]);
521 catch (std::exception& ex)
523 RCLCPP_ERROR(LOGGER,
"Caught %s when sending trajectory to controller", ex.what());
527 for (std::size_t j = 0; j < i; ++j)
530 handles[j]->cancelExecution();
532 catch (std::exception& ex)
534 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution", ex.what());
536 RCLCPP_ERROR(LOGGER,
"Failed to send trajectory part %zu of %zu to controller %s", i + 1,
537 context->trajectory_parts_.size(), handles[i]->getName().c_str());
539 RCLCPP_ERROR(LOGGER,
"Cancelling previously sent trajectory parts");
548 for (
const moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
549 used_handles.insert(handle);
553 RCLCPP_ERROR(LOGGER,
"Not all needed controllers are active. Cannot push and execute. You can try "
554 "calling ensureActiveControllers() before pushAndExecute()");
562 void TrajectoryExecutionManager::reloadControllerInformation()
564 known_controllers_.clear();
565 if (controller_manager_)
567 std::vector<std::string> names;
568 controller_manager_->getControllersList(names);
569 for (
const std::string&
name : names)
571 std::vector<std::string> joints;
572 controller_manager_->getControllerJoints(
name, joints);
573 ControllerInformation ci;
575 ci.joints_.insert(joints.begin(), joints.end());
576 known_controllers_[ci.name_] = ci;
580 controller_manager_->getActiveControllers(names);
581 for (
const auto& active_name : names)
583 auto found_it = std::find_if(known_controllers_.begin(), known_controllers_.end(),
584 [&](
const auto& known_controller) { return known_controller.first == active_name; });
585 if (found_it != known_controllers_.end())
587 found_it->second.state_.active_ =
true;
591 for (std::map<std::string, ControllerInformation>::iterator it = known_controllers_.begin();
592 it != known_controllers_.end(); ++it)
593 for (std::map<std::string, ControllerInformation>::iterator jt = known_controllers_.begin();
594 jt != known_controllers_.end(); ++jt)
597 std::vector<std::string> intersect;
598 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), jt->second.joints_.begin(),
599 jt->second.joints_.end(), std::back_inserter(intersect));
600 if (!intersect.empty())
602 it->second.overlapping_controllers_.insert(jt->first);
603 jt->second.overlapping_controllers_.insert(it->first);
609 RCLCPP_ERROR(LOGGER,
"Failed to reload controllers: `controller_manager_` does not exist.");
613 void TrajectoryExecutionManager::updateControllerState(
const std::string& controller,
const rclcpp::Duration& age)
615 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
616 if (it != known_controllers_.end())
617 updateControllerState(it->second, age);
619 RCLCPP_ERROR(LOGGER,
"Controller '%s' is not known.", controller.c_str());
622 void TrajectoryExecutionManager::updateControllerState(ControllerInformation& ci,
const rclcpp::Duration& age)
624 if (node_->now() - ci.last_update_ >= age)
626 if (controller_manager_)
629 RCLCPP_INFO(LOGGER,
"Updating information for controller '%s'.", ci.name_.c_str());
630 ci.state_ = controller_manager_->getControllerState(ci.name_);
631 ci.last_update_ = node_->now();
635 RCLCPP_INFO(LOGGER,
"Information for controller '%s' is assumed to be up to date.", ci.name_.c_str());
638 void TrajectoryExecutionManager::updateControllersState(
const rclcpp::Duration& age)
640 for (std::pair<const std::string, ControllerInformation>& known_controller : known_controllers_)
641 updateControllerState(known_controller.second, age);
644 bool TrajectoryExecutionManager::checkControllerCombination(std::vector<std::string>& selected,
645 const std::set<std::string>& actuated_joints)
647 std::set<std::string> combined_joints;
648 for (
const std::string& controller : selected)
650 const ControllerInformation& ci = known_controllers_[controller];
651 combined_joints.insert(ci.joints_.begin(), ci.joints_.end());
656 std::stringstream ss, saj, sac;
657 for (
const std::string& controller : selected)
658 ss << controller <<
" ";
659 for (
const std::string& actuated_joint : actuated_joints)
660 saj << actuated_joint <<
" ";
661 for (
const std::string& combined_joint : combined_joints)
662 sac << combined_joint <<
" ";
663 RCLCPP_INFO(LOGGER,
"Checking if controllers [ %s] operating on joints [ %s] cover joints [ %s]", ss.str().c_str(),
664 sac.str().c_str(), saj.str().c_str());
667 return std::includes(combined_joints.begin(), combined_joints.end(), actuated_joints.begin(), actuated_joints.end());
670 void TrajectoryExecutionManager::generateControllerCombination(std::size_t start_index, std::size_t controller_count,
671 const std::vector<std::string>& available_controllers,
672 std::vector<std::string>& selected_controllers,
674 const std::set<std::string>& actuated_joints)
676 if (selected_controllers.size() == controller_count)
678 if (checkControllerCombination(selected_controllers, actuated_joints))
683 for (std::size_t i = start_index; i < available_controllers.size(); ++i)
685 bool overlap =
false;
686 const ControllerInformation& ci = known_controllers_[available_controllers[i]];
687 for (std::size_t j = 0; j < selected_controllers.size() && !overlap; ++j)
689 if (ci.overlapping_controllers_.find(selected_controllers[j]) != ci.overlapping_controllers_.end())
694 selected_controllers.push_back(available_controllers[i]);
695 generateControllerCombination(i + 1, controller_count, available_controllers, selected_controllers,
697 selected_controllers.pop_back();
703 struct OrderPotentialControllerCombination
705 bool operator()(
const std::size_t
a,
const std::size_t b)
const
735 bool TrajectoryExecutionManager::findControllers(
const std::set<std::string>& actuated_joints,
736 std::size_t controller_count,
737 const std::vector<std::string>& available_controllers,
738 std::vector<std::string>& selected_controllers)
741 std::vector<std::string> work_area;
742 OrderPotentialControllerCombination order;
743 std::vector<std::vector<std::string>>&
selected_options = order.selected_options;
744 generateControllerCombination(0, controller_count, available_controllers, work_area,
selected_options,
749 std::stringstream saj;
750 std::stringstream sac;
751 for (
const std::string& available_controller : available_controllers)
752 sac << available_controller <<
" ";
753 for (
const std::string& actuated_joint : actuated_joints)
754 saj << actuated_joint <<
" ";
755 RCLCPP_INFO(
LOGGER,
"Looking for %zu controllers among [ %s] that cover joints [ %s]. Found %zd options.",
756 controller_count, sac.str().c_str(), saj.str().c_str(),
selected_options.size());
782 updateControllerState(
selected_options[i][k], DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
783 const ControllerInformation& ci = known_controllers_[
selected_options[i][k]];
785 if (ci.state_.default_)
786 order.nrdefault[i]++;
787 if (ci.state_.active_)
789 order.nrjoints[i] += ci.joints_.size();
799 std::sort(bijection.begin(), bijection.end(), order);
803 if (!manage_controllers_)
826 for (
const std::string& controller : controllers)
828 updateControllerState(controller, DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
829 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
830 if (it == known_controllers_.end() || !it->second.state_.active_)
836 bool TrajectoryExecutionManager::selectControllers(
const std::set<std::string>& actuated_joints,
837 const std::vector<std::string>& available_controllers,
838 std::vector<std::string>& selected_controllers)
840 for (std::size_t i = 1; i <= available_controllers.size(); ++i)
841 if (findControllers(actuated_joints, i, available_controllers, selected_controllers))
846 std::vector<std::string> other_option;
847 for (std::size_t j = i + 1; j <= available_controllers.size(); ++j)
848 if (findControllers(actuated_joints, j, available_controllers, other_option))
852 selected_controllers = other_option;
862 bool TrajectoryExecutionManager::distributeTrajectory(
const moveit_msgs::msg::RobotTrajectory& trajectory,
863 const std::vector<std::string>& controllers,
864 std::vector<moveit_msgs::msg::RobotTrajectory>& parts)
867 parts.resize(controllers.size());
869 std::set<std::string> actuated_joints_mdof;
870 actuated_joints_mdof.insert(trajectory.multi_dof_joint_trajectory.joint_names.begin(),
871 trajectory.multi_dof_joint_trajectory.joint_names.end());
872 std::set<std::string> actuated_joints_single;
873 for (
const std::string& joint_name : trajectory.joint_trajectory.joint_names)
880 actuated_joints_single.insert(jm->
getName());
884 for (std::size_t i = 0; i < controllers.size(); ++i)
886 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controllers[i]);
887 if (it == known_controllers_.end())
889 RCLCPP_ERROR_STREAM(LOGGER,
"Controller " << controllers[i] <<
" not found.");
892 std::vector<std::string> intersect_mdof;
893 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_mdof.begin(),
894 actuated_joints_mdof.end(), std::back_inserter(intersect_mdof));
895 std::vector<std::string> intersect_single;
896 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_single.begin(),
897 actuated_joints_single.end(), std::back_inserter(intersect_single));
898 if (intersect_mdof.empty() && intersect_single.empty())
899 RCLCPP_WARN_STREAM(LOGGER,
"No joints to be distributed for controller " << controllers[i]);
901 if (!intersect_mdof.empty())
903 std::vector<std::string>& jnames = parts[i].multi_dof_joint_trajectory.joint_names;
904 jnames.insert(jnames.end(), intersect_mdof.begin(), intersect_mdof.end());
905 std::map<std::string, std::size_t> index;
906 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
907 index[trajectory.multi_dof_joint_trajectory.joint_names[j]] = j;
908 std::vector<std::size_t> bijection(jnames.size());
909 for (std::size_t j = 0; j < jnames.size(); ++j)
910 bijection[j] = index[jnames[j]];
912 parts[i].multi_dof_joint_trajectory.header.frame_id = trajectory.multi_dof_joint_trajectory.header.frame_id;
913 parts[i].multi_dof_joint_trajectory.points.resize(trajectory.multi_dof_joint_trajectory.points.size());
914 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.points.size(); ++j)
916 parts[i].multi_dof_joint_trajectory.points[j].time_from_start =
917 trajectory.multi_dof_joint_trajectory.points[j].time_from_start;
918 parts[i].multi_dof_joint_trajectory.points[j].transforms.resize(bijection.size());
919 for (std::size_t k = 0; k < bijection.size(); ++k)
921 parts[i].multi_dof_joint_trajectory.points[j].transforms[k] =
922 trajectory.multi_dof_joint_trajectory.points[j].transforms[bijection[k]];
924 if (!trajectory.multi_dof_joint_trajectory.points[j].velocities.empty())
926 parts[i].multi_dof_joint_trajectory.points[j].velocities.resize(bijection.size());
928 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.x =
929 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.x * execution_velocity_scaling_;
931 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.y =
932 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.y * execution_velocity_scaling_;
934 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.z =
935 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.z * execution_velocity_scaling_;
937 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.x =
938 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.x * execution_velocity_scaling_;
940 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.y =
941 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.y * execution_velocity_scaling_;
943 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.z =
944 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.z * execution_velocity_scaling_;
949 if (!intersect_single.empty())
951 std::vector<std::string>& jnames = parts[i].joint_trajectory.joint_names;
952 jnames.insert(jnames.end(), intersect_single.begin(), intersect_single.end());
953 parts[i].joint_trajectory.header = trajectory.joint_trajectory.header;
954 std::map<std::string, std::size_t> index;
955 for (std::size_t j = 0; j < trajectory.joint_trajectory.joint_names.size(); ++j)
956 index[trajectory.joint_trajectory.joint_names[j]] = j;
957 std::vector<std::size_t> bijection(jnames.size());
958 for (std::size_t j = 0; j < jnames.size(); ++j)
959 bijection[j] = index[jnames[j]];
960 parts[i].joint_trajectory.points.resize(trajectory.joint_trajectory.points.size());
961 for (std::size_t j = 0; j < trajectory.joint_trajectory.points.size(); ++j)
963 parts[i].joint_trajectory.points[j].time_from_start = trajectory.joint_trajectory.points[j].time_from_start;
964 if (!trajectory.joint_trajectory.points[j].positions.empty())
966 parts[i].joint_trajectory.points[j].positions.resize(bijection.size());
967 for (std::size_t k = 0; k < bijection.size(); ++k)
968 parts[i].joint_trajectory.points[j].positions[k] =
969 trajectory.joint_trajectory.points[j].positions[bijection[k]];
971 if (!trajectory.joint_trajectory.points[j].velocities.empty())
973 parts[i].joint_trajectory.points[j].velocities.resize(bijection.size());
974 for (std::size_t k = 0; k < bijection.size(); ++k)
975 parts[i].joint_trajectory.points[j].velocities[k] =
976 trajectory.joint_trajectory.points[j].velocities[bijection[k]] * execution_velocity_scaling_;
978 if (!trajectory.joint_trajectory.points[j].accelerations.empty())
980 parts[i].joint_trajectory.points[j].accelerations.resize(bijection.size());
981 for (std::size_t k = 0; k < bijection.size(); ++k)
982 parts[i].joint_trajectory.points[j].accelerations[k] =
983 trajectory.joint_trajectory.points[j].accelerations[bijection[k]];
985 if (!trajectory.joint_trajectory.points[j].effort.empty())
987 parts[i].joint_trajectory.points[j].effort.resize(bijection.size());
988 for (std::size_t k = 0; k < bijection.size(); ++k)
989 parts[i].joint_trajectory.points[j].effort[k] =
990 trajectory.joint_trajectory.points[j].effort[bijection[k]];
999 bool TrajectoryExecutionManager::validate(
const TrajectoryExecutionContext& context)
const
1001 if (allowed_start_tolerance_ == 0)
1004 RCLCPP_INFO(LOGGER,
"Validating trajectory with allowed_start_tolerance %g", allowed_start_tolerance_);
1006 moveit::core::RobotStatePtr current_state;
1007 if (!csm_->waitForCurrentState(node_->now()) || !(current_state = csm_->getCurrentState()))
1009 RCLCPP_WARN(LOGGER,
"Failed to validate trajectory: couldn't receive full current joint state within 1s");
1013 for (
const auto& trajectory : context.trajectory_parts_)
1015 if (!trajectory.joint_trajectory.points.empty())
1018 const std::vector<double>& positions = trajectory.joint_trajectory.points.front().positions;
1019 const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1020 if (positions.size() != joint_names.size())
1022 RCLCPP_ERROR(LOGGER,
"Wrong trajectory: #joints: %zu != #positions: %zu", joint_names.size(), positions.size());
1026 for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
1031 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown joint in trajectory: " << joint_names[i]);
1035 double cur_position = current_state->getJointPositions(jm)[0];
1036 double traj_position = positions[i];
1040 if (jm->
distance(&cur_position, &traj_position) > allowed_start_tolerance_)
1042 RCLCPP_ERROR(LOGGER,
1043 "\nInvalid Trajectory: start point deviates from current robot state more than %g"
1044 "\njoint '%s': expected: %g, current: %g",
1045 allowed_start_tolerance_, joint_names[i].c_str(), traj_position, cur_position);
1050 if (!trajectory.multi_dof_joint_trajectory.points.empty())
1053 const std::vector<geometry_msgs::msg::Transform>& transforms =
1054 trajectory.multi_dof_joint_trajectory.points.front().transforms;
1055 const std::vector<std::string>& joint_names = trajectory.multi_dof_joint_trajectory.joint_names;
1056 if (transforms.size() != joint_names.size())
1058 RCLCPP_ERROR(LOGGER,
"Wrong trajectory: #joints: %zu != #transforms: %zu", joint_names.size(),
1063 for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
1068 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown joint in trajectory: " << joint_names[i]);
1074 Eigen::Isometry3d cur_transform, start_transform;
1077 start_transform = tf2::transformToEigen(transforms[i]);
1078 ASSERT_ISOMETRY(start_transform)
1079 Eigen::Vector3d offset = cur_transform.translation() - start_transform.translation();
1080 Eigen::AngleAxisd rotation;
1081 rotation.fromRotationMatrix(cur_transform.linear().transpose() * start_transform.linear());
1082 if ((offset.array() > allowed_start_tolerance_).any() || rotation.angle() > allowed_start_tolerance_)
1084 RCLCPP_ERROR_STREAM(LOGGER,
"\nInvalid Trajectory: start point deviates from current robot state more than "
1085 << allowed_start_tolerance_ <<
"\nmulti-dof joint '" << joint_names[i]
1086 <<
"': pos delta: " << offset.transpose()
1087 <<
" rot delta: " << rotation.angle());
1096 bool TrajectoryExecutionManager::configure(TrajectoryExecutionContext& context,
1097 const moveit_msgs::msg::RobotTrajectory& trajectory,
1098 const std::vector<std::string>& controllers)
1100 if (trajectory.multi_dof_joint_trajectory.points.empty() && trajectory.joint_trajectory.points.empty())
1106 reloadControllerInformation();
1107 std::set<std::string> actuated_joints;
1109 auto is_actuated = [
this](
const std::string& joint_name) ->
bool {
1113 for (
const std::string& joint_name : trajectory.multi_dof_joint_trajectory.joint_names)
1114 if (is_actuated(joint_name))
1115 actuated_joints.insert(joint_name);
1116 for (
const std::string& joint_name : trajectory.joint_trajectory.joint_names)
1117 if (is_actuated(joint_name))
1118 actuated_joints.insert(joint_name);
1120 if (actuated_joints.empty())
1122 RCLCPP_WARN(LOGGER,
"The trajectory to execute specifies no joints");
1126 if (controllers.empty())
1129 bool reloaded =
false;
1133 std::vector<std::string> all_controller_names;
1134 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1135 it != known_controllers_.end(); ++it)
1136 all_controller_names.push_back(it->first);
1137 if (selectControllers(actuated_joints, all_controller_names, context.controllers_))
1139 if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
1147 reloadControllerInformation();
1158 bool reloaded =
false;
1159 for (
const std::string& controller : controllers)
1160 if (known_controllers_.find(controller) == known_controllers_.end())
1162 reloadControllerInformation();
1167 for (
const std::string& controller : controllers)
1168 if (known_controllers_.find(controller) == known_controllers_.end())
1170 RCLCPP_ERROR(LOGGER,
"Controller '%s' is not known", controller.c_str());
1173 if (selectControllers(actuated_joints, controllers, context.controllers_))
1175 if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
1179 std::stringstream ss;
1180 for (
const std::string& actuated_joint : actuated_joints)
1181 ss << actuated_joint <<
" ";
1182 RCLCPP_ERROR(LOGGER,
"Unable to identify any set of controllers that can actuate the specified joints: [ %s]",
1185 std::stringstream ss2;
1186 std::map<std::string, ControllerInformation>::const_iterator mi;
1187 for (mi = known_controllers_.begin(); mi != known_controllers_.end(); ++mi)
1189 ss2 <<
"controller '" << mi->second.name_ <<
"' controls joints:\n";
1191 std::set<std::string>::const_iterator ji;
1192 for (ji = mi->second.joints_.begin(); ji != mi->second.joints_.end(); ++ji)
1194 ss2 <<
" " << *ji <<
'\n';
1197 RCLCPP_ERROR(LOGGER,
"Known controllers and their joints:\n%s", ss2.str().c_str());
1207 void TrajectoryExecutionManager::stopExecutionInternal()
1210 for (moveit_controller_manager::MoveItControllerHandlePtr& active_handle : active_handles_)
1213 active_handle->cancelExecution();
1215 catch (std::exception& ex)
1217 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution.", ex.what());
1223 stop_continuous_execution_ =
true;
1224 continuous_execution_condition_.notify_all();
1226 if (!execution_complete_)
1228 execution_state_mutex_.lock();
1229 if (!execution_complete_)
1235 execution_complete_ =
true;
1236 stopExecutionInternal();
1240 execution_state_mutex_.unlock();
1241 RCLCPP_INFO(LOGGER,
"Stopped trajectory execution.");
1244 std::scoped_lock lock(execution_thread_mutex_);
1245 if (execution_thread_)
1247 execution_thread_->join();
1248 execution_thread_.reset();
1255 execution_state_mutex_.unlock();
1257 else if (execution_thread_)
1260 std::scoped_lock lock(execution_thread_mutex_);
1261 if (execution_thread_)
1263 execution_thread_->join();
1264 execution_thread_.reset();
1280 if (!trajectories_.empty() && !validate(*trajectories_.front()))
1286 callback(last_execution_status_);
1291 execution_complete_ =
false;
1292 execution_thread_ = std::make_unique<std::thread>(&TrajectoryExecutionManager::executeThread,
this, callback,
1293 part_callback, auto_clear);
1299 std::unique_lock<std::mutex> ulock(execution_state_mutex_);
1300 while (!execution_complete_)
1301 execution_complete_condition_.wait(ulock);
1304 std::unique_lock<std::mutex> ulock(continuous_execution_mutex_);
1305 while (!continuous_execution_queue_.empty())
1306 continuous_execution_condition_.wait(ulock);
1312 return last_execution_status_;
1317 if (execution_complete_)
1321 trajectories_.clear();
1323 std::scoped_lock slock(continuous_execution_mutex_);
1324 while (!continuous_execution_queue_.empty())
1326 delete continuous_execution_queue_.front();
1327 continuous_execution_queue_.pop_front();
1332 RCLCPP_ERROR(LOGGER,
"Cannot push a new trajectory while another is being executed");
1335 void TrajectoryExecutionManager::executeThread(
const ExecutionCompleteCallback& callback,
1336 const PathSegmentCompleteCallback& part_callback,
bool auto_clear)
1339 if (execution_complete_)
1343 callback(last_execution_status_);
1347 RCLCPP_INFO(LOGGER,
"Starting trajectory execution ...");
1354 for (; i < trajectories_.size(); ++i)
1356 bool epart = executePart(i);
1357 if (epart && part_callback)
1359 if (!epart || execution_complete_)
1368 waitForRobotToStop(*trajectories_[i - 1]);
1370 RCLCPP_INFO(LOGGER,
"Completed trajectory execution with status %s ...", last_execution_status_.
asString().c_str());
1373 execution_state_mutex_.lock();
1374 execution_complete_ =
true;
1375 execution_state_mutex_.unlock();
1376 execution_complete_condition_.notify_all();
1384 callback(last_execution_status_);
1387 bool TrajectoryExecutionManager::executePart(std::size_t part_index)
1389 TrajectoryExecutionContext& context = *trajectories_[part_index];
1395 if (execution_complete_)
1398 std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles;
1400 std::scoped_lock slock(execution_state_mutex_);
1401 if (!execution_complete_)
1404 time_index_mutex_.lock();
1405 current_context_ = part_index;
1406 time_index_mutex_.unlock();
1407 active_handles_.resize(context.controllers_.size());
1408 for (std::size_t i = 0; i < context.controllers_.size(); ++i)
1410 moveit_controller_manager::MoveItControllerHandlePtr h;
1413 h = controller_manager_->getControllerHandle(context.controllers_[i]);
1415 catch (std::exception& ex)
1417 RCLCPP_ERROR(LOGGER,
"Caught %s when retrieving controller handle", ex.what());
1421 active_handles_.clear();
1422 current_context_ = -1;
1424 RCLCPP_ERROR(LOGGER,
"No controller handle for controller '%s'. Aborting.", context.controllers_[i].c_str());
1427 active_handles_[i] = h;
1429 handles = active_handles_;
1430 for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1435 ok = active_handles_[i]->sendTrajectory(context.trajectory_parts_[i]);
1437 catch (std::exception& ex)
1439 RCLCPP_ERROR(LOGGER,
"Caught %s when sending trajectory to controller", ex.what());
1443 for (std::size_t j = 0; j < i; ++j)
1446 active_handles_[j]->cancelExecution();
1448 catch (std::exception& ex)
1450 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution", ex.what());
1452 RCLCPP_ERROR(LOGGER,
"Failed to send trajectory part %zu of %zu to controller %s", i + 1,
1453 context.trajectory_parts_.size(), active_handles_[i]->getName().c_str());
1455 RCLCPP_ERROR(LOGGER,
"Cancelling previously sent trajectory parts");
1456 active_handles_.clear();
1457 current_context_ = -1;
1466 rclcpp::Time current_time = node_->now();
1467 auto expected_trajectory_duration = rclcpp::Duration::from_seconds(0);
1468 int longest_part = -1;
1469 for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1471 auto d = rclcpp::Duration::from_seconds(0);
1472 if (!(context.trajectory_parts_[i].joint_trajectory.points.empty() &&
1473 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty()))
1475 if (rclcpp::Time(context.trajectory_parts_[i].joint_trajectory.header.stamp) > current_time)
1476 d = rclcpp::Time(context.trajectory_parts_[i].joint_trajectory.header.stamp) - current_time;
1477 if (rclcpp::Time(context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp) > current_time)
1478 d = std::max(
d, rclcpp::Time(context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp) -
1481 std::max(context.trajectory_parts_[i].joint_trajectory.points.empty() ?
1482 rclcpp::Duration::from_seconds(0) :
1483 rclcpp::Duration(context.trajectory_parts_[i].joint_trajectory.points.back().time_from_start),
1484 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty() ?
1485 rclcpp::Duration::from_seconds(0) :
1487 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.back().time_from_start));
1489 if (longest_part < 0 ||
1490 std::max(context.trajectory_parts_[i].joint_trajectory.points.size(),
1491 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.size()) >
1492 std::max(context.trajectory_parts_[longest_part].joint_trajectory.points.size(),
1493 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size()))
1500 std::map<std::string, double>::const_iterator scaling_it =
1501 controller_allowed_execution_duration_scaling_.find(context.controllers_[i]);
1502 const double current_scaling = scaling_it != controller_allowed_execution_duration_scaling_.end() ?
1503 scaling_it->second :
1504 allowed_execution_duration_scaling_;
1506 std::map<std::string, double>::const_iterator margin_it =
1507 controller_allowed_goal_duration_margin_.find(context.controllers_[i]);
1508 const double current_margin = margin_it != controller_allowed_goal_duration_margin_.end() ?
1510 allowed_goal_duration_margin_;
1513 expected_trajectory_duration =
1514 std::max(
d * current_scaling + rclcpp::Duration::from_seconds(current_margin), expected_trajectory_duration);
1518 if (longest_part >= 0)
1520 std::scoped_lock slock(time_index_mutex_);
1522 if (context.trajectory_parts_[longest_part].joint_trajectory.points.size() >=
1523 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size())
1525 auto d = rclcpp::Duration::from_seconds(0);
1526 if (rclcpp::Time(context.trajectory_parts_[longest_part].joint_trajectory.header.stamp) > current_time)
1527 d = rclcpp::Time(context.trajectory_parts_[longest_part].joint_trajectory.header.stamp) - current_time;
1528 for (trajectory_msgs::msg::JointTrajectoryPoint& point :
1529 context.trajectory_parts_[longest_part].joint_trajectory.points)
1530 time_index_.push_back(current_time +
d + rclcpp::Duration(point.time_from_start));
1534 auto d = rclcpp::Duration::from_seconds(0);
1535 if (rclcpp::Time(context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp) > current_time)
1536 d = rclcpp::Time(context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp) -
1538 for (trajectory_msgs::msg::MultiDOFJointTrajectoryPoint& point :
1539 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points)
1540 time_index_.push_back(current_time +
d + rclcpp::Duration(point.time_from_start));
1545 for (moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
1547 if (execution_duration_monitoring_)
1549 if (!handle->waitForExecution(expected_trajectory_duration))
1550 if (!execution_complete_ && node_->now() - current_time > expected_trajectory_duration)
1552 RCLCPP_ERROR(LOGGER,
1553 "Controller is taking too long to execute trajectory (the expected upper "
1554 "bound for the trajectory execution was %lf seconds). Stopping trajectory.",
1555 expected_trajectory_duration.seconds());
1557 std::scoped_lock slock(execution_state_mutex_);
1558 stopExecutionInternal();
1567 handle->waitForExecution();
1570 if (execution_complete_)
1577 RCLCPP_WARN_STREAM(LOGGER,
"Controller handle " << handle->getName() <<
" reports status "
1578 << handle->getLastExecutionStatus().asString());
1579 last_execution_status_ = handle->getLastExecutionStatus();
1585 execution_state_mutex_.lock();
1586 active_handles_.clear();
1589 time_index_mutex_.lock();
1590 time_index_.clear();
1591 current_context_ = -1;
1592 time_index_mutex_.unlock();
1594 execution_state_mutex_.unlock();
1599 RCLCPP_ERROR(LOGGER,
"Active status of required controllers can not be assured.");
1605 bool TrajectoryExecutionManager::waitForRobotToStop(
const TrajectoryExecutionContext& context,
double wait_time)
1608 if (allowed_start_tolerance_ == 0 || !wait_for_trajectory_completion_)
1610 RCLCPP_INFO(LOGGER,
"Not waiting for trajectory completion");
1614 auto start = std::chrono::system_clock::now();
1615 double time_remaining = wait_time;
1617 moveit::core::RobotStatePtr prev_state, cur_state;
1618 prev_state = csm_->getCurrentState();
1619 prev_state->enforceBounds();
1622 unsigned int no_motion_count = 0;
1623 while (time_remaining > 0. && no_motion_count < 3)
1625 if (!csm_->waitForCurrentState(node_->now(), time_remaining) || !(cur_state = csm_->getCurrentState()))
1627 RCLCPP_WARN(LOGGER,
"Failed to receive current joint state");
1630 cur_state->enforceBounds();
1631 std::chrono::duration<double> elapsed_seconds = std::chrono::system_clock::now() - start;
1632 time_remaining = wait_time - elapsed_seconds.count();
1636 for (
const auto& trajectory : context.trajectory_parts_)
1638 const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1639 const std::size_t n = joint_names.size();
1641 for (std::size_t i = 0; i < n && !moved; ++i)
1647 if (fabs(cur_state->getJointPositions(jm)[0] - prev_state->getJointPositions(jm)[0]) > allowed_start_tolerance_)
1650 no_motion_count = 0;
1659 std::swap(prev_state, cur_state);
1662 return time_remaining > 0;
1667 std::scoped_lock slock(time_index_mutex_);
1668 if (current_context_ < 0)
1669 return std::make_pair(-1, -1);
1670 if (time_index_.empty())
1671 return std::make_pair(
static_cast<int>(current_context_), -1);
1672 std::vector<rclcpp::Time>::const_iterator time_index_it =
1673 std::lower_bound(time_index_.begin(), time_index_.end(), node_->now());
1674 int pos = time_index_it - time_index_.begin();
1675 return std::make_pair(
static_cast<int>(current_context_), pos);
1678 const std::vector<TrajectoryExecutionManager::TrajectoryExecutionContext*>&
1681 return trajectories_;
1686 return last_execution_status_;
1692 if (joint_model_group)
1700 std::vector<std::string> all_controller_names;
1701 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1702 it != known_controllers_.end(); ++it)
1703 all_controller_names.push_back(it->first);
1704 std::vector<std::string> selected_controllers;
1705 std::set<std::string> jset;
1706 for (
const std::string& joint : joints)
1717 if (selectControllers(jset, all_controller_names, selected_controllers))
1730 reloadControllerInformation();
1732 updateControllersState(DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
1734 if (manage_controllers_)
1736 std::vector<std::string> controllers_to_activate;
1737 std::vector<std::string> controllers_to_deactivate;
1738 std::set<std::string> joints_to_be_activated;
1739 std::set<std::string> joints_to_be_deactivated;
1740 for (
const std::string& controller : controllers)
1742 std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.find(controller);
1743 if (it == known_controllers_.end())
1745 std::stringstream stream;
1746 for (
const auto& controller : known_controllers_)
1748 stream <<
" `" << controller.first <<
"`";
1750 RCLCPP_WARN_STREAM(LOGGER,
"Controller " << controller <<
" is not known. Known controllers: " << stream.str());
1753 if (!it->second.state_.active_)
1755 RCLCPP_DEBUG_STREAM(LOGGER,
"Need to activate " << controller);
1756 controllers_to_activate.push_back(controller);
1757 joints_to_be_activated.insert(it->second.joints_.begin(), it->second.joints_.end());
1758 for (
const std::string& overlapping_controller : it->second.overlapping_controllers_)
1760 const ControllerInformation& ci = known_controllers_[overlapping_controller];
1761 if (ci.state_.active_)
1763 controllers_to_deactivate.push_back(overlapping_controller);
1764 joints_to_be_deactivated.insert(ci.joints_.begin(), ci.joints_.end());
1769 RCLCPP_DEBUG_STREAM(LOGGER,
"Controller " << controller <<
" is already active");
1771 std::set<std::string> diff;
1772 std::set_difference(joints_to_be_deactivated.begin(), joints_to_be_deactivated.end(),
1773 joints_to_be_activated.begin(), joints_to_be_activated.end(), std::inserter(diff, diff.end()));
1777 std::vector<std::string> possible_additional_controllers;
1778 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1779 it != known_controllers_.end(); ++it)
1782 for (
const std::string& controller_to_activate : controllers_to_activate)
1783 if (it->second.overlapping_controllers_.find(controller_to_activate) !=
1784 it->second.overlapping_controllers_.end())
1790 possible_additional_controllers.push_back(it->first);
1794 std::vector<std::string> additional_controllers;
1795 if (selectControllers(diff, possible_additional_controllers, additional_controllers))
1796 controllers_to_activate.insert(controllers_to_activate.end(), additional_controllers.begin(),
1797 additional_controllers.end());
1801 if (!controllers_to_activate.empty() || !controllers_to_deactivate.empty())
1803 if (controller_manager_)
1806 for (
const std::string& controller_to_activate : controllers_to_activate)
1808 ControllerInformation& ci = known_controllers_[controller_to_activate];
1809 ci.last_update_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
1812 for (
const std::string& controller_to_activate : controllers_to_deactivate)
1813 known_controllers_[controller_to_activate].last_update_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
1814 return controller_manager_->switchControllers(controllers_to_activate, controllers_to_deactivate);
1824 std::set<std::string> originally_active;
1825 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1826 it != known_controllers_.end(); ++it)
1828 if (it->second.state_.active_)
1830 originally_active.insert(it->first);
1833 return std::includes(originally_active.begin(), originally_active.end(), controllers.begin(), controllers.end());
1837 void TrajectoryExecutionManager::loadControllerParams()
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....
const std::string & getName() const
Get the name of the joint.
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.
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,...
JointType getType() const
Get the type of joint.
const JointModel * getMimic() const
Get the joint this one is mimicking.
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.
void clear()
Clear the trajectories to execute.
bool ensureActiveControllersForGroup(const std::string &group)
Make sure the active controllers are such that trajectories that actuate joints in the specified grou...
void setAllowedGoalDurationMargin(double margin)
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.
void setAllowedExecutionDurationScaling(double scaling)
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="")
std::pair< int, int > getCurrentExpectedTrajectoryIndex() const
static const std::string EXECUTION_EVENT_TOPIC
void enableExecutionDurationMonitoring(bool flag)
bool push(const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &controller="")
void setExecutionVelocityScaling(double scaling)
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)
moveit_controller_manager::ExecutionStatus waitForExecution()
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.
std::function< void(std::size_t)> PathSegmentCompleteCallback
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
const rclcpp::Logger LOGGER
The reported execution status.
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