From ce2369bf21fc14123fa53f06dae4b286af60e5e2 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Mon, 18 Sep 2023 14:09:35 +0000 Subject: [PATCH] Updated to ros2_controllers JTC API --- 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 9a950019b..b32596682 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -249,7 +249,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const RCLCPP_INFO(get_node()->get_logger(), "Goal reached, success!"); } else if (default_tolerances_.goal_time_tolerance != 0.0) { // if we exceed goal_time_toleralance set it to aborted - const rclcpp::Time traj_start = traj_external_point_ptr_->get_trajectory_start_time(); + const rclcpp::Time traj_start = traj_external_point_ptr_->time_from_start(); const rclcpp::Time traj_end = traj_start + start_segment_itr->time_from_start; // TODO(anyone): This will break in speed scaling we have to discuss how to handle the goal