Skip to content

Commit 91f22d3

Browse files
Juliajmamueluth
authored andcommitted
Remove empty on_shutdown() callbacks (ros-controls#1477)
1 parent 4e08ad2 commit 91f22d3

File tree

6 files changed

+0
-27
lines changed

6 files changed

+0
-27
lines changed

diff_drive_controller/include/diff_drive_controller/diff_drive_controller.hpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -72,9 +72,6 @@ class DiffDriveController : public controller_interface::ControllerInterface
7272
controller_interface::CallbackReturn on_error(
7373
const rclcpp_lifecycle::State & previous_state) override;
7474

75-
controller_interface::CallbackReturn on_shutdown(
76-
const rclcpp_lifecycle::State & previous_state) override;
77-
7875
protected:
7976
struct WheelHandle
8077
{

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -578,12 +578,6 @@ bool DiffDriveController::reset()
578578
return true;
579579
}
580580

581-
controller_interface::CallbackReturn DiffDriveController::on_shutdown(
582-
const rclcpp_lifecycle::State &)
583-
{
584-
return controller_interface::CallbackReturn::SUCCESS;
585-
}
586-
587581
void DiffDriveController::halt()
588582
{
589583
const auto halt_wheels = [](auto & wheel_handles)

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -84,9 +84,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
8484
controller_interface::CallbackReturn on_error(
8585
const rclcpp_lifecycle::State & previous_state) override;
8686

87-
controller_interface::CallbackReturn on_shutdown(
88-
const rclcpp_lifecycle::State & previous_state) override;
89-
9087
protected:
9188
// To reduce number of variables and to make the code shorter the interfaces are ordered in types
9289
// as the following constants

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1077,14 +1077,6 @@ bool JointTrajectoryController::reset()
10771077
return true;
10781078
}
10791079

1080-
controller_interface::CallbackReturn JointTrajectoryController::on_shutdown(
1081-
const rclcpp_lifecycle::State &)
1082-
{
1083-
// TODO(karsten1987): what to do?
1084-
1085-
return CallbackReturn::SUCCESS;
1086-
}
1087-
10881080
void JointTrajectoryController::publish_state(
10891081
const rclcpp::Time & time, const JointTrajectoryPoint & desired_state,
10901082
const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error)

tricycle_controller/include/tricycle_controller/tricycle_controller.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,8 +76,6 @@ class TricycleController : public controller_interface::ControllerInterface
7676

7777
CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override;
7878

79-
CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override;
80-
8179
protected:
8280
struct TractionHandle
8381
{

tricycle_controller/src/tricycle_controller.cpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -440,11 +440,6 @@ bool TricycleController::reset()
440440
return true;
441441
}
442442

443-
CallbackReturn TricycleController::on_shutdown(const rclcpp_lifecycle::State &)
444-
{
445-
return CallbackReturn::SUCCESS;
446-
}
447-
448443
void TricycleController::halt()
449444
{
450445
traction_joint_[0].velocity_command.get().set_value(0.0);

0 commit comments

Comments
 (0)