From 3f08b2037cad00169b2ed03f86f56c9dd675a401 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Mon, 19 May 2025 14:01:50 +0200 Subject: [PATCH] Remove deprecated code from sjtc The open_loop parameter has been removed upstream, so we'll have to remove it from here, as well. --- ur_controllers/src/scaled_joint_trajectory_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ur_controllers/src/scaled_joint_trajectory_controller.cpp b/ur_controllers/src/scaled_joint_trajectory_controller.cpp index 4a6320fa1..b0b5de7e9 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -133,7 +133,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const // if sampling the first time, set the point before you sample if (!current_trajectory_->is_sampled_already()) { first_sample = true; - if (params_.interpolate_from_desired_state || params_.open_loop_control) { + if (params_.interpolate_from_desired_state) { if (std::abs(last_commanded_time_.seconds()) < std::numeric_limits::epsilon()) { last_commanded_time_ = time; }