From 76402a543dadcaf55d422905af53be249f0b9724 Mon Sep 17 00:00:00 2001 From: Vincenzo Di Pentima Date: Thu, 29 Aug 2024 14:59:12 +0200 Subject: [PATCH] Updated get_state to get_lifecycle_state (#1087) --- 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 93ffa0a94..27303c1ea 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -83,7 +83,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const scaled_params_.speed_scaling_interface_name.c_str()); } - if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { + if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { return controller_interface::return_type::OK; }