diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 765f80fc73..5bc8da69c9 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -722,7 +722,7 @@ void JointTrajectoryController::query_state_service( { const auto logger = get_node()->get_logger(); // Preconditions - if (get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + if (get_lifecycle_id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { RCLCPP_ERROR(logger, "Can't sample trajectory. Controller is not active."); response->success = false; @@ -1360,7 +1360,7 @@ rclcpp_action::GoalResponse JointTrajectoryController::goal_received_callback( RCLCPP_INFO(get_node()->get_logger(), "Received new action goal"); // Precondition: Running controller - if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + if (get_lifecycle_id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { RCLCPP_ERROR( get_node()->get_logger(), "Can't accept new action goals. Controller is not running."); diff --git a/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp b/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp index 5b7da75390..f80b281061 100644 --- a/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp +++ b/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp @@ -427,9 +427,7 @@ class TrajectoryControllerTest : public ::testing::Test { if (traj_controller_) { - if ( - traj_controller_->get_lifecycle_state().id() == - lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + if (traj_controller_->get_lifecycle_id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { EXPECT_EQ( traj_controller_->get_node()->deactivate().id(), diff --git a/motion_primitives_controllers/src/motion_primitives_forward_controller.cpp b/motion_primitives_controllers/src/motion_primitives_forward_controller.cpp index db8a974ece..35bdfb511b 100644 --- a/motion_primitives_controllers/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_controllers/src/motion_primitives_forward_controller.cpp @@ -224,7 +224,7 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal RCLCPP_INFO(get_node()->get_logger(), "Received new action goal"); // Precondition: Running controller - if (get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + if (get_lifecycle_id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { RCLCPP_ERROR( get_node()->get_logger(), "Can't accept new trajectories. Controller is not running.");