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;
103 controller_manager_loader_ =
104 std::make_unique<pluginlib::ClassLoader<moveit_controller_manager::MoveItControllerManager>>(
105 "moveit_core",
"moveit_controller_manager::MoveItControllerManager");
107 catch (pluginlib::PluginlibException& ex)
109 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while creating controller manager plugin loader: " << ex.what());
113 if (controller_manager_loader_)
115 std::string controller;
117 if (!node_->get_parameter(
"moveit_controller_manager", controller))
119 const std::vector<std::string>& classes = controller_manager_loader_->getDeclaredClasses();
120 if (classes.size() == 1)
122 controller = classes[0];
124 "Parameter '~moveit_controller_manager' is not specified but only one "
125 "matching plugin was found: '%s'. Using that one.",
130 RCLCPP_FATAL(LOGGER,
"Parameter '~moveit_controller_manager' not specified. This is needed to "
131 "identify the plugin to use for interacting with controllers. No paths can "
137 if (controller ==
"moveit_ros_control_interface/MoveItControllerManager")
139 RCLCPP_WARN(LOGGER,
"moveit_ros_control_interface/MoveItControllerManager is deprecated. Replace with "
140 "`moveit_ros_control_interface/MoveItControllerManager.`");
142 if (controller ==
"moveit_ros_control_interface/MoveItMultiControllerManager")
144 RCLCPP_WARN(LOGGER,
"moveit_ros_control_interface/MoveItMultiControllerManager is deprecated. Replace with "
145 "`moveit_ros_control_interface/Ros2ControlMultiManager.`");
148 if (!controller.empty())
154 rclcpp::NodeOptions
opt;
155 opt.allow_undeclared_parameters(
true);
156 opt.automatically_declare_parameters_from_overrides(
true);
157 controller_mgr_node_.reset(
new rclcpp::Node(
"moveit_simple_controller_manager",
opt));
159 auto all_params = node_->get_node_parameters_interface()->get_parameter_overrides();
160 for (
const auto& param : all_params)
161 controller_mgr_node_->set_parameter(rclcpp::Parameter(param.first, param.second));
163 controller_manager_ = controller_manager_loader_->createUniqueInstance(controller);
164 controller_manager_->initialize(controller_mgr_node_);
165 private_executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
166 private_executor_->add_node(controller_mgr_node_);
169 private_executor_thread_ = std::thread([
this]() { private_executor_->spin(); });
171 catch (pluginlib::PluginlibException& ex)
173 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while loading controller manager '" << controller <<
"': " << ex.what());
178 reloadControllerInformation();
181 loadControllerParams();
186 auto callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
187 auto options = rclcpp::SubscriptionOptions();
188 options.callback_group = callback_group;
189 event_topic_subscriber_ = node_->create_subscription<std_msgs::msg::String>(
191 [
this](
const std_msgs::msg::String::ConstSharedPtr& event) {
return receiveEvent(event); },
options);
193 controller_mgr_node_->get_parameter(
"trajectory_execution.execution_duration_monitoring",
194 execution_duration_monitoring_);
195 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_execution_duration_scaling",
196 allowed_execution_duration_scaling_);
197 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_goal_duration_margin",
198 allowed_goal_duration_margin_);
199 controller_mgr_node_->get_parameter(
"trajectory_execution.allowed_start_tolerance", allowed_start_tolerance_);
201 if (manage_controllers_)
202 RCLCPP_INFO(LOGGER,
"Trajectory execution is managing controllers");
204 RCLCPP_INFO(LOGGER,
"Trajectory execution is not managing controllers");
206 auto controller_mgr_parameter_set_callback = [
this](
const std::vector<rclcpp::Parameter>& parameters) {
207 auto result = rcl_interfaces::msg::SetParametersResult();
208 result.successful =
true;
209 for (
const auto& parameter : parameters)
211 const std::string&
name = parameter.get_name();
212 if (
name ==
"trajectory_execution.execution_duration_monitoring")
214 else if (
name ==
"trajectory_execution.allowed_execution_duration_scaling")
216 else if (
name ==
"trajectory_execution.allowed_goal_duration_margin")
218 else if (
name ==
"trajectory_execution.execution_velocity_scaling")
220 else if (
name ==
"trajectory_execution.allowed_start_tolerance")
222 else if (
name ==
"trajectory_execution.wait_for_trajectory_completion")
225 result.successful =
false;
229 callback_handler_ = controller_mgr_node_->add_on_set_parameters_callback(controller_mgr_parameter_set_callback);
234 execution_duration_monitoring_ = flag;
239 allowed_execution_duration_scaling_ = scaling;
244 allowed_goal_duration_margin_ = margin;
249 execution_velocity_scaling_ = scaling;
254 allowed_start_tolerance_ = tolerance;
259 wait_for_trajectory_completion_ = flag;
264 return manage_controllers_;
269 return controller_manager_;
277 RCLCPP_WARN_STREAM(LOGGER,
"Unknown event type: '" << event <<
"'");
280 void TrajectoryExecutionManager::receiveEvent(
const std_msgs::msg::String::ConstSharedPtr& event)
282 RCLCPP_INFO_STREAM(LOGGER,
"Received event '" << event->data <<
"'");
288 if (controller.empty())
289 return push(trajectory, std::vector<std::string>());
291 return push(trajectory, std::vector<std::string>(1, controller));
295 const std::string& controller)
297 if (controller.empty())
298 return push(trajectory, std::vector<std::string>());
300 return push(trajectory, std::vector<std::string>(1, controller));
304 const std::vector<std::string>& controllers)
306 moveit_msgs::msg::RobotTrajectory traj;
307 traj.joint_trajectory = trajectory;
308 return push(traj, controllers);
312 const std::vector<std::string>& controllers)
314 if (!execution_complete_)
316 RCLCPP_ERROR(LOGGER,
"Cannot push a new trajectory while another is being executed");
321 if (configure(*context, trajectory, controllers))
325 std::stringstream ss;
326 ss <<
"Pushed trajectory for execution using controllers [ ";
327 for (
const std::string& controller : context->
controllers_)
328 ss << controller <<
" ";
333 RCLCPP_INFO_STREAM(LOGGER, ss.str());
335 trajectories_.push_back(context);
348 const std::string& controller)
350 if (controller.empty())
353 return pushAndExecute(trajectory, std::vector<std::string>(1, controller));
357 const std::string& controller)
359 if (controller.empty())
362 return pushAndExecute(trajectory, std::vector<std::string>(1, controller));
367 if (controller.empty())
370 return pushAndExecute(state, std::vector<std::string>(1, controller));
374 const std::vector<std::string>& controllers)
376 moveit_msgs::msg::RobotTrajectory traj;
377 traj.joint_trajectory = trajectory;
382 const std::vector<std::string>& controllers)
384 moveit_msgs::msg::RobotTrajectory traj;
385 traj.joint_trajectory.header = state.header;
386 traj.joint_trajectory.joint_names = state.name;
387 traj.joint_trajectory.points.resize(1);
388 traj.joint_trajectory.points[0].positions = state.position;
389 traj.joint_trajectory.points[0].velocities = state.velocity;
390 traj.joint_trajectory.points[0].effort = state.effort;
391 traj.joint_trajectory.points[0].time_from_start = rclcpp::Duration(0, 0);
396 const std::vector<std::string>& controllers)
398 if (!execution_complete_)
400 RCLCPP_ERROR(LOGGER,
"Cannot push & execute a new trajectory while another is being executed");
405 if (configure(*context, trajectory, controllers))
408 std::scoped_lock slock(continuous_execution_mutex_);
409 continuous_execution_queue_.push_back(context);
410 if (!continuous_execution_thread_)
411 continuous_execution_thread_ = std::make_unique<std::thread>([
this] { continuousExecutionThread(); });
414 continuous_execution_condition_.notify_all();
425 void TrajectoryExecutionManager::continuousExecutionThread()
427 std::set<moveit_controller_manager::MoveItControllerHandlePtr> used_handles;
428 while (run_continuous_execution_thread_)
430 if (!stop_continuous_execution_)
432 std::unique_lock<std::mutex> ulock(continuous_execution_mutex_);
433 while (continuous_execution_queue_.empty() && run_continuous_execution_thread_ && !stop_continuous_execution_)
434 continuous_execution_condition_.wait(ulock);
437 if (stop_continuous_execution_ || !run_continuous_execution_thread_)
439 for (
const moveit_controller_manager::MoveItControllerHandlePtr& used_handle : used_handles)
441 used_handle->cancelExecution();
442 used_handles.clear();
443 while (!continuous_execution_queue_.empty())
445 TrajectoryExecutionContext* context = continuous_execution_queue_.front();
446 continuous_execution_queue_.pop_front();
449 stop_continuous_execution_ =
false;
453 while (!continuous_execution_queue_.empty())
455 TrajectoryExecutionContext* context =
nullptr;
457 std::scoped_lock slock(continuous_execution_mutex_);
458 if (continuous_execution_queue_.empty())
460 context = continuous_execution_queue_.front();
461 continuous_execution_queue_.pop_front();
462 if (continuous_execution_queue_.empty())
463 continuous_execution_condition_.notify_all();
467 std::set<moveit_controller_manager::MoveItControllerHandlePtr>::iterator uit = used_handles.begin();
468 while (uit != used_handles.end())
471 std::set<moveit_controller_manager::MoveItControllerHandlePtr>::iterator to_erase = uit;
473 used_handles.erase(to_erase);
484 std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles(context->controllers_.size());
485 for (std::size_t i = 0; i < context->controllers_.size(); ++i)
487 moveit_controller_manager::MoveItControllerHandlePtr h;
490 h = controller_manager_->getControllerHandle(context->controllers_[i]);
492 catch (std::exception& ex)
494 RCLCPP_ERROR(LOGGER,
"%s caught when retrieving controller handle", ex.what());
499 RCLCPP_ERROR(LOGGER,
"No controller handle for controller '%s'. Aborting.",
500 context->controllers_[i].c_str());
507 if (stop_continuous_execution_ || !run_continuous_execution_thread_)
514 if (!handles.empty())
515 for (std::size_t i = 0; i < context->trajectory_parts_.size(); ++i)
520 ok = handles[i]->sendTrajectory(context->trajectory_parts_[i]);
522 catch (std::exception& ex)
524 RCLCPP_ERROR(LOGGER,
"Caught %s when sending trajectory to controller", ex.what());
528 for (std::size_t j = 0; j < i; ++j)
531 handles[j]->cancelExecution();
533 catch (std::exception& ex)
535 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution", ex.what());
537 RCLCPP_ERROR(LOGGER,
"Failed to send trajectory part %zu of %zu to controller %s", i + 1,
538 context->trajectory_parts_.size(), handles[i]->getName().c_str());
540 RCLCPP_ERROR(LOGGER,
"Cancelling previously sent trajectory parts");
549 for (
const moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
550 used_handles.insert(handle);
554 RCLCPP_ERROR(LOGGER,
"Not all needed controllers are active. Cannot push and execute. You can try "
555 "calling ensureActiveControllers() before pushAndExecute()");
563 void TrajectoryExecutionManager::reloadControllerInformation()
565 known_controllers_.clear();
566 if (controller_manager_)
568 std::vector<std::string> names;
569 controller_manager_->getControllersList(names);
570 for (
const std::string&
name : names)
572 std::vector<std::string> joints;
573 controller_manager_->getControllerJoints(
name, joints);
574 ControllerInformation ci;
576 ci.joints_.insert(joints.begin(), joints.end());
577 known_controllers_[ci.name_] = ci;
581 controller_manager_->getActiveControllers(names);
582 for (
const auto& active_name : names)
584 auto found_it = std::find_if(known_controllers_.begin(), known_controllers_.end(),
585 [&](
const auto& known_controller) { return known_controller.first == active_name; });
586 if (found_it != known_controllers_.end())
588 found_it->second.state_.active_ =
true;
592 for (std::map<std::string, ControllerInformation>::iterator it = known_controllers_.begin();
593 it != known_controllers_.end(); ++it)
594 for (std::map<std::string, ControllerInformation>::iterator jt = known_controllers_.begin();
595 jt != known_controllers_.end(); ++jt)
598 std::vector<std::string> intersect;
599 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), jt->second.joints_.begin(),
600 jt->second.joints_.end(), std::back_inserter(intersect));
601 if (!intersect.empty())
603 it->second.overlapping_controllers_.insert(jt->first);
604 jt->second.overlapping_controllers_.insert(it->first);
610 RCLCPP_ERROR(LOGGER,
"Failed to reload controllers: `controller_manager_` does not exist.");
614 void TrajectoryExecutionManager::updateControllerState(
const std::string& controller,
const rclcpp::Duration& age)
616 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
617 if (it != known_controllers_.end())
618 updateControllerState(it->second, age);
620 RCLCPP_ERROR(LOGGER,
"Controller '%s' is not known.", controller.c_str());
623 void TrajectoryExecutionManager::updateControllerState(ControllerInformation& ci,
const rclcpp::Duration& age)
625 if (node_->now() - ci.last_update_ >= age)
627 if (controller_manager_)
630 RCLCPP_INFO(LOGGER,
"Updating information for controller '%s'.", ci.name_.c_str());
631 ci.state_ = controller_manager_->getControllerState(ci.name_);
632 ci.last_update_ = node_->now();
636 RCLCPP_INFO(LOGGER,
"Information for controller '%s' is assumed to be up to date.", ci.name_.c_str());
639 void TrajectoryExecutionManager::updateControllersState(
const rclcpp::Duration& age)
641 for (std::pair<const std::string, ControllerInformation>& known_controller : known_controllers_)
642 updateControllerState(known_controller.second, age);
645 bool TrajectoryExecutionManager::checkControllerCombination(std::vector<std::string>& selected,
646 const std::set<std::string>& actuated_joints)
648 std::set<std::string> combined_joints;
649 for (
const std::string& controller : selected)
651 const ControllerInformation& ci = known_controllers_[controller];
652 combined_joints.insert(ci.joints_.begin(), ci.joints_.end());
657 std::stringstream ss, saj, sac;
658 for (
const std::string& controller : selected)
659 ss << controller <<
" ";
660 for (
const std::string& actuated_joint : actuated_joints)
661 saj << actuated_joint <<
" ";
662 for (
const std::string& combined_joint : combined_joints)
663 sac << combined_joint <<
" ";
664 RCLCPP_INFO(LOGGER,
"Checking if controllers [ %s] operating on joints [ %s] cover joints [ %s]", ss.str().c_str(),
665 sac.str().c_str(), saj.str().c_str());
668 return std::includes(combined_joints.begin(), combined_joints.end(), actuated_joints.begin(), actuated_joints.end());
671 void TrajectoryExecutionManager::generateControllerCombination(std::size_t start_index, std::size_t controller_count,
672 const std::vector<std::string>& available_controllers,
673 std::vector<std::string>& selected_controllers,
675 const std::set<std::string>& actuated_joints)
677 if (selected_controllers.size() == controller_count)
679 if (checkControllerCombination(selected_controllers, actuated_joints))
684 for (std::size_t i = start_index; i < available_controllers.size(); ++i)
686 bool overlap =
false;
687 const ControllerInformation& ci = known_controllers_[available_controllers[i]];
688 for (std::size_t j = 0; j < selected_controllers.size() && !overlap; ++j)
690 if (ci.overlapping_controllers_.find(selected_controllers[j]) != ci.overlapping_controllers_.end())
695 selected_controllers.push_back(available_controllers[i]);
696 generateControllerCombination(i + 1, controller_count, available_controllers, selected_controllers,
698 selected_controllers.pop_back();
704 struct OrderPotentialControllerCombination
706 bool operator()(
const std::size_t
a,
const std::size_t b)
const
736 bool TrajectoryExecutionManager::findControllers(
const std::set<std::string>& actuated_joints,
737 std::size_t controller_count,
738 const std::vector<std::string>& available_controllers,
739 std::vector<std::string>& selected_controllers)
742 std::vector<std::string> work_area;
743 OrderPotentialControllerCombination order;
744 std::vector<std::vector<std::string>>&
selected_options = order.selected_options;
745 generateControllerCombination(0, controller_count, available_controllers, work_area,
selected_options,
750 std::stringstream saj;
751 std::stringstream sac;
752 for (
const std::string& available_controller : available_controllers)
753 sac << available_controller <<
" ";
754 for (
const std::string& actuated_joint : actuated_joints)
755 saj << actuated_joint <<
" ";
756 RCLCPP_INFO(
LOGGER,
"Looking for %zu controllers among [ %s] that cover joints [ %s]. Found %zd options.",
757 controller_count, sac.str().c_str(), saj.str().c_str(),
selected_options.size());
783 updateControllerState(
selected_options[i][k], DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
784 const ControllerInformation& ci = known_controllers_[
selected_options[i][k]];
786 if (ci.state_.default_)
787 order.nrdefault[i]++;
788 if (ci.state_.active_)
790 order.nrjoints[i] += ci.joints_.size();
800 std::sort(bijection.begin(), bijection.end(), order);
804 if (!manage_controllers_)
827 for (
const std::string& controller : controllers)
829 updateControllerState(controller, DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
830 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controller);
831 if (it == known_controllers_.end() || !it->second.state_.active_)
837 bool TrajectoryExecutionManager::selectControllers(
const std::set<std::string>& actuated_joints,
838 const std::vector<std::string>& available_controllers,
839 std::vector<std::string>& selected_controllers)
841 for (std::size_t i = 1; i <= available_controllers.size(); ++i)
842 if (findControllers(actuated_joints, i, available_controllers, selected_controllers))
847 std::vector<std::string> other_option;
848 for (std::size_t j = i + 1; j <= available_controllers.size(); ++j)
849 if (findControllers(actuated_joints, j, available_controllers, other_option))
853 selected_controllers = other_option;
863 bool TrajectoryExecutionManager::distributeTrajectory(
const moveit_msgs::msg::RobotTrajectory& trajectory,
864 const std::vector<std::string>& controllers,
865 std::vector<moveit_msgs::msg::RobotTrajectory>& parts)
868 parts.resize(controllers.size());
870 std::set<std::string> actuated_joints_mdof;
871 actuated_joints_mdof.insert(trajectory.multi_dof_joint_trajectory.joint_names.begin(),
872 trajectory.multi_dof_joint_trajectory.joint_names.end());
873 std::set<std::string> actuated_joints_single;
874 for (
const std::string& joint_name : trajectory.joint_trajectory.joint_names)
881 actuated_joints_single.insert(jm->
getName());
885 for (std::size_t i = 0; i < controllers.size(); ++i)
887 std::map<std::string, ControllerInformation>::iterator it = known_controllers_.find(controllers[i]);
888 if (it == known_controllers_.end())
890 RCLCPP_ERROR_STREAM(LOGGER,
"Controller " << controllers[i] <<
" not found.");
893 std::vector<std::string> intersect_mdof;
894 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_mdof.begin(),
895 actuated_joints_mdof.end(), std::back_inserter(intersect_mdof));
896 std::vector<std::string> intersect_single;
897 std::set_intersection(it->second.joints_.begin(), it->second.joints_.end(), actuated_joints_single.begin(),
898 actuated_joints_single.end(), std::back_inserter(intersect_single));
899 if (intersect_mdof.empty() && intersect_single.empty())
900 RCLCPP_WARN_STREAM(LOGGER,
"No joints to be distributed for controller " << controllers[i]);
902 if (!intersect_mdof.empty())
904 std::vector<std::string>& jnames = parts[i].multi_dof_joint_trajectory.joint_names;
905 jnames.insert(jnames.end(), intersect_mdof.begin(), intersect_mdof.end());
906 std::map<std::string, std::size_t> index;
907 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
908 index[trajectory.multi_dof_joint_trajectory.joint_names[j]] = j;
909 std::vector<std::size_t> bijection(jnames.size());
910 for (std::size_t j = 0; j < jnames.size(); ++j)
911 bijection[j] = index[jnames[j]];
913 parts[i].multi_dof_joint_trajectory.header.frame_id = trajectory.multi_dof_joint_trajectory.header.frame_id;
914 parts[i].multi_dof_joint_trajectory.points.resize(trajectory.multi_dof_joint_trajectory.points.size());
915 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.points.size(); ++j)
917 parts[i].multi_dof_joint_trajectory.points[j].time_from_start =
918 trajectory.multi_dof_joint_trajectory.points[j].time_from_start;
919 parts[i].multi_dof_joint_trajectory.points[j].transforms.resize(bijection.size());
920 for (std::size_t k = 0; k < bijection.size(); ++k)
922 parts[i].multi_dof_joint_trajectory.points[j].transforms[k] =
923 trajectory.multi_dof_joint_trajectory.points[j].transforms[bijection[k]];
925 if (!trajectory.multi_dof_joint_trajectory.points[j].velocities.empty())
927 parts[i].multi_dof_joint_trajectory.points[j].velocities.resize(bijection.size());
929 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.x =
930 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.x * execution_velocity_scaling_;
932 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.y =
933 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.y * execution_velocity_scaling_;
935 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].linear.z =
936 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].linear.z * execution_velocity_scaling_;
938 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.x =
939 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.x * execution_velocity_scaling_;
941 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.y =
942 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.y * execution_velocity_scaling_;
944 parts[i].multi_dof_joint_trajectory.points[j].velocities[0].angular.z =
945 trajectory.multi_dof_joint_trajectory.points[j].velocities[0].angular.z * execution_velocity_scaling_;
950 if (!intersect_single.empty())
952 std::vector<std::string>& jnames = parts[i].joint_trajectory.joint_names;
953 jnames.insert(jnames.end(), intersect_single.begin(), intersect_single.end());
954 parts[i].joint_trajectory.header = trajectory.joint_trajectory.header;
955 std::map<std::string, std::size_t> index;
956 for (std::size_t j = 0; j < trajectory.joint_trajectory.joint_names.size(); ++j)
957 index[trajectory.joint_trajectory.joint_names[j]] = j;
958 std::vector<std::size_t> bijection(jnames.size());
959 for (std::size_t j = 0; j < jnames.size(); ++j)
960 bijection[j] = index[jnames[j]];
961 parts[i].joint_trajectory.points.resize(trajectory.joint_trajectory.points.size());
962 for (std::size_t j = 0; j < trajectory.joint_trajectory.points.size(); ++j)
964 parts[i].joint_trajectory.points[j].time_from_start = trajectory.joint_trajectory.points[j].time_from_start;
965 if (!trajectory.joint_trajectory.points[j].positions.empty())
967 parts[i].joint_trajectory.points[j].positions.resize(bijection.size());
968 for (std::size_t k = 0; k < bijection.size(); ++k)
969 parts[i].joint_trajectory.points[j].positions[k] =
970 trajectory.joint_trajectory.points[j].positions[bijection[k]];
972 if (!trajectory.joint_trajectory.points[j].velocities.empty())
974 parts[i].joint_trajectory.points[j].velocities.resize(bijection.size());
975 for (std::size_t k = 0; k < bijection.size(); ++k)
976 parts[i].joint_trajectory.points[j].velocities[k] =
977 trajectory.joint_trajectory.points[j].velocities[bijection[k]] * execution_velocity_scaling_;
979 if (!trajectory.joint_trajectory.points[j].accelerations.empty())
981 parts[i].joint_trajectory.points[j].accelerations.resize(bijection.size());
982 for (std::size_t k = 0; k < bijection.size(); ++k)
983 parts[i].joint_trajectory.points[j].accelerations[k] =
984 trajectory.joint_trajectory.points[j].accelerations[bijection[k]];
986 if (!trajectory.joint_trajectory.points[j].effort.empty())
988 parts[i].joint_trajectory.points[j].effort.resize(bijection.size());
989 for (std::size_t k = 0; k < bijection.size(); ++k)
990 parts[i].joint_trajectory.points[j].effort[k] =
991 trajectory.joint_trajectory.points[j].effort[bijection[k]];
1000 bool TrajectoryExecutionManager::validate(
const TrajectoryExecutionContext& context)
const
1002 if (allowed_start_tolerance_ == 0)
1005 RCLCPP_INFO(LOGGER,
"Validating trajectory with allowed_start_tolerance %g", allowed_start_tolerance_);
1007 moveit::core::RobotStatePtr current_state;
1008 if (!csm_->waitForCurrentState(node_->now()) || !(current_state = csm_->getCurrentState()))
1010 RCLCPP_WARN(LOGGER,
"Failed to validate trajectory: couldn't receive full current joint state within 1s");
1014 for (
const auto& trajectory : context.trajectory_parts_)
1016 if (!trajectory.joint_trajectory.points.empty())
1019 const std::vector<double>& positions = trajectory.joint_trajectory.points.front().positions;
1020 const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1021 if (positions.size() != joint_names.size())
1023 RCLCPP_ERROR(LOGGER,
"Wrong trajectory: #joints: %zu != #positions: %zu", joint_names.size(), positions.size());
1027 for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
1032 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown joint in trajectory: " << joint_names[i]);
1036 double cur_position = current_state->getJointPositions(jm)[0];
1037 double traj_position = positions[i];
1041 if (jm->
distance(&cur_position, &traj_position) > allowed_start_tolerance_)
1043 RCLCPP_ERROR(LOGGER,
1044 "\nInvalid Trajectory: start point deviates from current robot state more than %g"
1045 "\njoint '%s': expected: %g, current: %g",
1046 allowed_start_tolerance_, joint_names[i].c_str(), traj_position, cur_position);
1051 if (!trajectory.multi_dof_joint_trajectory.points.empty())
1054 const std::vector<geometry_msgs::msg::Transform>& transforms =
1055 trajectory.multi_dof_joint_trajectory.points.front().transforms;
1056 const std::vector<std::string>& joint_names = trajectory.multi_dof_joint_trajectory.joint_names;
1057 if (transforms.size() != joint_names.size())
1059 RCLCPP_ERROR(LOGGER,
"Wrong trajectory: #joints: %zu != #transforms: %zu", joint_names.size(),
1064 for (std::size_t i = 0, end = joint_names.size(); i < end; ++i)
1069 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown joint in trajectory: " << joint_names[i]);
1075 Eigen::Isometry3d cur_transform, start_transform;
1078 start_transform = tf2::transformToEigen(transforms[i]);
1079 ASSERT_ISOMETRY(start_transform)
1080 Eigen::Vector3d offset = cur_transform.translation() - start_transform.translation();
1081 Eigen::AngleAxisd rotation;
1082 rotation.fromRotationMatrix(cur_transform.linear().transpose() * start_transform.linear());
1083 if ((offset.array() > allowed_start_tolerance_).any() || rotation.angle() > allowed_start_tolerance_)
1085 RCLCPP_ERROR_STREAM(LOGGER,
"\nInvalid Trajectory: start point deviates from current robot state more than "
1086 << allowed_start_tolerance_ <<
"\nmulti-dof joint '" << joint_names[i]
1087 <<
"': pos delta: " << offset.transpose()
1088 <<
" rot delta: " << rotation.angle());
1097 bool TrajectoryExecutionManager::configure(TrajectoryExecutionContext& context,
1098 const moveit_msgs::msg::RobotTrajectory& trajectory,
1099 const std::vector<std::string>& controllers)
1101 if (trajectory.multi_dof_joint_trajectory.points.empty() && trajectory.joint_trajectory.points.empty())
1107 reloadControllerInformation();
1108 std::set<std::string> actuated_joints;
1110 auto is_actuated = [
this](
const std::string& joint_name) ->
bool {
1114 for (
const std::string& joint_name : trajectory.multi_dof_joint_trajectory.joint_names)
1115 if (is_actuated(joint_name))
1116 actuated_joints.insert(joint_name);
1117 for (
const std::string& joint_name : trajectory.joint_trajectory.joint_names)
1118 if (is_actuated(joint_name))
1119 actuated_joints.insert(joint_name);
1121 if (actuated_joints.empty())
1123 RCLCPP_WARN(LOGGER,
"The trajectory to execute specifies no joints");
1127 if (controllers.empty())
1130 bool reloaded =
false;
1134 std::vector<std::string> all_controller_names;
1135 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1136 it != known_controllers_.end(); ++it)
1137 all_controller_names.push_back(it->first);
1138 if (selectControllers(actuated_joints, all_controller_names, context.controllers_))
1140 if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
1148 reloadControllerInformation();
1159 bool reloaded =
false;
1160 for (
const std::string& controller : controllers)
1161 if (known_controllers_.find(controller) == known_controllers_.end())
1163 reloadControllerInformation();
1168 for (
const std::string& controller : controllers)
1169 if (known_controllers_.find(controller) == known_controllers_.end())
1171 RCLCPP_ERROR(LOGGER,
"Controller '%s' is not known", controller.c_str());
1174 if (selectControllers(actuated_joints, controllers, context.controllers_))
1176 if (distributeTrajectory(trajectory, context.controllers_, context.trajectory_parts_))
1180 std::stringstream ss;
1181 for (
const std::string& actuated_joint : actuated_joints)
1182 ss << actuated_joint <<
" ";
1183 RCLCPP_ERROR(LOGGER,
"Unable to identify any set of controllers that can actuate the specified joints: [ %s]",
1186 std::stringstream ss2;
1187 std::map<std::string, ControllerInformation>::const_iterator mi;
1188 for (mi = known_controllers_.begin(); mi != known_controllers_.end(); ++mi)
1190 ss2 <<
"controller '" << mi->second.name_ <<
"' controls joints:\n";
1192 std::set<std::string>::const_iterator ji;
1193 for (ji = mi->second.joints_.begin(); ji != mi->second.joints_.end(); ++ji)
1195 ss2 <<
" " << *ji <<
'\n';
1198 RCLCPP_ERROR(LOGGER,
"Known controllers and their joints:\n%s", ss2.str().c_str());
1208 void TrajectoryExecutionManager::stopExecutionInternal()
1211 for (moveit_controller_manager::MoveItControllerHandlePtr& active_handle : active_handles_)
1214 active_handle->cancelExecution();
1216 catch (std::exception& ex)
1218 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution.", ex.what());
1224 stop_continuous_execution_ =
true;
1225 continuous_execution_condition_.notify_all();
1227 if (!execution_complete_)
1229 execution_state_mutex_.lock();
1230 if (!execution_complete_)
1236 execution_complete_ =
true;
1237 stopExecutionInternal();
1241 execution_state_mutex_.unlock();
1242 RCLCPP_INFO(LOGGER,
"Stopped trajectory execution.");
1245 std::scoped_lock lock(execution_thread_mutex_);
1246 if (execution_thread_)
1248 execution_thread_->join();
1249 execution_thread_.reset();
1256 execution_state_mutex_.unlock();
1258 else if (execution_thread_)
1261 std::scoped_lock lock(execution_thread_mutex_);
1262 if (execution_thread_)
1264 execution_thread_->join();
1265 execution_thread_.reset();
1281 if (!trajectories_.empty() && !validate(*trajectories_.front()))
1287 callback(last_execution_status_);
1292 execution_complete_ =
false;
1293 execution_thread_ = std::make_unique<std::thread>(&TrajectoryExecutionManager::executeThread,
this, callback,
1294 part_callback, auto_clear);
1300 std::unique_lock<std::mutex> ulock(execution_state_mutex_);
1301 while (!execution_complete_)
1302 execution_complete_condition_.wait(ulock);
1305 std::unique_lock<std::mutex> ulock(continuous_execution_mutex_);
1306 while (!continuous_execution_queue_.empty())
1307 continuous_execution_condition_.wait(ulock);
1313 return last_execution_status_;
1316 void TrajectoryExecutionManager::clear()
1318 if (execution_complete_)
1320 std::scoped_lock slock(execution_state_mutex_);
1321 for (TrajectoryExecutionContext* trajectory : trajectories_)
1323 trajectories_.clear();
1325 std::scoped_lock slock(continuous_execution_mutex_);
1326 while (!continuous_execution_queue_.empty())
1328 delete continuous_execution_queue_.front();
1329 continuous_execution_queue_.pop_front();
1334 RCLCPP_FATAL(LOGGER,
"Expecting execution_complete_ to be true!");
1337 void TrajectoryExecutionManager::executeThread(
const ExecutionCompleteCallback& callback,
1338 const PathSegmentCompleteCallback& part_callback,
bool auto_clear)
1341 if (execution_complete_)
1345 callback(last_execution_status_);
1349 RCLCPP_INFO(LOGGER,
"Starting trajectory execution ...");
1356 for (; i < trajectories_.size(); ++i)
1358 bool epart = executePart(i);
1359 if (epart && part_callback)
1361 if (!epart || execution_complete_)
1371 std::scoped_lock slock(execution_state_mutex_);
1372 if (!execution_complete_)
1374 waitForRobotToStop(*trajectories_[i - 1]);
1378 RCLCPP_INFO(LOGGER,
"Completed trajectory execution with status %s ...", last_execution_status_.
asString().c_str());
1381 execution_state_mutex_.lock();
1382 execution_complete_ =
true;
1383 execution_state_mutex_.unlock();
1384 execution_complete_condition_.notify_all();
1392 callback(last_execution_status_);
1395 bool TrajectoryExecutionManager::executePart(std::size_t part_index)
1397 TrajectoryExecutionContext& context = *trajectories_[part_index];
1403 if (execution_complete_)
1406 std::vector<moveit_controller_manager::MoveItControllerHandlePtr> handles;
1408 std::scoped_lock slock(execution_state_mutex_);
1409 if (!execution_complete_)
1412 time_index_mutex_.lock();
1413 current_context_ = part_index;
1414 time_index_mutex_.unlock();
1415 active_handles_.resize(context.controllers_.size());
1416 for (std::size_t i = 0; i < context.controllers_.size(); ++i)
1418 moveit_controller_manager::MoveItControllerHandlePtr h;
1421 h = controller_manager_->getControllerHandle(context.controllers_[i]);
1423 catch (std::exception& ex)
1425 RCLCPP_ERROR(LOGGER,
"Caught %s when retrieving controller handle", ex.what());
1429 active_handles_.clear();
1430 current_context_ = -1;
1432 RCLCPP_ERROR(LOGGER,
"No controller handle for controller '%s'. Aborting.", context.controllers_[i].c_str());
1435 active_handles_[i] = h;
1437 handles = active_handles_;
1438 for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1443 ok = active_handles_[i]->sendTrajectory(context.trajectory_parts_[i]);
1445 catch (std::exception& ex)
1447 RCLCPP_ERROR(LOGGER,
"Caught %s when sending trajectory to controller", ex.what());
1451 for (std::size_t j = 0; j < i; ++j)
1454 active_handles_[j]->cancelExecution();
1456 catch (std::exception& ex)
1458 RCLCPP_ERROR(LOGGER,
"Caught %s when canceling execution", ex.what());
1460 RCLCPP_ERROR(LOGGER,
"Failed to send trajectory part %zu of %zu to controller %s", i + 1,
1461 context.trajectory_parts_.size(), active_handles_[i]->getName().c_str());
1463 RCLCPP_ERROR(LOGGER,
"Cancelling previously sent trajectory parts");
1464 active_handles_.clear();
1465 current_context_ = -1;
1474 rclcpp::Time current_time = node_->now();
1475 auto expected_trajectory_duration = rclcpp::Duration::from_seconds(0);
1476 int longest_part = -1;
1477 for (std::size_t i = 0; i < context.trajectory_parts_.size(); ++i)
1479 auto d = rclcpp::Duration::from_seconds(0);
1480 if (!(context.trajectory_parts_[i].joint_trajectory.points.empty() &&
1481 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty()))
1483 if (rclcpp::Time(context.trajectory_parts_[i].joint_trajectory.header.stamp) > current_time)
1484 d = rclcpp::Time(context.trajectory_parts_[i].joint_trajectory.header.stamp) - current_time;
1485 if (rclcpp::Time(context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp) > current_time)
1486 d = std::max(
d, rclcpp::Time(context.trajectory_parts_[i].multi_dof_joint_trajectory.header.stamp) -
1489 std::max(context.trajectory_parts_[i].joint_trajectory.points.empty() ?
1490 rclcpp::Duration::from_seconds(0) :
1491 rclcpp::Duration(context.trajectory_parts_[i].joint_trajectory.points.back().time_from_start),
1492 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.empty() ?
1493 rclcpp::Duration::from_seconds(0) :
1495 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.back().time_from_start));
1497 if (longest_part < 0 ||
1498 std::max(context.trajectory_parts_[i].joint_trajectory.points.size(),
1499 context.trajectory_parts_[i].multi_dof_joint_trajectory.points.size()) >
1500 std::max(context.trajectory_parts_[longest_part].joint_trajectory.points.size(),
1501 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size()))
1508 std::map<std::string, double>::const_iterator scaling_it =
1509 controller_allowed_execution_duration_scaling_.find(context.controllers_[i]);
1510 const double current_scaling = scaling_it != controller_allowed_execution_duration_scaling_.end() ?
1511 scaling_it->second :
1512 allowed_execution_duration_scaling_;
1514 std::map<std::string, double>::const_iterator margin_it =
1515 controller_allowed_goal_duration_margin_.find(context.controllers_[i]);
1516 const double current_margin = margin_it != controller_allowed_goal_duration_margin_.end() ?
1518 allowed_goal_duration_margin_;
1521 expected_trajectory_duration =
1522 std::max(
d * current_scaling + rclcpp::Duration::from_seconds(current_margin), expected_trajectory_duration);
1526 if (longest_part >= 0)
1528 std::scoped_lock slock(time_index_mutex_);
1530 if (context.trajectory_parts_[longest_part].joint_trajectory.points.size() >=
1531 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points.size())
1533 auto d = rclcpp::Duration::from_seconds(0);
1534 if (rclcpp::Time(context.trajectory_parts_[longest_part].joint_trajectory.header.stamp) > current_time)
1535 d = rclcpp::Time(context.trajectory_parts_[longest_part].joint_trajectory.header.stamp) - current_time;
1536 for (trajectory_msgs::msg::JointTrajectoryPoint& point :
1537 context.trajectory_parts_[longest_part].joint_trajectory.points)
1538 time_index_.push_back(current_time +
d + rclcpp::Duration(point.time_from_start));
1542 auto d = rclcpp::Duration::from_seconds(0);
1543 if (rclcpp::Time(context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp) > current_time)
1544 d = rclcpp::Time(context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.header.stamp) -
1546 for (trajectory_msgs::msg::MultiDOFJointTrajectoryPoint& point :
1547 context.trajectory_parts_[longest_part].multi_dof_joint_trajectory.points)
1548 time_index_.push_back(current_time +
d + rclcpp::Duration(point.time_from_start));
1553 for (moveit_controller_manager::MoveItControllerHandlePtr& handle : handles)
1555 if (execution_duration_monitoring_)
1557 if (!handle->waitForExecution(expected_trajectory_duration))
1558 if (!execution_complete_ && node_->now() - current_time > expected_trajectory_duration)
1560 RCLCPP_ERROR(LOGGER,
1561 "Controller is taking too long to execute trajectory (the expected upper "
1562 "bound for the trajectory execution was %lf seconds). Stopping trajectory.",
1563 expected_trajectory_duration.seconds());
1565 std::scoped_lock slock(execution_state_mutex_);
1566 stopExecutionInternal();
1575 handle->waitForExecution();
1578 if (execution_complete_)
1585 RCLCPP_WARN_STREAM(LOGGER,
"Controller handle " << handle->getName() <<
" reports status "
1586 << handle->getLastExecutionStatus().asString());
1587 last_execution_status_ = handle->getLastExecutionStatus();
1593 execution_state_mutex_.lock();
1594 active_handles_.clear();
1597 time_index_mutex_.lock();
1598 time_index_.clear();
1599 current_context_ = -1;
1600 time_index_mutex_.unlock();
1602 execution_state_mutex_.unlock();
1607 RCLCPP_ERROR(LOGGER,
"Active status of required controllers can not be assured.");
1613 bool TrajectoryExecutionManager::waitForRobotToStop(
const TrajectoryExecutionContext& context,
double wait_time)
1616 if (allowed_start_tolerance_ == 0 || !wait_for_trajectory_completion_)
1618 RCLCPP_INFO(LOGGER,
"Not waiting for trajectory completion");
1622 auto start = std::chrono::system_clock::now();
1623 double time_remaining = wait_time;
1625 moveit::core::RobotStatePtr prev_state, cur_state;
1626 prev_state = csm_->getCurrentState();
1627 prev_state->enforceBounds();
1630 unsigned int no_motion_count = 0;
1631 while (time_remaining > 0. && no_motion_count < 3)
1633 if (!csm_->waitForCurrentState(node_->now(), time_remaining) || !(cur_state = csm_->getCurrentState()))
1635 RCLCPP_WARN(LOGGER,
"Failed to receive current joint state");
1638 cur_state->enforceBounds();
1639 std::chrono::duration<double> elapsed_seconds = std::chrono::system_clock::now() - start;
1640 time_remaining = wait_time - elapsed_seconds.count();
1644 for (
const auto& trajectory : context.trajectory_parts_)
1646 const std::vector<std::string>& joint_names = trajectory.joint_trajectory.joint_names;
1647 const std::size_t n = joint_names.size();
1649 for (std::size_t i = 0; i < n && !moved; ++i)
1655 if (fabs(cur_state->getJointPositions(jm)[0] - prev_state->getJointPositions(jm)[0]) > allowed_start_tolerance_)
1658 no_motion_count = 0;
1667 std::swap(prev_state, cur_state);
1670 return time_remaining > 0;
1675 std::scoped_lock slock(time_index_mutex_);
1676 if (current_context_ < 0)
1677 return std::make_pair(-1, -1);
1678 if (time_index_.empty())
1679 return std::make_pair(
static_cast<int>(current_context_), -1);
1680 std::vector<rclcpp::Time>::const_iterator time_index_it =
1681 std::lower_bound(time_index_.begin(), time_index_.end(), node_->now());
1682 int pos = time_index_it - time_index_.begin();
1683 return std::make_pair(
static_cast<int>(current_context_), pos);
1686 const std::vector<TrajectoryExecutionManager::TrajectoryExecutionContext*>&
1689 return trajectories_;
1694 return last_execution_status_;
1700 if (joint_model_group)
1708 std::vector<std::string> all_controller_names;
1709 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1710 it != known_controllers_.end(); ++it)
1711 all_controller_names.push_back(it->first);
1712 std::vector<std::string> selected_controllers;
1713 std::set<std::string> jset;
1714 for (
const std::string& joint : joints)
1725 if (selectControllers(jset, all_controller_names, selected_controllers))
1738 reloadControllerInformation();
1740 updateControllersState(DEFAULT_CONTROLLER_INFORMATION_VALIDITY_AGE);
1742 if (manage_controllers_)
1744 std::vector<std::string> controllers_to_activate;
1745 std::vector<std::string> controllers_to_deactivate;
1746 std::set<std::string> joints_to_be_activated;
1747 std::set<std::string> joints_to_be_deactivated;
1748 for (
const std::string& controller : controllers)
1750 std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.find(controller);
1751 if (it == known_controllers_.end())
1753 std::stringstream stream;
1754 for (
const auto& controller : known_controllers_)
1756 stream <<
" `" << controller.first <<
"`";
1758 RCLCPP_WARN_STREAM(LOGGER,
"Controller " << controller <<
" is not known. Known controllers: " << stream.str());
1761 if (!it->second.state_.active_)
1763 RCLCPP_DEBUG_STREAM(LOGGER,
"Need to activate " << controller);
1764 controllers_to_activate.push_back(controller);
1765 joints_to_be_activated.insert(it->second.joints_.begin(), it->second.joints_.end());
1766 for (
const std::string& overlapping_controller : it->second.overlapping_controllers_)
1768 const ControllerInformation& ci = known_controllers_[overlapping_controller];
1769 if (ci.state_.active_)
1771 controllers_to_deactivate.push_back(overlapping_controller);
1772 joints_to_be_deactivated.insert(ci.joints_.begin(), ci.joints_.end());
1777 RCLCPP_DEBUG_STREAM(LOGGER,
"Controller " << controller <<
" is already active");
1779 std::set<std::string> diff;
1780 std::set_difference(joints_to_be_deactivated.begin(), joints_to_be_deactivated.end(),
1781 joints_to_be_activated.begin(), joints_to_be_activated.end(), std::inserter(diff, diff.end()));
1785 std::vector<std::string> possible_additional_controllers;
1786 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1787 it != known_controllers_.end(); ++it)
1790 for (
const std::string& controller_to_activate : controllers_to_activate)
1791 if (it->second.overlapping_controllers_.find(controller_to_activate) !=
1792 it->second.overlapping_controllers_.end())
1798 possible_additional_controllers.push_back(it->first);
1802 std::vector<std::string> additional_controllers;
1803 if (selectControllers(diff, possible_additional_controllers, additional_controllers))
1804 controllers_to_activate.insert(controllers_to_activate.end(), additional_controllers.begin(),
1805 additional_controllers.end());
1809 if (!controllers_to_activate.empty() || !controllers_to_deactivate.empty())
1811 if (controller_manager_)
1814 for (
const std::string& controller_to_activate : controllers_to_activate)
1816 ControllerInformation& ci = known_controllers_[controller_to_activate];
1817 ci.last_update_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
1820 for (
const std::string& controller_to_activate : controllers_to_deactivate)
1821 known_controllers_[controller_to_activate].last_update_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
1822 return controller_manager_->switchControllers(controllers_to_activate, controllers_to_deactivate);
1832 std::set<std::string> originally_active;
1833 for (std::map<std::string, ControllerInformation>::const_iterator it = known_controllers_.begin();
1834 it != known_controllers_.end(); ++it)
1836 if (it->second.state_.active_)
1838 originally_active.insert(it->first);
1841 return std::includes(originally_active.begin(), originally_active.end(), controllers.begin(), controllers.end());
1845 void TrajectoryExecutionManager::loadControllerParams()
1847 for (
const auto& controller : known_controllers_)
1849 const std::string& controller_name = controller.first;
1850 for (
const auto& controller_manager_name : controller_manager_loader_->getDeclaredClasses())
1852 const std::string parameter_prefix =
1853 controller_manager_loader_->getClassPackage(controller_manager_name) +
"." + controller_name;
1855 double allowed_execution_duration_scaling;
1856 if (node_->get_parameter(parameter_prefix +
".allowed_execution_duration_scaling",
1857 allowed_execution_duration_scaling))
1858 controller_allowed_execution_duration_scaling_.insert({ controller_name, allowed_execution_duration_scaling });
1860 double allowed_goal_duration_margin;
1861 if (node_->get_parameter(parameter_prefix +
".allowed_goal_duration_margin", allowed_goal_duration_margin))
1862 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