Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
5 changes: 3 additions & 2 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -689,8 +689,9 @@ controller_interface::CallbackReturn DiffDriveController::configure_side(

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;
// Fix to adhere to CppLint standards
Copy link
Copy Markdown
Member

@bmagyar bmagyar Mar 2, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

A moor reference isn't really adhering to cppkint standards ;)

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You can achieve the same by commenting out the name of the argument. It tricks the parser and also the compiler. We already use that approach in the codebase, just look for "/*" in ros2_control

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, I don't think so. See #1491 and the linked cpplint issue.

(void)chained_mode
return true;
}

std::vector<hardware_interface::CommandInterface>
Expand Down
5 changes: 3 additions & 2 deletions mecanum_drive_controller/src/mecanum_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -293,8 +293,9 @@ MecanumDriveController::on_export_reference_interfaces()

bool MecanumDriveController::on_set_chained_mode(bool chained_mode)
{
// Always accept switch to/from chained mode
return true || chained_mode;
// Fix to adhere to CppLint standards
(void)chained_mode
return true;
}

controller_interface::CallbackReturn MecanumDriveController::on_activate(
Expand Down
5 changes: 3 additions & 2 deletions pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -425,8 +425,9 @@ std::vector<hardware_interface::StateInterface> PidController::on_export_state_i

bool PidController::on_set_chained_mode(bool chained_mode)
{
// Always accept switch to/from chained mode
return true || chained_mode;
// Fix to adhere to CppLint standards
(void)chained_mode
return true;
}

controller_interface::CallbackReturn PidController::on_activate(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -329,8 +329,9 @@ SteeringControllersLibrary::on_export_reference_interfaces()

bool SteeringControllersLibrary::on_set_chained_mode(bool chained_mode)
{
// Always accept switch to/from chained mode
return true || chained_mode;
// Fix to adhere to CppLint standards
(void)chained_mode
return true;
}

controller_interface::CallbackReturn SteeringControllersLibrary::on_activate(
Expand Down
Loading