File tree 4 files changed +4
-20
lines changed
diff_drive_controller/src
mecanum_drive_controller/src
steering_controllers_library/src 4 files changed +4
-20
lines changed Original file line number Diff line number Diff line change @@ -642,11 +642,7 @@ controller_interface::CallbackReturn DiffDriveController::configure_side(
642
642
return controller_interface::CallbackReturn::SUCCESS;
643
643
}
644
644
645
- bool DiffDriveController::on_set_chained_mode (bool chained_mode)
646
- {
647
- // Always accept switch to/from chained mode (without linting type-cast error)
648
- return true || chained_mode;
649
- }
645
+ bool DiffDriveController::on_set_chained_mode (bool /* chained_mode*/ ) { return true ; }
650
646
651
647
std::vector<hardware_interface::CommandInterface>
652
648
DiffDriveController::on_export_reference_interfaces ()
Original file line number Diff line number Diff line change @@ -298,11 +298,7 @@ MecanumDriveController::on_export_reference_interfaces()
298
298
return reference_interfaces;
299
299
}
300
300
301
- bool MecanumDriveController::on_set_chained_mode (bool chained_mode)
302
- {
303
- // Always accept switch to/from chained mode
304
- return true || chained_mode;
305
- }
301
+ bool MecanumDriveController::on_set_chained_mode (bool /* chained_mode*/ ) { return true ; }
306
302
307
303
controller_interface::CallbackReturn MecanumDriveController::on_activate (
308
304
const rclcpp_lifecycle::State & /* previous_state*/ )
Original file line number Diff line number Diff line change @@ -425,11 +425,7 @@ std::vector<hardware_interface::StateInterface> PidController::on_export_state_i
425
425
return state_interfaces;
426
426
}
427
427
428
- bool PidController::on_set_chained_mode (bool chained_mode)
429
- {
430
- // Always accept switch to/from chained mode
431
- return true || chained_mode;
432
- }
428
+ bool PidController::on_set_chained_mode (bool /* chained_mode*/ ) { return true ; }
433
429
434
430
controller_interface::CallbackReturn PidController::on_activate (
435
431
const rclcpp_lifecycle::State & /* previous_state*/ )
Original file line number Diff line number Diff line change @@ -513,11 +513,7 @@ SteeringControllersLibrary::on_export_reference_interfaces()
513
513
return reference_interfaces;
514
514
}
515
515
516
- bool SteeringControllersLibrary::on_set_chained_mode (bool chained_mode)
517
- {
518
- // Always accept switch to/from chained mode
519
- return true || chained_mode;
520
- }
516
+ bool SteeringControllersLibrary::on_set_chained_mode (bool /* chained_mode*/ ) { return true ; }
521
517
522
518
controller_interface::CallbackReturn SteeringControllersLibrary::on_activate (
523
519
const rclcpp_lifecycle::State & /* previous_state*/ )
You can’t perform that action at this time.
0 commit comments