From ce12694c6c948509a470783fd3b770cfab60a26e Mon Sep 17 00:00:00 2001 From: Manuel Muth Date: Mon, 26 Aug 2024 14:51:49 +0200 Subject: [PATCH] rename get/set_state to get/set_lifecylce_state (#1250) --- diff_drive_controller/src/diff_drive_controller.cpp | 2 +- .../src/joint_trajectory_controller.cpp | 6 +++--- tricycle_controller/src/tricycle_controller.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index a64f210503..66da6d6738 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -101,7 +101,7 @@ controller_interface::return_type DiffDriveController::update( const rclcpp::Time & time, const rclcpp::Duration & period) { auto logger = get_node()->get_logger(); - if (get_state().id() == State::PRIMARY_STATE_INACTIVE) + if (get_lifecycle_state().id() == State::PRIMARY_STATE_INACTIVE) { if (!is_halted) { diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 9563568ad5..e4923604fd 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -137,7 +137,7 @@ JointTrajectoryController::state_interface_configuration() const controller_interface::return_type JointTrajectoryController::update( const rclcpp::Time & time, const rclcpp::Duration & period) { - 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; } @@ -593,7 +593,7 @@ void JointTrajectoryController::query_state_service( { const auto logger = get_node()->get_logger(); // Preconditions - if (get_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + if (get_lifecycle_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { RCLCPP_ERROR(logger, "Can't sample trajectory. Controller is not active."); response->success = false; @@ -1112,7 +1112,7 @@ rclcpp_action::GoalResponse JointTrajectoryController::goal_received_callback( RCLCPP_INFO(get_node()->get_logger(), "Received new action goal"); // Precondition: Running controller - if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + if (get_lifecycle_state().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/tricycle_controller/src/tricycle_controller.cpp b/tricycle_controller/src/tricycle_controller.cpp index 94ff63e659..ec7ca7bd5e 100644 --- a/tricycle_controller/src/tricycle_controller.cpp +++ b/tricycle_controller/src/tricycle_controller.cpp @@ -86,7 +86,7 @@ InterfaceConfiguration TricycleController::state_interface_configuration() const controller_interface::return_type TricycleController::update( const rclcpp::Time & time, const rclcpp::Duration & period) { - if (get_state().id() == State::PRIMARY_STATE_INACTIVE) + if (get_lifecycle_state().id() == State::PRIMARY_STATE_INACTIVE) { if (!is_halted) {