Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove empty on_shutdown() callbacks #1477

Merged
merged 1 commit into from
Jan 9, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
6 changes: 0 additions & 6 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
5 changes: 0 additions & 5 deletions tricycle_controller/src/tricycle_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
Loading