Skip to content

Commit f182e41

Browse files
Simplify on_set_chained_mode avoiding cpplint warnings (backport #1564) (#1687)
Co-authored-by: Bhagyesh Agresar <[email protected]>
1 parent 5090d28 commit f182e41

File tree

3 files changed

+3
-15
lines changed

3 files changed

+3
-15
lines changed

mecanum_drive_controller/src/mecanum_drive_controller.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -321,11 +321,7 @@ MecanumDriveController::on_export_reference_interfaces()
321321
return reference_interfaces;
322322
}
323323

324-
bool MecanumDriveController::on_set_chained_mode(bool chained_mode)
325-
{
326-
// Always accept switch to/from chained mode
327-
return true || chained_mode;
328-
}
324+
bool MecanumDriveController::on_set_chained_mode(bool /*chained_mode*/) { return true; }
329325

330326
controller_interface::CallbackReturn MecanumDriveController::on_activate(
331327
const rclcpp_lifecycle::State & /*previous_state*/)

pid_controller/src/pid_controller.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -358,11 +358,7 @@ std::vector<hardware_interface::CommandInterface> PidController::on_export_refer
358358
return reference_interfaces;
359359
}
360360

361-
bool PidController::on_set_chained_mode(bool chained_mode)
362-
{
363-
// Always accept switch to/from chained mode
364-
return true || chained_mode;
365-
}
361+
bool PidController::on_set_chained_mode(bool /*chained_mode*/) { return true; }
366362

367363
controller_interface::CallbackReturn PidController::on_activate(
368364
const rclcpp_lifecycle::State & /*previous_state*/)

steering_controllers_library/src/steering_controllers_library.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -379,11 +379,7 @@ SteeringControllersLibrary::on_export_reference_interfaces()
379379
return reference_interfaces;
380380
}
381381

382-
bool SteeringControllersLibrary::on_set_chained_mode(bool chained_mode)
383-
{
384-
// Always accept switch to/from chained mode
385-
return true || chained_mode;
386-
}
382+
bool SteeringControllersLibrary::on_set_chained_mode(bool /*chained_mode*/) { return true; }
387383

388384
controller_interface::CallbackReturn SteeringControllersLibrary::on_activate(
389385
const rclcpp_lifecycle::State & /*previous_state*/)

0 commit comments

Comments
 (0)