clang-tidy: modernize-pass-by-value

This commit is contained in:
Peter Johnson
2020-12-28 10:12:52 -08:00
parent 29c7da5f1a
commit aee4603269
32 changed files with 158 additions and 107 deletions

View File

@@ -4,6 +4,8 @@
#include "frc2/command/MecanumControllerCommand.h"
#include <utility>
using namespace frc2;
using namespace units;
@@ -24,12 +26,12 @@ MecanumControllerCommand::MecanumControllerCommand(
units::volt_t)>
output,
std::initializer_list<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_desiredRotation(desiredRotation),
m_desiredRotation(std::move(desiredRotation)),
m_maxWheelVelocity(maxWheelVelocity),
m_frontLeftController(
std::make_unique<frc2::PIDController>(frontLeftController)),
@@ -39,8 +41,8 @@ MecanumControllerCommand::MecanumControllerCommand(
std::make_unique<frc2::PIDController>(frontRightController)),
m_rearRightController(
std::make_unique<frc2::PIDController>(rearRightController)),
m_currentWheelSpeeds(currentWheelSpeeds),
m_outputVolts(output),
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
m_outputVolts(std::move(output)),
m_usePID(true) {
AddRequirements(requirements);
}
@@ -61,8 +63,8 @@ MecanumControllerCommand::MecanumControllerCommand(
units::volt_t)>
output,
std::initializer_list<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
@@ -75,8 +77,8 @@ MecanumControllerCommand::MecanumControllerCommand(
std::make_unique<frc2::PIDController>(frontRightController)),
m_rearRightController(
std::make_unique<frc2::PIDController>(rearRightController)),
m_currentWheelSpeeds(currentWheelSpeeds),
m_outputVolts(output),
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
m_outputVolts(std::move(output)),
m_usePID(true) {
AddRequirements(requirements);
m_desiredRotation = [&] {
@@ -101,12 +103,12 @@ MecanumControllerCommand::MecanumControllerCommand(
units::volt_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_desiredRotation(desiredRotation),
m_desiredRotation(std::move(desiredRotation)),
m_maxWheelVelocity(maxWheelVelocity),
m_frontLeftController(
std::make_unique<frc2::PIDController>(frontLeftController)),
@@ -116,8 +118,8 @@ MecanumControllerCommand::MecanumControllerCommand(
std::make_unique<frc2::PIDController>(frontRightController)),
m_rearRightController(
std::make_unique<frc2::PIDController>(rearRightController)),
m_currentWheelSpeeds(currentWheelSpeeds),
m_outputVolts(output),
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
m_outputVolts(std::move(output)),
m_usePID(true) {
AddRequirements(requirements);
}
@@ -138,8 +140,8 @@ MecanumControllerCommand::MecanumControllerCommand(
units::volt_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
@@ -152,8 +154,8 @@ MecanumControllerCommand::MecanumControllerCommand(
std::make_unique<frc2::PIDController>(frontRightController)),
m_rearRightController(
std::make_unique<frc2::PIDController>(rearRightController)),
m_currentWheelSpeeds(currentWheelSpeeds),
m_outputVolts(output),
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
m_outputVolts(std::move(output)),
m_usePID(true) {
AddRequirements(requirements);
m_desiredRotation = [&] {
@@ -172,13 +174,13 @@ MecanumControllerCommand::MecanumControllerCommand(
units::meters_per_second_t, units::meters_per_second_t)>
output,
std::initializer_list<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_desiredRotation(desiredRotation),
m_desiredRotation(std::move(desiredRotation)),
m_maxWheelVelocity(maxWheelVelocity),
m_outputVel(output),
m_outputVel(std::move(output)),
m_usePID(false) {
AddRequirements(requirements);
}
@@ -193,12 +195,12 @@ MecanumControllerCommand::MecanumControllerCommand(
units::meters_per_second_t, units::meters_per_second_t)>
output,
std::initializer_list<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_maxWheelVelocity(maxWheelVelocity),
m_outputVel(output),
m_outputVel(std::move(output)),
m_usePID(false) {
AddRequirements(requirements);
m_desiredRotation = [&] {
@@ -217,13 +219,13 @@ MecanumControllerCommand::MecanumControllerCommand(
units::meters_per_second_t, units::meters_per_second_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_desiredRotation(desiredRotation),
m_desiredRotation(std::move(desiredRotation)),
m_maxWheelVelocity(maxWheelVelocity),
m_outputVel(output),
m_outputVel(std::move(output)),
m_usePID(false) {
AddRequirements(requirements);
}
@@ -238,12 +240,12 @@ MecanumControllerCommand::MecanumControllerCommand(
units::meters_per_second_t, units::meters_per_second_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_kinematics(kinematics),
m_controller(xController, yController, thetaController),
m_maxWheelVelocity(maxWheelVelocity),
m_outputVel(output),
m_outputVel(std::move(output)),
m_usePID(false) {
AddRequirements(requirements);
m_desiredRotation = [&] {

View File

@@ -4,6 +4,8 @@
#include "frc2/command/PIDCommand.h"
#include <utility>
using namespace frc2;
PIDCommand::PIDCommand(PIDController controller,
@@ -11,7 +13,7 @@ PIDCommand::PIDCommand(PIDController controller,
std::function<double()> setpointSource,
std::function<void(double)> useOutput,
std::initializer_list<Subsystem*> requirements)
: m_controller{controller},
: m_controller{std::move(controller)},
m_measurement{std::move(measurementSource)},
m_setpoint{std::move(setpointSource)},
m_useOutput{std::move(useOutput)} {
@@ -23,7 +25,7 @@ PIDCommand::PIDCommand(PIDController controller,
std::function<double()> setpointSource,
std::function<void(double)> useOutput,
wpi::ArrayRef<Subsystem*> requirements)
: m_controller{controller},
: m_controller{std::move(controller)},
m_measurement{std::move(measurementSource)},
m_setpoint{std::move(setpointSource)},
m_useOutput{std::move(useOutput)} {

View File

@@ -4,10 +4,12 @@
#include "frc2/command/PIDSubsystem.h"
#include <utility>
using namespace frc2;
PIDSubsystem::PIDSubsystem(PIDController controller, double initialPosition)
: m_controller{controller} {
: m_controller{std::move(controller)} {
SetSetpoint(initialPosition);
AddChild("PID Controller", &m_controller);
}

View File

@@ -4,6 +4,8 @@
#include "frc2/command/RamseteCommand.h"
#include <utility>
using namespace frc2;
using namespace units;
@@ -16,15 +18,15 @@ RamseteCommand::RamseteCommand(
frc2::PIDController leftController, frc2::PIDController rightController,
std::function<void(volt_t, volt_t)> output,
std::initializer_list<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_controller(controller),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_speeds(wheelSpeeds),
m_speeds(std::move(wheelSpeeds)),
m_leftController(std::make_unique<frc2::PIDController>(leftController)),
m_rightController(std::make_unique<frc2::PIDController>(rightController)),
m_outputVolts(output),
m_outputVolts(std::move(output)),
m_usePID(true) {
AddRequirements(requirements);
}
@@ -38,15 +40,15 @@ RamseteCommand::RamseteCommand(
frc2::PIDController leftController, frc2::PIDController rightController,
std::function<void(volt_t, volt_t)> output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_controller(controller),
m_feedforward(feedforward),
m_kinematics(kinematics),
m_speeds(wheelSpeeds),
m_speeds(std::move(wheelSpeeds)),
m_leftController(std::make_unique<frc2::PIDController>(leftController)),
m_rightController(std::make_unique<frc2::PIDController>(rightController)),
m_outputVolts(output),
m_outputVolts(std::move(output)),
m_usePID(true) {
AddRequirements(requirements);
}
@@ -58,11 +60,11 @@ RamseteCommand::RamseteCommand(
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
output,
std::initializer_list<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_controller(controller),
m_kinematics(kinematics),
m_outputVel(output),
m_outputVel(std::move(output)),
m_usePID(false) {
AddRequirements(requirements);
}
@@ -74,11 +76,11 @@ RamseteCommand::RamseteCommand(
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
output,
wpi::ArrayRef<Subsystem*> requirements)
: m_trajectory(trajectory),
m_pose(pose),
: m_trajectory(std::move(trajectory)),
m_pose(std::move(pose)),
m_controller(controller),
m_kinematics(kinematics),
m_outputVel(output),
m_outputVel(std::move(output)),
m_usePID(false) {
AddRequirements(requirements);
}