Skip to content

fixed on_set_chained_mode implementations to avoid cpplint warnings #1564

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
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
6 changes: 1 addition & 5 deletions diff_drive_controller/src/diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<hardware_interface::CommandInterface>
DiffDriveController::on_export_reference_interfaces()
Expand Down
6 changes: 1 addition & 5 deletions mecanum_drive_controller/src/mecanum_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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*/)
Expand Down
6 changes: 1 addition & 5 deletions pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -425,11 +425,7 @@ std::vector<hardware_interface::StateInterface> 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*/)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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*/)
Expand Down
Loading