39 #include <geometric_shapes/check_isometry.h>
40 #include <tf2_eigen/tf2_eigen.hpp>
42 #include <rclcpp/qos.hpp>
46 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.trajectory_execution_manager");
50 static const auto DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE = rclcpp::Duration::from_seconds(1);
51 static const double DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN = 0.5;
54 static const double DEFAULT_CONTROLLER_GOAL_DURATION_SCALING =
58 const moveit::core::RobotModelConstPtr& robot_model,
59 const planning_scene_monitor::CurrentStateMonitorPtr& csm)
60 : node_(node), robot_model_(robot_model), csm_(csm)
62 if (!node_->get_parameter(
"moveit_manage_controllers", manage_controllers_))
63 manage_controllers_ =
false;
68 const moveit::core::RobotModelConstPtr& robot_model,
69 const planning_scene_monitor::CurrentStateMonitorPtr& csm,
70 bool manage_controllers)
71 : node_(node), robot_model_(robot_model), csm_(csm), manage_controllers_(manage_controllers)
78 run_continuous_execution_thread_ =
false;
80 private_executor_->cancel();
81 if (private_executor_thread_.joinable())
82 private_executor_thread_.join();
83 private_executor_.reset();
86 void TrajectoryExecutionManager::initialize()
89 execution_complete_ =
true;
90 stop_continuous_execution_ =
false;
91 current_context_ = -1;
93 run_continuous_execution_thread_ =
true;
94 execution_duration_monitoring_ =
true;
95 execution_velocity_scaling_ = 1.0;
96 allowed_start_tolerance_ = 0.01;
97 wait_for_trajectory_completion_ =
true;
99 allowed_execution_duration_scaling_ = DEFAULT_CONTROLLER_GOAL_DURATION_SCALING;
100 allowed_goal_duration_margin_ = DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN;
105 controller_manager_loader_ =
106 std::make_unique<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager>>(
107 "moveit_core",
"moveit_controller_manager::MoveItControllerManager");
109 catch (pluginlib::PluginlibException& ex)
111 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while creating controller manager plugin loader: " << ex.what());
115 if (controller_manager_loader_)
117 std::string controller;
119 if (!node_->get_parameter(
"moveit_controller_manager", controller))
121 const std::vector<std::string>& classes = controller_manager_loader_->getDeclaredClasses();
122 if (classes.size() == 1)
124 controller = classes[0];
126 "Parameter '~moveit_controller_manager' is not specified but only one "
127 "matching plugin was found: '%s'. Using that one.",
132 RCLCPP_FATAL(LOGGER,
"Parameter '~moveit_controller_manager' not specified. This is needed to "
133 "identify the plugin to use for interacting with controllers. No paths can "
139 if (controller ==
"moveit_ros_control_interface/MoveItControllerManager")
141 RCLCPP_WARN(LOGGER,
"moveit_ros_control_interface/MoveItControllerManager is deprecated. Replace with "
142 "`moveit_ros_control_interface/MoveItControllerManager.`");
144 if (controller ==
"moveit_ros_control_interface/MoveItMultiControllerManager")
146 RCLCPP_WARN(LOGGER,
"moveit_ros_control_interface/MoveItMultiControllerManager is deprecated. Replace with "
147 "`moveit_ros_control_interface/Ros2ControlMultiManager.`");
150 if (!controller.empty())
156 rclcpp::NodeOptions
opt;
157 opt.allow_undeclared_parameters(
true);
158 opt.automatically_declare_parameters_from_overrides(
true);
159 controller_mgr_node_.reset(
new rclcpp::Node(
"moveit_simple_controller_manager",
opt));
161 auto all_params = node_->get_node_parameters_interface()->get_parameter_overrides();
162 for (
const auto& param : all_params)
163 controller_mgr_node_->set_parameter(rclcpp::Parameter(param.first, param.second));
165 controller_manager_ = controller_manager_loader_->createUniqueInstance(controller);
166 controller_manager_->initialize(controller_mgr_node_);
167 private_executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
168 private_executor_->add_node(controller_mgr_node_);
171 private_executor_thread_ = std::thread([
this]() { private_executor_->spin(); });
173 catch (pluginlib::PluginlibException& ex)
175 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while loading controller manager '" << controller <<
"': " << ex.what());
180 reloadControllerInformation();
183 loadControllerParams();
188 auto callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
189 auto options = rclcpp::SubscriptionOptions();
190 options.callback_group = callback_group;
191 event_topic_subscriber_ = node_->create_subscription<std_msgs::msg::String>(
193 [
this](
const std_msgs::msg::String::ConstSharedPtr& event) {
return receiveEvent(event); },
options);
195 controller_mgr_node_->get_parameter(
"trajectory_execution.execution_duration_monitoring",
196 execution_duration_monitoring_);
197 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_execution_duration_scaling",
198 allowed_execution_duration_scaling_);
199 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_goal_duration_margin",
200 allowed_goal_duration_margin_);
201 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_start_tolerance", allowed_start_tolerance_);
203 if (manage_controllers_)
204 RCLCPP_INFO(LOGGER,
"Trajectory execution is managing controllers");
206 RCLCPP_INFO(LOGGER,
"Trajectory execution is not managing controllers");
208 auto controller_mgr_parameter_set_callback = [
this](
const std::vector<rclcpp::Parameter>& parameters) {
209 auto result = rcl_interfaces::msg::SetParametersResult();
210 result.successful =
true;
211 for (
const auto& parameter : parameters)
213 const std::string&
name = parameter.get_name();
214 if (
name ==
"trajectory_execution.execution_duration_monitoring")
216 else if (
name ==
"trajectory_execution.allowed_execution_duration_scaling")
218 else if (
name ==
"trajectory_execution.allowed_goal_duration_margin")
220 else if (
name ==
"trajectory_execution.execution_velocity_scaling")
222 else if (
name ==
"trajectory_execution.allowed_start_tolerance")
224 else if (
name ==
"trajectory_execution.wait_for_trajectory_completion")
227 result.successful =
false;
231 callback_handler_ = controller_mgr_node_->add_on_set_parameters_callback(controller_mgr_parameter_set_callback);
236 execution_duration_monitoring_ = flag;
241 allowed_execution_duration_scaling_ = scaling;
246 allowed_goal_duration_margin_ = margin;
251 execution_velocity_scaling_ = scaling;
256 allowed_start_tolerance_ = tolerance;
261 wait_for_trajectory_completion_ = flag;
266 return manage_controllers_;
271 return controller_manager_;
279 RCLCPP_WARN_STREAM(LOGGER,
"Unknown event type: '" << event <<
"'");
282 void TrajectoryExecutionManager::receiveEvent(
const std_msgs::msg::String::ConstSharedPtr& event)
284 RCLCPP_INFO_STREAM(LOGGER,
"Received event '" << event->data <<
"'");
290 if (controller.empty())
291 return push(trajectory, std::vector<std::string>());
293 return push(trajectory, std::vector<std::string>(1, controller));
297 const std::string& controller)
299 if (controller.empty())
300 return push(trajectory, std::vector<std::string>());
302 return push(trajectory, std::vector<std::string>(1, controller));
306 const std::vector<std::string>& controllers)
308 moveit_msgs::msg::RobotTrajectory traj;
309 traj.joint_trajectory = trajectory;
310 return push(traj, controllers);
314 const std::vector<std::string>& controllers)
316 if (!execution_complete_)
318 RCLCPP_ERROR(LOGGER,
"Cannot push a new trajectory while another is being executed");
323 if (configure(*context, trajectory, controllers))
327 std::stringstream ss;
328 ss <<
"Pushed trajectory for execution using controllers [ ";
329 for (
const std::string& controller : context->
controllers_)
330 ss << controller <<
" ";
335 RCLCPP_INFO_STREAM(LOGGER, ss.str());
337 trajectories_.push_back(context);
350 const std::string& controller)
352 if (controller.empty())
355 return pushAndExecute(trajectory, std::vector<std::string>(1, controller));
359 const std::string& controller)
361 if (controller.empty())
364 return pushAndExecute(trajectory, std::vector<std::string>(1, controller));
369 if (controller.empty())
372 return pushAndExecute(state, std::vector<std::string>(1, controller));
376 const std::vector<std::string>& controllers)
378 moveit_msgs::msg::RobotTrajectory traj;
379 traj.joint_trajectory = trajectory;
384 const std::vector<std::string>& controllers)
386 moveit_msgs::msg::RobotTrajectory traj;
387 traj.joint_trajectory.header = state.header;
388 traj.joint_trajectory.joint_names = state.name;
389 traj.joint_trajectory.points.resize(1);
390 traj.joint_trajectory.points[0].positions = state.position;
391 traj.joint_trajectory.points[0].velocities = state.velocity;
392 traj.joint_trajectory.points[0].effort = state.effort;
393 traj.joint_trajectory.points[0].time_from_start = rclcpp::Duration(0, 0);
398 const std::vector<std::string>& controllers)
400 if (!execution_complete_)
402 RCLCPP_ERROR(LOGGER,
"Cannot push & execute a new trajectory while another is being executed");
407 if (configure(*context, trajectory, controllers))
410 std::scoped_lock slock(continuous_execution_mutex_);
411 continuous_execution_queue_.push_back(context);
412 if (!continuous_execution_thread_)
413 continuous_execution_thread_ = std::make_unique<std::thread>([
this] { continuousExecutionThread(); });
416 continuous_execution_condition_.notify_all();
427 void TrajectoryExecutionManager::continuousExecutionThread()
429 std::set<moveit_controller_manager::MoveItControllerHandlePtr> used_handles;
430 while (run_continuous_execution_thread_)
432 if (!stop_continuous_execution_)
434 std::unique_lock<std::mutex> ulock(continuous_execution_mutex_);
435 while (continuous_execution_queue_.empty() && run_continuous_execution_thread_ && !stop_continuous_execution_)
436 continuous_execution_condition_.wait(ulock);
439 if (stop_continuous_execution_ || !run_continuous_execution_thread_)
441 for (
const moveit_controller_manager::MoveItControllerHandlePtr& used_handle : used_handles)
443 used_handle->cancelExecution();
444 used_handles.clear();
445 while (!continuous_execution_queue_.empty())
447 TrajectoryExecutionContext* context = continuous_execution_queue_.front();
448 continuous_execution_queue_.pop_front();
451 stop_continuous_execution_ =
false;
455 while (!continuous_execution_queue_.empty())
457 TrajectoryExecutionContext* context =
nullptr;
459 std::scoped_lock slock(continuous_execution_mutex_);
460 if (continuous_execution_queue_.empty())
462 context = continuous_execution_queue_.front();
463 continuous_execution_queue_.pop_front();
464 if (continuous_execution_queue_.empty())
465 continuous_execution_condition_.notify_all();
469 std::set<moveit_controller_manager::MoveItControllerHandlePtr>::iterator uit = used_handles.begin();
470 while (uit != used_handles.end())
473 std::set<moveit_controller_manager::MoveItControllerHandlePtr>::iterator to_erase = uit;
475 used_handles.erase(to_erase);
486 std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles(context->controllers_.size());
487 for (std::size_t i = 0; i < context->controllers_.size(); ++i)
489 moveit_controller_manager::MoveItControllerHandlePtr h;
492 h = controller_manager_->getControllerHandle(context->controllers_[i]);
494 catch (std::exception& ex)
496 RCLCPP_ERROR(LOGGER,
"%s caught when retrieving controller handle", ex.what());
501 RCLCPP_ERROR(LOGGER,
"No controller handle for controller '%s'. Aborting.",
502 context->controllers_[i].c_str());
509 if (stop_continuous_execution_ || !run_continuous_execution_thread_)
516 if (!handles.empty())
517 for (std::size_t i = 0; i < context->trajectory_parts_.size(); ++i)
522 ok = handles[i]->sendTrajectory(context->trajectory_parts_[i]);
524 catch (std::exception& ex)
526 RCLCPP_ERROR(LOGGER,
"Caught %s when sending trajectory to controller", ex.what());
530 for (std::size_t j = 0; j < i; ++j)
533 handles[j]->cancelExecution();
535 catch (std::exception& ex)
537 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution", ex.what());
539 RCLCPP_ERROR(LOGGER,
"Failed to send trajectory part %zu of %zu to controller %s", i + 1,
540 context->trajectory_parts_.size(), handles[i]->getName().c_str());
542 RCLCPP_ERROR(LOGGER,
"Cancelling previously sent trajectory parts");
551 for (
const moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
552 used_handles.insert(handle);
556 RCLCPP_ERROR(LOGGER,
"Not all needed controllers are active. Cannot push and execute. You can try "
557 "calling ensureActiveControllers() before pushAndExecute()");
565 void TrajectoryExecutionManager::reloadControllerInformation()
567 known_controllers_.clear();
568 if (controller_manager_)
570 std::vector<std::string> names;
571 controller_manager_->getControllersList(names);
572 for (
const std::string&
name : names)
574 std::vector<std::string> joints;
575 controller_manager_->getControllerJoints(
name, joints);
576 ControllerInformation ci;
578 ci.joints_.insert(joints.begin(), joints.end());
579 known_controllers_[ci.name_] = ci;
583 controller_manager_->getActiveControllers(names);
584 for (
const auto& active_name : names)
586 auto found_it = std::find_if(known_controllers_.begin(), known_controllers_.end(),
587 [&](
const auto& known_controller) { return known_controller.first == active_name; });
588 if (found_it != known_controllers_.end())
590 found_it->second.state_.active_ =
true;
594 for (std::map<std::string, ControllerInformation>::iterator it = known_controllers_.begin();
595 it != known_controllers_.end(); ++it)
596 for (std::map<std::string, ControllerInformation>::iterator jt = known_controllers_.begin();
597 jt != known_controllers_.end(); ++jt)
600 std::vector<std::string> intersect;
601 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), jt->second.joints_.begin(),
602 jt->second.joints_.end(), std::back_inserter(intersect));
603 if (!intersect.empty())
605 it->second.overlapping_controllers_.insert(jt->first);
606 jt->second.overlapping_controllers_.insert(it->first);
612 RCLCPP_ERROR(LOGGER,
"Failed to reload controllers: `controller_manager_` does not exist.");
616 void TrajectoryExecutionManager::updateControllerState(
const std::string& controller,
const rclcpp::Duration& age)
618 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
619 if (it != known_controllers_.end())
620 updateControllerState(it->second, age);
622 RCLCPP_ERROR(LOGGER,
"Controller '%s' is not known.", controller.c_str());
625 void TrajectoryExecutionManager::updateControllerState(ControllerInformation& ci,
const rclcpp::Duration& age)
627 if (node_->now() - ci.last_update_ >= age)
629 if (controller_manager_)
632 RCLCPP_INFO(LOGGER,
"Updating information for controller '%s'.", ci.name_.c_str());
633 ci.state_ = controller_manager_->getControllerState(ci.name_);
634 ci.last_update_ = node_->now();
638 RCLCPP_INFO(LOGGER,
"Information for controller '%s' is assumed to be up to date.", ci.name_.c_str());
641 void TrajectoryExecutionManager::updateControllersState(
const rclcpp::Duration& age)
643 for (std::pair<const std::string, ControllerInformation>& known_controller : known_controllers_)
644 updateControllerState(known_controller.second, age);
647 bool TrajectoryExecutionManager::checkControllerCombination(std::vector<std::string>& selected,
648 const std::set<std::string>& actuated_joints)
650 std::set<std::string> combined_joints;
651 for (
const std::string& controller : selected)
653 const ControllerInformation& ci = known_controllers_[controller];
654 combined_joints.insert(ci.joints_.begin(), ci.joints_.end());
659 std::stringstream ss, saj, sac;
660 for (
const std::string& controller : selected)
661 ss << controller <<
" ";
662 for (
const std::string& actuated_joint : actuated_joints)
663 saj << actuated_joint <<
" ";
664 for (
const std::string& combined_joint : combined_joints)
665 sac << combined_joint <<
" ";
666 RCLCPP_INFO(LOGGER,
"Checking if controllers [ %s] operating on joints [ %s] cover joints [ %s]", ss.str().c_str(),
667 sac.str().c_str(), saj.str().c_str());
670 return std::includes(combined_joints.begin(), combined_joints.end(), actuated_joints.begin(), actuated_joints.end());
673 void TrajectoryExecutionManager::generateControllerCombination(std::size_t start_index, std::size_t controller_count,
674 const std::vector<std::string>& available_controllers,
675 std::vector<std::string>& selected_controllers,
677 const std::set<std::string>& actuated_joints)
679 if (selected_controllers.size() == controller_count)
681 if (checkControllerCombination(selected_controllers, actuated_joints))
686 for (std::size_t i = start_index; i < available_controllers.size(); ++i)
688 bool overlap =
false;
689 const ControllerInformation& ci = known_controllers_[available_controllers[i]];
690 for (std::size_t j = 0; j < selected_controllers.size() && !overlap; ++j)
692 if (ci.overlapping_controllers_.find(selected_controllers[j]) != ci.overlapping_controllers_.end())
697 selected_controllers.push_back(available_controllers[i]);
698 generateControllerCombination(i + 1, controller_count, available_controllers, selected_controllers,
700 selected_controllers.pop_back();
706 struct OrderPotentialControllerCombination
708 bool operator()(
const std::size_t
a,
const std::size_t b)
const
738 bool TrajectoryExecutionManager::findControllers(
const std::set<std::string>& actuated_joints,
739 std::size_t controller_count,
740 const std::vector<std::string>& available_controllers,
741 std::vector<std::string>& selected_controllers)
744 std::vector<std::string> work_area;
745 OrderPotentialControllerCombination order;
746 std::vector<std::vector<std::string>>&
selected_options = order.selected_options;
747 generateControllerCombination(0, controller_count, available_controllers, work_area,
selected_options,
752 std::stringstream saj;
753 std::stringstream sac;
754 for (
const std::string& available_controller : available_controllers)
755 sac << available_controller <<
" ";
756 for (
const std::string& actuated_joint : actuated_joints)
757 saj << actuated_joint <<
" ";
758 RCLCPP_INFO(
LOGGER,
"Looking for %zu controllers among [ %s] that cover joints [ %s]. Found %zd options.",
759 controller_count, sac.str().c_str(), saj.str().c_str(),
selected_options.size());
785 updateControllerState(
selected_options[i][k], DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
786 const ControllerInformation& ci = known_controllers_[
selected_options[i][k]];
788 if (ci.state_.default_)
789 order.nrdefault[i]++;
790 if (ci.state_.active_)
792 order.nrjoints[i] += ci.joints_.size();
802 std::sort(bijection.begin(), bijection.end(), order);
806 if (!manage_controllers_)
829 for (
const std::string& controller : controllers)
831 updateControllerState(controller, DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
832 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
833 if (it == known_controllers_.end() || !it->second.state_.active_)
839 bool TrajectoryExecutionManager::selectControllers(
const std::set<std::string>& actuated_joints,
840 const std::vector<std::string>& available_controllers,
841 std::vector<std::string>& selected_controllers)
843 for (std::size_t i = 1; i <= available_controllers.size(); ++i)
844 if (findControllers(actuated_joints, i, available_controllers, selected_controllers))
849 std::vector<std::string> other_option;
850 for (std::size_t j = i + 1; j <= available_controllers.size(); ++j)
851 if (findControllers(actuated_joints, j, available_controllers, other_option))
855 selected_controllers = other_option;
865 bool TrajectoryExecutionManager::distributeTrajectory(
const moveit_msgs::msg::RobotTrajectory& trajectory,
866 const std::vector<std::string>& controllers,
867 std::vector<moveit_msgs::msg::RobotTrajectory>& parts)
870 parts.resize(controllers.size());
872 std::set<std::string> actuated_joints_mdof;
873 actuated_joints_mdof.insert(trajectory.multi_dof_joint_trajectory.joint_names.begin(),
874 trajectory.multi_dof_joint_trajectory.joint_names.end());
875 std::set<std::string> actuated_joints_single;
876 for (
const std::string& joint_name : trajectory.joint_trajectory.joint_names)
883 actuated_joints_single.insert(jm->
getName());
887 for (std::size_t i = 0; i < controllers.size(); ++i)
889 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controllers[i]);
890 if (it == known_controllers_.end())
892 RCLCPP_ERROR_STREAM(LOGGER,
"Controller " << controllers[i] <<
" not found.");
895 std::vector<std::string> intersect_mdof;
896 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_mdof.begin(),
897 actuated_joints_mdof.end(), std::back_inserter(intersect_mdof));
898 std::vector<std::string> intersect_single;
899 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_single.begin(),
900 actuated_joints_single.end(), std::back_inserter(intersect_single));
901 if (intersect_mdof.empty() && intersect_single.empty())
902 RCLCPP_WARN_STREAM(LOGGER,
"No joints to be distributed for controller " << controllers[i]);
904 if (!intersect_mdof.empty())
906 std::vector<std::string>& jnames = parts[i].multi_dof_joint_trajectory.joint_names;
907 jnames.insert(jnames.end(), intersect_mdof.begin(), intersect_mdof.end());
908 std::map<std::string, std::size_t> index;
909 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
910 index[trajectory.multi_dof_joint_trajectory.joint_names[j]] = j;
911 std::vector<std::size_t> bijection(jnames.size());
912 for (std::size_t j = 0; j < jnames.size(); ++j)
913 bijection[j] = index[jnames[j]];
915 parts[i].multi_dof_joint_trajectory.header.frame_id = trajectory.multi_dof_joint_trajectory.header.frame_id;
916 parts[i].multi_dof_joint_trajectory.points.resize(trajectory.multi_dof_joint_trajectory.points.size());
917 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.points.size(); ++j)
919 parts[i].multi_dof_joint_trajectory.points[j].time_from_start =
920 trajectory.multi_dof_joint_trajectory.points[j].time_from_start;
921 parts[i].multi_dof_joint_trajectory.points[j].transforms.resize(bijection.size());
922 for (std::size_t k = 0; k < bijection.size(); ++k)
924 parts[i].multi_dof_joint_trajectory.points[j].transforms[k] =
925 trajectory.multi_dof_joint_trajectory.points[j].transforms[bijection[k]];
927 if (!trajectory.multi_dof_joint_trajectory.points[j].velocities.empty())
929 parts[i].multi_dof_joint_trajectory.points[j].velocities.resize(bijection.size());
931 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.x =
932 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.x * execution_velocity_scaling_;
934 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.y =
935 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.y * execution_velocity_scaling_;
937 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.z =
938 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.z * execution_velocity_scaling_;
940 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.x =
941 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.x * execution_velocity_scaling_;
943 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.y =
944 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.y * execution_velocity_scaling_;
946 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.z =
947 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.z * execution_velocity_scaling_;
952 if (!intersect_single.empty())
954 std::vector<std::string>& jnames = parts[i].joint_trajectory.joint_names;
955 jnames.insert(jnames.end(), intersect_single.begin(), intersect_single.end());
956 parts[i].joint_trajectory.header = trajectory.joint_trajectory.header;
957 std::map<std::string, std::size_t> index;
958 for (std::size_t j = 0; j < trajectory.joint_trajectory.joint_names.size(); ++j)
959 index[trajectory.joint_trajectory.joint_names[j]] = j;
960 std::vector<std::size_t> bijection(jnames.size());
961 for (std::size_t j = 0; j < jnames.size(); ++j)
962 bijection[j] = index[jnames[j]];
963 parts[i].joint_trajectory.points.resize(trajectory.joint_trajectory.points.size());
964 for (std::size_t j = 0; j < trajectory.joint_trajectory.points.size(); ++j)
966 parts[i].joint_trajectory.points[j].time_from_start = trajectory.joint_trajectory.points[j].time_from_start;
967 if (!trajectory.joint_trajectory.points[j].positions.empty())
969 parts[i].joint_trajectory.points[j].positions.resize(bijection.size());
970 for (std::size_t k = 0; k < bijection.size(); ++k)
971 parts[i].joint_trajectory.points[j].positions[k] =
972 trajectory.joint_trajectory.points[j].positions[bijection[k]];
974 if (!trajectory.joint_trajectory.points[j].velocities.empty())
976 parts[i].joint_trajectory.points[j].velocities.resize(bijection.size());
977 for (std::size_t k = 0; k < bijection.size(); ++k)
978 parts[i].joint_trajectory.points[j].velocities[k] =
979 trajectory.joint_trajectory.points[j].velocities[bijection[k]] * execution_velocity_scaling_;
981 if (!trajectory.joint_trajectory.points[j].accelerations.empty())
983 parts[i].joint_trajectory.points[j].accelerations.resize(bijection.size());
984 for (std::size_t k = 0; k < bijection.size(); ++k)
985 parts[i].joint_trajectory.points[j].accelerations[k] =
986 trajectory.joint_trajectory.points[j].accelerations[bijection[k]];
988 if (!trajectory.joint_trajectory.points[j].effort.empty())
990 parts[i].joint_trajectory.points[j].effort.resize(bijection.size());
991 for (std::size_t k = 0; k < bijection.size(); ++k)
992 parts[i].joint_trajectory.points[j].effort[k] =
993 trajectory.joint_trajectory.points[j].effort[bijection[k]];
1002 bool TrajectoryExecutionManager::validate(
const TrajectoryExecutionContext& context)
const
1004 if (allowed_start_tolerance_ == 0)
1007 RCLCPP_INFO(LOGGER,
"Validating trajectory with allowed_start_tolerance %g", allowed_start_tolerance_);
1009 moveit::core::RobotStatePtr current_state;
1010 if (!csm_->waitForCurrentState(node_->now()) || !(current_state = csm_->getCurrentState()))
1012 RCLCPP_WARN(LOGGER,
"Failed to validate trajectory: couldn't receive full current joint state within 1s");
1016 for (
const auto& trajectory : context.trajectory_parts_)
1018 if (!trajectory.joint_trajectory.points.empty())
1021 const std::vector<double>& positions = trajectory.joint_trajectory.points.front().positions;
1022 const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1023 if (positions.size() != joint_names.size())
1025 RCLCPP_ERROR(LOGGER,
"Wrong trajectory: #joints: %zu != #positions: %zu", joint_names.size(), positions.size());
1029 for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
1034 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown joint in trajectory: " << joint_names[i]);
1038 double cur_position = current_state->getJointPositions(jm)[0];
1039 double traj_position = positions[i];
1043 if (jm->
distance(&cur_position, &traj_position) > allowed_start_tolerance_)
1045 RCLCPP_ERROR(LOGGER,
1046 "\nInvalid Trajectory: start point deviates from current robot state more than %g"
1047 "\njoint '%s': expected: %g, current: %g",
1048 allowed_start_tolerance_, joint_names[i].c_str(), traj_position, cur_position);
1053 if (!trajectory.multi_dof_joint_trajectory.points.empty())
1056 const std::vector<geometry_msgs::msg::Transform>& transforms =
1057 trajectory.multi_dof_joint_trajectory.points.front().transforms;
1058 const std::vector<std::string>& joint_names = trajectory.multi_dof_joint_trajectory.joint_names;
1059 if (transforms.size() != joint_names.size())
1061 RCLCPP_ERROR(LOGGER,
"Wrong trajectory: #joints: %zu != #transforms: %zu", joint_names.size(),
1066 for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
1071 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown joint in trajectory: " << joint_names[i]);
1077 Eigen::Isometry3d cur_transform, start_transform;
1080 start_transform = tf2::transformToEigen(transforms[i]);
1081 ASSERT_ISOMETRY(start_transform)
1082 Eigen::Vector3d offset = cur_transform.translation() - start_transform.translation();
1083 Eigen::AngleAxisd rotation;
1084 rotation.fromRotationMatrix(cur_transform.linear().transpose() * start_transform.linear());
1085 if ((offset.array() > allowed_start_tolerance_).any() || rotation.angle() > allowed_start_tolerance_)
1087 RCLCPP_ERROR_STREAM(LOGGER,
"\nInvalid Trajectory: start point deviates from current robot state more than "
1088 << allowed_start_tolerance_ <<
"\nmulti-dof joint '" << joint_names[i]
1089 <<
"': pos delta: " << offset.transpose()
1090 <<
" rot delta: " << rotation.angle());
1099 bool TrajectoryExecutionManager::configure(TrajectoryExecutionContext& context,
1100 const moveit_msgs::msg::RobotTrajectory& trajectory,
1101 const std::vector<std::string>& controllers)
1103 if (trajectory.multi_dof_joint_trajectory.points.empty() && trajectory.joint_trajectory.points.empty())
1109 reloadControllerInformation();
1110 std::set<std::string> actuated_joints;
1112 auto is_actuated = [
this](
const std::string& joint_name) ->
bool {
1116 for (
const std::string& joint_name : trajectory.multi_dof_joint_trajectory.joint_names)
1117 if (is_actuated(joint_name))
1118 actuated_joints.insert(joint_name);
1119 for (
const std::string& joint_name : trajectory.joint_trajectory.joint_names)
1120 if (is_actuated(joint_name))
1121 actuated_joints.insert(joint_name);
1123 if (actuated_joints.empty())
1125 RCLCPP_WARN(LOGGER,
"The trajectory to execute specifies no joints");
1129 if (controllers.empty())
1132 bool reloaded =
false;
1136 std::vector<std::string> all_controller_names;
1137 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1138 it != known_controllers_.end(); ++it)
1139 all_controller_names.push_back(it->first);
1140 if (selectControllers(actuated_joints, all_controller_names, context.controllers_))
1142 if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
1150 reloadControllerInformation();
1161 bool reloaded =
false;
1162 for (
const std::string& controller : controllers)
1163 if (known_controllers_.find(controller) == known_controllers_.end())
1165 reloadControllerInformation();
1170 for (
const std::string& controller : controllers)
1171 if (known_controllers_.find(controller) == known_controllers_.end())
1173 RCLCPP_ERROR(LOGGER,
"Controller '%s' is not known", controller.c_str());
1176 if (selectControllers(actuated_joints, controllers, context.controllers_))
1178 if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
1182 std::stringstream ss;
1183 for (
const std::string& actuated_joint : actuated_joints)
1184 ss << actuated_joint <<
" ";
1185 RCLCPP_ERROR(LOGGER,
"Unable to identify any set of controllers that can actuate the specified joints: [ %s]",
1188 std::stringstream ss2;
1189 std::map<std::string, ControllerInformation>::const_iterator mi;
1190 for (mi = known_controllers_.begin(); mi != known_controllers_.end(); ++mi)
1192 ss2 <<
"controller '" << mi->second.name_ <<
"' controls joints:\n";
1194 std::set<std::string>::const_iterator ji;
1195 for (ji = mi->second.joints_.begin(); ji != mi->second.joints_.end(); ++ji)
1197 ss2 <<
" " << *ji <<
'\n';
1200 RCLCPP_ERROR(LOGGER,
"Known controllers and their joints:\n%s", ss2.str().c_str());
1210 void TrajectoryExecutionManager::stopExecutionInternal()
1213 for (moveit_controller_manager::MoveItControllerHandlePtr& active_handle : active_handles_)
1216 active_handle->cancelExecution();
1218 catch (std::exception& ex)
1220 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution.", ex.what());
1226 stop_continuous_execution_ =
true;
1227 continuous_execution_condition_.notify_all();
1229 if (!execution_complete_)
1231 execution_state_mutex_.lock();
1232 if (!execution_complete_)
1238 execution_complete_ =
true;
1239 stopExecutionInternal();
1243 execution_state_mutex_.unlock();
1244 RCLCPP_INFO(LOGGER,
"Stopped trajectory execution.");
1247 std::scoped_lock lock(execution_thread_mutex_);
1248 if (execution_thread_)
1250 execution_thread_->join();
1251 execution_thread_.reset();
1258 execution_state_mutex_.unlock();
1260 else if (execution_thread_)
1263 std::scoped_lock lock(execution_thread_mutex_);
1264 if (execution_thread_)
1266 execution_thread_->join();
1267 execution_thread_.reset();
1283 if (!trajectories_.empty() && !validate(*trajectories_.front()))
1289 callback(last_execution_status_);
1294 execution_complete_ =
false;
1295 execution_thread_ = std::make_unique<std::thread>(&TrajectoryExecutionManager::executeThread,
this, callback,
1296 part_callback, auto_clear);
1302 std::unique_lock<std::mutex> ulock(execution_state_mutex_);
1303 while (!execution_complete_)
1304 execution_complete_condition_.wait(ulock);
1307 std::unique_lock<std::mutex> ulock(continuous_execution_mutex_);
1308 while (!continuous_execution_queue_.empty())
1309 continuous_execution_condition_.wait(ulock);
1315 return last_execution_status_;
1318 void TrajectoryExecutionManager::clear()
1320 if (execution_complete_)
1322 std::scoped_lock slock(execution_state_mutex_);
1323 for (TrajectoryExecutionContext* trajectory : trajectories_)
1325 trajectories_.clear();
1327 std::scoped_lock slock(continuous_execution_mutex_);
1328 while (!continuous_execution_queue_.empty())
1330 delete continuous_execution_queue_.front();
1331 continuous_execution_queue_.pop_front();
1336 RCLCPP_FATAL(LOGGER,
"Expecting execution_complete_ to be true!");
1339 void TrajectoryExecutionManager::executeThread(
const ExecutionCompleteCallback& callback,
1340 const PathSegmentCompleteCallback& part_callback,
bool auto_clear)
1343 if (execution_complete_)
1347 callback(last_execution_status_);
1351 RCLCPP_INFO(LOGGER,
"Starting trajectory execution ...");
1358 for (; i < trajectories_.size(); ++i)
1360 bool epart = executePart(i);
1361 if (epart && part_callback)
1363 if (!epart || execution_complete_)
1373 std::scoped_lock slock(execution_state_mutex_);
1374 if (!execution_complete_)
1376 waitForRobotToStop(*trajectories_[i - 1]);
1380 RCLCPP_INFO(LOGGER,
"Completed trajectory execution with status %s ...", last_execution_status_.
asString().c_str());
1383 execution_state_mutex_.lock();
1384 execution_complete_ =
true;
1385 execution_state_mutex_.unlock();
1386 execution_complete_condition_.notify_all();
1394 callback(last_execution_status_);
1397 bool TrajectoryExecutionManager::executePart(std::size_t part_index)
1399 TrajectoryExecutionContext& context = *trajectories_[part_index];
1405 if (execution_complete_)
1408 std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles;
1410 std::scoped_lock slock(execution_state_mutex_);
1411 if (!execution_complete_)
1414 time_index_mutex_.lock();
1415 current_context_ = part_index;
1416 time_index_mutex_.unlock();
1417 active_handles_.resize(context.controllers_.size());
1418 for (std::size_t i = 0; i < context.controllers_.size(); ++i)
1420 moveit_controller_manager::MoveItControllerHandlePtr h;
1423 h = controller_manager_->getControllerHandle(context.controllers_[i]);
1425 catch (std::exception& ex)
1427 RCLCPP_ERROR(LOGGER,
"Caught %s when retrieving controller handle", ex.what());
1431 active_handles_.clear();
1432 current_context_ = -1;
1434 RCLCPP_ERROR(LOGGER,
"No controller handle for controller '%s'. Aborting.", context.controllers_[i].c_str());
1437 active_handles_[i] = h;
1439 handles = active_handles_;
1440 for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1445 ok = active_handles_[i]->sendTrajectory(context.trajectory_parts_[i]);
1447 catch (std::exception& ex)
1449 RCLCPP_ERROR(LOGGER,
"Caught %s when sending trajectory to controller", ex.what());
1453 for (std::size_t j = 0; j < i; ++j)
1456 active_handles_[j]->cancelExecution();
1458 catch (std::exception& ex)
1460 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution", ex.what());
1462 RCLCPP_ERROR(LOGGER,
"Failed to send trajectory part %zu of %zu to controller %s", i + 1,
1463 context.trajectory_parts_.size(), active_handles_[i]->getName().c_str());
1465 RCLCPP_ERROR(LOGGER,
"Cancelling previously sent trajectory parts");
1466 active_handles_.clear();
1467 current_context_ = -1;
1476 rclcpp::Time current_time = node_->now();
1477 auto expected_trajectory_duration = rclcpp::Duration::from_seconds(0);
1478 int longest_part = -1;
1479 for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1481 auto d = rclcpp::Duration::from_seconds(0);
1482 if (!(context.trajectory_parts_[i].joint_trajectory.points.empty() &&
1483 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty()))
1485 if (rclcpp::Time(context.trajectory_parts_[i].joint_trajectory.header.stamp) > current_time)
1486 d = rclcpp::Time(context.trajectory_parts_[i].joint_trajectory.header.stamp) - current_time;
1487 if (rclcpp::Time(context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp) > current_time)
1488 d = std::max(
d, rclcpp::Time(context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp) -
1491 std::max(context.trajectory_parts_[i].joint_trajectory.points.empty() ?
1492 rclcpp::Duration::from_seconds(0) :
1493 rclcpp::Duration(context.trajectory_parts_[i].joint_trajectory.points.back().time_from_start),
1494 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty() ?
1495 rclcpp::Duration::from_seconds(0) :
1497 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.back().time_from_start));
1499 if (longest_part < 0 ||
1500 std::max(context.trajectory_parts_[i].joint_trajectory.points.size(),
1501 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.size()) >
1502 std::max(context.trajectory_parts_[longest_part].joint_trajectory.points.size(),
1503 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size()))
1510 std::map<std::string, double>::const_iterator scaling_it =
1511 controller_allowed_execution_duration_scaling_.find(context.controllers_[i]);
1512 const double current_scaling = scaling_it != controller_allowed_execution_duration_scaling_.end() ?
1513 scaling_it->second :
1514 allowed_execution_duration_scaling_;
1516 std::map<std::string, double>::const_iterator margin_it =
1517 controller_allowed_goal_duration_margin_.find(context.controllers_[i]);
1518 const double current_margin = margin_it != controller_allowed_goal_duration_margin_.end() ?
1520 allowed_goal_duration_margin_;
1523 expected_trajectory_duration =
1524 std::max(
d * current_scaling + rclcpp::Duration::from_seconds(current_margin), expected_trajectory_duration);
1528 if (longest_part >= 0)
1530 std::scoped_lock slock(time_index_mutex_);
1532 if (context.trajectory_parts_[longest_part].joint_trajectory.points.size() >=
1533 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size())
1535 auto d = rclcpp::Duration::from_seconds(0);
1536 if (rclcpp::Time(context.trajectory_parts_[longest_part].joint_trajectory.header.stamp) > current_time)
1537 d = rclcpp::Time(context.trajectory_parts_[longest_part].joint_trajectory.header.stamp) - current_time;
1538 for (trajectory_msgs::msg::JointTrajectoryPoint& point :
1539 context.trajectory_parts_[longest_part].joint_trajectory.points)
1540 time_index_.push_back(current_time +
d + rclcpp::Duration(point.time_from_start));
1544 auto d = rclcpp::Duration::from_seconds(0);
1545 if (rclcpp::Time(context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp) > current_time)
1546 d = rclcpp::Time(context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp) -
1548 for (trajectory_msgs::msg::MultiDOFJointTrajectoryPoint& point :
1549 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points)
1550 time_index_.push_back(current_time +
d + rclcpp::Duration(point.time_from_start));
1555 for (moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
1557 if (execution_duration_monitoring_)
1559 if (!handle->waitForExecution(expected_trajectory_duration))
1560 if (!execution_complete_ && node_->now() - current_time > expected_trajectory_duration)
1562 RCLCPP_ERROR(LOGGER,
1563 "Controller is taking too long to execute trajectory (the expected upper "
1564 "bound for the trajectory execution was %lf seconds). Stopping trajectory.",
1565 expected_trajectory_duration.seconds());
1567 std::scoped_lock slock(execution_state_mutex_);
1568 stopExecutionInternal();
1577 handle->waitForExecution();
1580 if (execution_complete_)
1587 RCLCPP_WARN_STREAM(LOGGER,
"Controller handle " << handle->getName() <<
" reports status "
1588 << handle->getLastExecutionStatus().asString());
1589 last_execution_status_ = handle->getLastExecutionStatus();
1595 execution_state_mutex_.lock();
1596 active_handles_.clear();
1599 time_index_mutex_.lock();
1600 time_index_.clear();
1601 current_context_ = -1;
1602 time_index_mutex_.unlock();
1604 execution_state_mutex_.unlock();
1609 RCLCPP_ERROR(LOGGER,
"Active status of required controllers can not be assured.");
1615 bool TrajectoryExecutionManager::waitForRobotToStop(
const TrajectoryExecutionContext& context,
double wait_time)
1618 if (allowed_start_tolerance_ == 0 || !wait_for_trajectory_completion_)
1620 RCLCPP_INFO(LOGGER,
"Not waiting for trajectory completion");
1624 auto start = std::chrono::system_clock::now();
1625 double time_remaining = wait_time;
1627 moveit::core::RobotStatePtr prev_state, cur_state;
1628 prev_state = csm_->getCurrentState();
1629 prev_state->enforceBounds();
1632 unsigned int no_motion_count = 0;
1633 while (time_remaining > 0. && no_motion_count < 3)
1635 if (!csm_->waitForCurrentState(node_->now(), time_remaining) || !(cur_state = csm_->getCurrentState()))
1637 RCLCPP_WARN(LOGGER,
"Failed to receive current joint state");
1640 cur_state->enforceBounds();
1641 std::chrono::duration<double> elapsed_seconds = std::chrono::system_clock::now() - start;
1642 time_remaining = wait_time - elapsed_seconds.count();
1646 for (
const auto& trajectory : context.trajectory_parts_)
1648 const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1649 const std::size_t n = joint_names.size();
1651 for (std::size_t i = 0; i < n && !moved; ++i)
1657 if (fabs(cur_state->getJointPositions(jm)[0] - prev_state->getJointPositions(jm)[0]) > allowed_start_tolerance_)
1660 no_motion_count = 0;
1669 std::swap(prev_state, cur_state);
1672 return time_remaining > 0;
1677 std::scoped_lock slock(time_index_mutex_);
1678 if (current_context_ < 0)
1679 return std::make_pair(-1, -1);
1680 if (time_index_.empty())
1681 return std::make_pair(
static_cast<int>(current_context_), -1);
1682 std::vector<rclcpp::Time>::const_iterator time_index_it =
1683 std::lower_bound(time_index_.begin(), time_index_.end(), node_->now());
1684 int pos = time_index_it - time_index_.begin();
1685 return std::make_pair(
static_cast<int>(current_context_), pos);
1688 const std::vector<TrajectoryExecutionManager::TrajectoryExecutionContext*>&
1691 return trajectories_;
1696 return last_execution_status_;
1702 if (joint_model_group)
1710 std::vector<std::string> all_controller_names;
1711 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1712 it != known_controllers_.end(); ++it)
1713 all_controller_names.push_back(it->first);
1714 std::vector<std::string> selected_controllers;
1715 std::set<std::string> jset;
1716 for (
const std::string& joint : joints)
1727 if (selectControllers(jset, all_controller_names, selected_controllers))
1740 reloadControllerInformation();
1742 updateControllersState(DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
1744 if (manage_controllers_)
1746 std::vector<std::string> controllers_to_activate;
1747 std::vector<std::string> controllers_to_deactivate;
1748 std::set<std::string> joints_to_be_activated;
1749 std::set<std::string> joints_to_be_deactivated;
1750 for (
const std::string& controller : controllers)
1752 std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.find(controller);
1753 if (it == known_controllers_.end())
1755 std::stringstream stream;
1756 for (
const auto& controller : known_controllers_)
1758 stream <<
" `" << controller.first <<
"`";
1760 RCLCPP_WARN_STREAM(LOGGER,
"Controller " << controller <<
" is not known. Known controllers: " << stream.str());
1763 if (!it->second.state_.active_)
1765 RCLCPP_DEBUG_STREAM(LOGGER,
"Need to activate " << controller);
1766 controllers_to_activate.push_back(controller);
1767 joints_to_be_activated.insert(it->second.joints_.begin(), it->second.joints_.end());
1768 for (
const std::string& overlapping_controller : it->second.overlapping_controllers_)
1770 const ControllerInformation& ci = known_controllers_[overlapping_controller];
1771 if (ci.state_.active_)
1773 controllers_to_deactivate.push_back(overlapping_controller);
1774 joints_to_be_deactivated.insert(ci.joints_.begin(), ci.joints_.end());
1779 RCLCPP_DEBUG_STREAM(LOGGER,
"Controller " << controller <<
" is already active");
1781 std::set<std::string> diff;
1782 std::set_difference(joints_to_be_deactivated.begin(), joints_to_be_deactivated.end(),
1783 joints_to_be_activated.begin(), joints_to_be_activated.end(), std::inserter(diff, diff.end()));
1787 std::vector<std::string> possible_additional_controllers;
1788 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1789 it != known_controllers_.end(); ++it)
1792 for (
const std::string& controller_to_activate : controllers_to_activate)
1793 if (it->second.overlapping_controllers_.find(controller_to_activate) !=
1794 it->second.overlapping_controllers_.end())
1800 possible_additional_controllers.push_back(it->first);
1804 std::vector<std::string> additional_controllers;
1805 if (selectControllers(diff, possible_additional_controllers, additional_controllers))
1806 controllers_to_activate.insert(controllers_to_activate.end(), additional_controllers.begin(),
1807 additional_controllers.end());
1811 if (!controllers_to_activate.empty() || !controllers_to_deactivate.empty())
1813 if (controller_manager_)
1816 for (
const std::string& controller_to_activate : controllers_to_activate)
1818 ControllerInformation& ci = known_controllers_[controller_to_activate];
1819 ci.last_update_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
1822 for (
const std::string& controller_to_activate : controllers_to_deactivate)
1823 known_controllers_[controller_to_activate].last_update_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
1824 return controller_manager_->switchControllers(controllers_to_activate, controllers_to_deactivate);
1834 std::set<std::string> originally_active;
1835 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1836 it != known_controllers_.end(); ++it)
1838 if (it->second.state_.active_)
1840 originally_active.insert(it->first);
1843 return std::includes(originally_active.begin(), originally_active.end(), controllers.begin(), controllers.end());
1847 void TrajectoryExecutionManager::loadControllerParams()
1849 for (
const auto& controller : known_controllers_)
1851 const std::string& controller_name = controller.first;
1852 for (
const auto& controller_manager_name : controller_manager_loader_->getDeclaredClasses())
1854 const std::string parameter_prefix =
1855 controller_manager_loader_->getClassPackage(controller_manager_name) +
"." + controller_name;
1857 double allowed_execution_duration_scaling;
1858 if (node_->get_parameter(parameter_prefix +
".allowed_execution_duration_scaling",
1859 allowed_execution_duration_scaling))
1860 controller_allowed_execution_duration_scaling_.insert({ controller_name, allowed_execution_duration_scaling });
1862 double allowed_goal_duration_margin;
1863 if (node_->get_parameter(parameter_prefix +
".allowed_goal_duration_margin", allowed_goal_duration_margin))
1864 controller_allowed_goal_duration_margin_.insert({ controller_name, allowed_goal_duration_margin });
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.
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