Skip to content

Commit

Permalink
Merge branch 'humble' into mergify/bp/humble/pr-1479
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Jan 10, 2025
2 parents 7acf875 + bbb2ff5 commit cd96fe3
Show file tree
Hide file tree
Showing 6 changed files with 0 additions and 30 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -86,10 +86,6 @@ class DiffDriveController : public controller_interface::ControllerInterface
controller_interface::CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state) override;

DIFF_DRIVE_CONTROLLER_PUBLIC
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 @@ -542,12 +542,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 @@ -96,10 +96,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
controller_interface::CallbackReturn on_error(
const rclcpp_lifecycle::State & previous_state) override;

JOINT_TRAJECTORY_CONTROLLER_PUBLIC
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 @@ -1126,14 +1126,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 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 @@ -86,9 +86,6 @@ class TricycleController : public controller_interface::ControllerInterface
TRICYCLE_CONTROLLER_PUBLIC
CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override;

TRICYCLE_CONTROLLER_PUBLIC
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 @@ -531,11 +531,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

0 comments on commit cd96fe3

Please sign in to comment.