diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index a7c6ba100f..d209afb701 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -642,11 +642,7 @@ controller_interface::CallbackReturn DiffDriveController::configure_side( return controller_interface::CallbackReturn::SUCCESS; } -bool DiffDriveController::on_set_chained_mode(bool chained_mode) -{ - // Always accept switch to/from chained mode (without linting type-cast error) - return true || chained_mode; -} +bool DiffDriveController::on_set_chained_mode(bool /*chained_mode*/) { return true; } std::vector DiffDriveController::on_export_reference_interfaces() diff --git a/mecanum_drive_controller/src/mecanum_drive_controller.cpp b/mecanum_drive_controller/src/mecanum_drive_controller.cpp index 3ec118bf8c..0d0f1e49f8 100644 --- a/mecanum_drive_controller/src/mecanum_drive_controller.cpp +++ b/mecanum_drive_controller/src/mecanum_drive_controller.cpp @@ -298,11 +298,7 @@ MecanumDriveController::on_export_reference_interfaces() return reference_interfaces; } -bool MecanumDriveController::on_set_chained_mode(bool chained_mode) -{ - // Always accept switch to/from chained mode - return true || chained_mode; -} +bool MecanumDriveController::on_set_chained_mode(bool /*chained_mode*/) { return true; } controller_interface::CallbackReturn MecanumDriveController::on_activate( const rclcpp_lifecycle::State & /*previous_state*/) diff --git a/pid_controller/src/pid_controller.cpp b/pid_controller/src/pid_controller.cpp index e0ef70ffac..c267f11bb2 100644 --- a/pid_controller/src/pid_controller.cpp +++ b/pid_controller/src/pid_controller.cpp @@ -425,11 +425,7 @@ std::vector PidController::on_export_state_i return state_interfaces; } -bool PidController::on_set_chained_mode(bool chained_mode) -{ - // Always accept switch to/from chained mode - return true || chained_mode; -} +bool PidController::on_set_chained_mode(bool /*chained_mode*/) { return true; } controller_interface::CallbackReturn PidController::on_activate( const rclcpp_lifecycle::State & /*previous_state*/) diff --git a/steering_controllers_library/src/steering_controllers_library.cpp b/steering_controllers_library/src/steering_controllers_library.cpp index 3840e2803b..f34b3a78e0 100644 --- a/steering_controllers_library/src/steering_controllers_library.cpp +++ b/steering_controllers_library/src/steering_controllers_library.cpp @@ -513,11 +513,7 @@ SteeringControllersLibrary::on_export_reference_interfaces() return reference_interfaces; } -bool SteeringControllersLibrary::on_set_chained_mode(bool chained_mode) -{ - // Always accept switch to/from chained mode - return true || chained_mode; -} +bool SteeringControllersLibrary::on_set_chained_mode(bool /*chained_mode*/) { return true; } controller_interface::CallbackReturn SteeringControllersLibrary::on_activate( const rclcpp_lifecycle::State & /*previous_state*/)