From 8961e002458a5a62e36e2bf272c7f29924cc09de Mon Sep 17 00:00:00 2001 From: Julia Jia Date: Wed, 8 Jan 2025 21:49:49 -0800 Subject: [PATCH] Remove empty on_shutdown() --- .../diff_drive_controller/diff_drive_controller.hpp | 3 --- diff_drive_controller/src/diff_drive_controller.cpp | 6 ------ .../joint_trajectory_controller.hpp | 3 --- .../src/joint_trajectory_controller.cpp | 8 -------- .../include/tricycle_controller/tricycle_controller.hpp | 2 -- tricycle_controller/src/tricycle_controller.cpp | 5 ----- 6 files changed, 27 deletions(-) diff --git a/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp b/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp index 36ba2d6874..0e5e555b8c 100644 --- a/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp +++ b/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp @@ -72,9 +72,6 @@ class DiffDriveController : public controller_interface::ControllerInterface controller_interface::CallbackReturn on_error( const rclcpp_lifecycle::State & previous_state) override; - controller_interface::CallbackReturn on_shutdown( - const rclcpp_lifecycle::State & previous_state) override; - protected: struct WheelHandle { diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index 6957864321..fd9069237c 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -578,12 +578,6 @@ bool DiffDriveController::reset() return true; } -controller_interface::CallbackReturn DiffDriveController::on_shutdown( - const rclcpp_lifecycle::State &) -{ - return controller_interface::CallbackReturn::SUCCESS; -} - void DiffDriveController::halt() { const auto halt_wheels = [](auto & wheel_handles) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index abefec9d79..dd91377ee1 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -84,9 +84,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa controller_interface::CallbackReturn on_error( const rclcpp_lifecycle::State & previous_state) override; - controller_interface::CallbackReturn on_shutdown( - const rclcpp_lifecycle::State & previous_state) override; - protected: // To reduce number of variables and to make the code shorter the interfaces are ordered in types // as the following constants diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index b1c97175cb..9eea619d25 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1077,14 +1077,6 @@ bool JointTrajectoryController::reset() return true; } -controller_interface::CallbackReturn JointTrajectoryController::on_shutdown( - const rclcpp_lifecycle::State &) -{ - // TODO(karsten1987): what to do? - - return CallbackReturn::SUCCESS; -} - void JointTrajectoryController::publish_state( const rclcpp::Time & time, const JointTrajectoryPoint & desired_state, const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error) diff --git a/tricycle_controller/include/tricycle_controller/tricycle_controller.hpp b/tricycle_controller/include/tricycle_controller/tricycle_controller.hpp index 86793fd435..cd6251e803 100644 --- a/tricycle_controller/include/tricycle_controller/tricycle_controller.hpp +++ b/tricycle_controller/include/tricycle_controller/tricycle_controller.hpp @@ -76,8 +76,6 @@ class TricycleController : public controller_interface::ControllerInterface CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override; - CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override; - protected: struct TractionHandle { diff --git a/tricycle_controller/src/tricycle_controller.cpp b/tricycle_controller/src/tricycle_controller.cpp index bc04451ad6..9630d88b44 100644 --- a/tricycle_controller/src/tricycle_controller.cpp +++ b/tricycle_controller/src/tricycle_controller.cpp @@ -440,11 +440,6 @@ bool TricycleController::reset() return true; } -CallbackReturn TricycleController::on_shutdown(const rclcpp_lifecycle::State &) -{ - return CallbackReturn::SUCCESS; -} - void TricycleController::halt() { traction_joint_[0].velocity_command.get().set_value(0.0);