From e356cda3f0943ea5a5b0354e450605c9f0e58c5f Mon Sep 17 00:00:00 2001 From: Jafar Abdi Date: Mon, 7 Feb 2022 21:26:50 +0300 Subject: [PATCH] Get parameter on initialize (rebased version of #893) (#996) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Get parameter `trajectory_execution.execution_duration_monitoring` in initialize(). Co-authored-by: Gaël Écorchard (cherry picked from commit 3b5efca2246be28f875662d2c8ac6f5306d166e3) --- .../src/trajectory_execution_manager.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp index 3900c90081..0e770354ef 100644 --- a/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp +++ b/moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp @@ -176,6 +176,8 @@ void TrajectoryExecutionManager::initialize() EXECUTION_EVENT_TOPIC, 100, std::bind(&TrajectoryExecutionManager::receiveEvent, this, std::placeholders::_1), options); + controller_mgr_node_->get_parameter("trajectory_execution.execution_duration_monitoring", + execution_duration_monitoring_); controller_mgr_node_->get_parameter("trajectory_execution.allowed_execution_duration_scaling", allowed_execution_duration_scaling_); controller_mgr_node_->get_parameter("trajectory_execution.allowed_goal_duration_margin",