diff --git a/ur_controllers/src/scaled_joint_trajectory_controller.cpp b/ur_controllers/src/scaled_joint_trajectory_controller.cpp index 93ffa0a9..27303c1e 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; }