Skip to content

Commit 4082309

Browse files
committed
clang-tidy: modernize-pass-by-value
1 parent 2155804 commit 4082309

File tree

5 files changed

+59
-50
lines changed

5 files changed

+59
-50
lines changed

cpp/frc2/command/MecanumControllerCommand.cpp

Lines changed: 34 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@
44

55
#include "frc2/command/MecanumControllerCommand.h"
66

7+
#include <utility>
8+
79
using namespace frc2;
810
using namespace units;
911

@@ -24,12 +26,12 @@ MecanumControllerCommand::MecanumControllerCommand(
2426
units::volt_t)>
2527
output,
2628
std::initializer_list<Subsystem*> requirements)
27-
: m_trajectory(trajectory),
28-
m_pose(pose),
29+
: m_trajectory(std::move(trajectory)),
30+
m_pose(std::move(pose)),
2931
m_feedforward(feedforward),
3032
m_kinematics(kinematics),
3133
m_controller(xController, yController, thetaController),
32-
m_desiredRotation(desiredRotation),
34+
m_desiredRotation(std::move(desiredRotation)),
3335
m_maxWheelVelocity(maxWheelVelocity),
3436
m_frontLeftController(
3537
std::make_unique<frc2::PIDController>(frontLeftController)),
@@ -39,8 +41,8 @@ MecanumControllerCommand::MecanumControllerCommand(
3941
std::make_unique<frc2::PIDController>(frontRightController)),
4042
m_rearRightController(
4143
std::make_unique<frc2::PIDController>(rearRightController)),
42-
m_currentWheelSpeeds(currentWheelSpeeds),
43-
m_outputVolts(output),
44+
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
45+
m_outputVolts(std::move(output)),
4446
m_usePID(true) {
4547
AddRequirements(requirements);
4648
}
@@ -61,8 +63,8 @@ MecanumControllerCommand::MecanumControllerCommand(
6163
units::volt_t)>
6264
output,
6365
std::initializer_list<Subsystem*> requirements)
64-
: m_trajectory(trajectory),
65-
m_pose(pose),
66+
: m_trajectory(std::move(trajectory)),
67+
m_pose(std::move(pose)),
6668
m_feedforward(feedforward),
6769
m_kinematics(kinematics),
6870
m_controller(xController, yController, thetaController),
@@ -75,8 +77,8 @@ MecanumControllerCommand::MecanumControllerCommand(
7577
std::make_unique<frc2::PIDController>(frontRightController)),
7678
m_rearRightController(
7779
std::make_unique<frc2::PIDController>(rearRightController)),
78-
m_currentWheelSpeeds(currentWheelSpeeds),
79-
m_outputVolts(output),
80+
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
81+
m_outputVolts(std::move(output)),
8082
m_usePID(true) {
8183
AddRequirements(requirements);
8284
m_desiredRotation = [&] {
@@ -101,12 +103,12 @@ MecanumControllerCommand::MecanumControllerCommand(
101103
units::volt_t)>
102104
output,
103105
wpi::ArrayRef<Subsystem*> requirements)
104-
: m_trajectory(trajectory),
105-
m_pose(pose),
106+
: m_trajectory(std::move(trajectory)),
107+
m_pose(std::move(pose)),
106108
m_feedforward(feedforward),
107109
m_kinematics(kinematics),
108110
m_controller(xController, yController, thetaController),
109-
m_desiredRotation(desiredRotation),
111+
m_desiredRotation(std::move(desiredRotation)),
110112
m_maxWheelVelocity(maxWheelVelocity),
111113
m_frontLeftController(
112114
std::make_unique<frc2::PIDController>(frontLeftController)),
@@ -116,8 +118,8 @@ MecanumControllerCommand::MecanumControllerCommand(
116118
std::make_unique<frc2::PIDController>(frontRightController)),
117119
m_rearRightController(
118120
std::make_unique<frc2::PIDController>(rearRightController)),
119-
m_currentWheelSpeeds(currentWheelSpeeds),
120-
m_outputVolts(output),
121+
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
122+
m_outputVolts(std::move(output)),
121123
m_usePID(true) {
122124
AddRequirements(requirements);
123125
}
@@ -138,8 +140,8 @@ MecanumControllerCommand::MecanumControllerCommand(
138140
units::volt_t)>
139141
output,
140142
wpi::ArrayRef<Subsystem*> requirements)
141-
: m_trajectory(trajectory),
142-
m_pose(pose),
143+
: m_trajectory(std::move(trajectory)),
144+
m_pose(std::move(pose)),
143145
m_feedforward(feedforward),
144146
m_kinematics(kinematics),
145147
m_controller(xController, yController, thetaController),
@@ -152,8 +154,8 @@ MecanumControllerCommand::MecanumControllerCommand(
152154
std::make_unique<frc2::PIDController>(frontRightController)),
153155
m_rearRightController(
154156
std::make_unique<frc2::PIDController>(rearRightController)),
155-
m_currentWheelSpeeds(currentWheelSpeeds),
156-
m_outputVolts(output),
157+
m_currentWheelSpeeds(std::move(currentWheelSpeeds)),
158+
m_outputVolts(std::move(output)),
157159
m_usePID(true) {
158160
AddRequirements(requirements);
159161
m_desiredRotation = [&] {
@@ -172,13 +174,13 @@ MecanumControllerCommand::MecanumControllerCommand(
172174
units::meters_per_second_t, units::meters_per_second_t)>
173175
output,
174176
std::initializer_list<Subsystem*> requirements)
175-
: m_trajectory(trajectory),
176-
m_pose(pose),
177+
: m_trajectory(std::move(trajectory)),
178+
m_pose(std::move(pose)),
177179
m_kinematics(kinematics),
178180
m_controller(xController, yController, thetaController),
179-
m_desiredRotation(desiredRotation),
181+
m_desiredRotation(std::move(desiredRotation)),
180182
m_maxWheelVelocity(maxWheelVelocity),
181-
m_outputVel(output),
183+
m_outputVel(std::move(output)),
182184
m_usePID(false) {
183185
AddRequirements(requirements);
184186
}
@@ -193,12 +195,12 @@ MecanumControllerCommand::MecanumControllerCommand(
193195
units::meters_per_second_t, units::meters_per_second_t)>
194196
output,
195197
std::initializer_list<Subsystem*> requirements)
196-
: m_trajectory(trajectory),
197-
m_pose(pose),
198+
: m_trajectory(std::move(trajectory)),
199+
m_pose(std::move(pose)),
198200
m_kinematics(kinematics),
199201
m_controller(xController, yController, thetaController),
200202
m_maxWheelVelocity(maxWheelVelocity),
201-
m_outputVel(output),
203+
m_outputVel(std::move(output)),
202204
m_usePID(false) {
203205
AddRequirements(requirements);
204206
m_desiredRotation = [&] {
@@ -217,13 +219,13 @@ MecanumControllerCommand::MecanumControllerCommand(
217219
units::meters_per_second_t, units::meters_per_second_t)>
218220
output,
219221
wpi::ArrayRef<Subsystem*> requirements)
220-
: m_trajectory(trajectory),
221-
m_pose(pose),
222+
: m_trajectory(std::move(trajectory)),
223+
m_pose(std::move(pose)),
222224
m_kinematics(kinematics),
223225
m_controller(xController, yController, thetaController),
224-
m_desiredRotation(desiredRotation),
226+
m_desiredRotation(std::move(desiredRotation)),
225227
m_maxWheelVelocity(maxWheelVelocity),
226-
m_outputVel(output),
228+
m_outputVel(std::move(output)),
227229
m_usePID(false) {
228230
AddRequirements(requirements);
229231
}
@@ -238,12 +240,12 @@ MecanumControllerCommand::MecanumControllerCommand(
238240
units::meters_per_second_t, units::meters_per_second_t)>
239241
output,
240242
wpi::ArrayRef<Subsystem*> requirements)
241-
: m_trajectory(trajectory),
242-
m_pose(pose),
243+
: m_trajectory(std::move(trajectory)),
244+
m_pose(std::move(pose)),
243245
m_kinematics(kinematics),
244246
m_controller(xController, yController, thetaController),
245247
m_maxWheelVelocity(maxWheelVelocity),
246-
m_outputVel(output),
248+
m_outputVel(std::move(output)),
247249
m_usePID(false) {
248250
AddRequirements(requirements);
249251
m_desiredRotation = [&] {

cpp/frc2/command/PIDCommand.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,14 +4,16 @@
44

55
#include "frc2/command/PIDCommand.h"
66

7+
#include <utility>
8+
79
using namespace frc2;
810

911
PIDCommand::PIDCommand(PIDController controller,
1012
std::function<double()> measurementSource,
1113
std::function<double()> setpointSource,
1214
std::function<void(double)> useOutput,
1315
std::initializer_list<Subsystem*> requirements)
14-
: m_controller{controller},
16+
: m_controller{std::move(controller)},
1517
m_measurement{std::move(measurementSource)},
1618
m_setpoint{std::move(setpointSource)},
1719
m_useOutput{std::move(useOutput)} {
@@ -23,7 +25,7 @@ PIDCommand::PIDCommand(PIDController controller,
2325
std::function<double()> setpointSource,
2426
std::function<void(double)> useOutput,
2527
wpi::ArrayRef<Subsystem*> requirements)
26-
: m_controller{controller},
28+
: m_controller{std::move(controller)},
2729
m_measurement{std::move(measurementSource)},
2830
m_setpoint{std::move(setpointSource)},
2931
m_useOutput{std::move(useOutput)} {

cpp/frc2/command/PIDSubsystem.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,12 @@
44

55
#include "frc2/command/PIDSubsystem.h"
66

7+
#include <utility>
8+
79
using namespace frc2;
810

911
PIDSubsystem::PIDSubsystem(PIDController controller, double initialPosition)
10-
: m_controller{controller} {
12+
: m_controller{std::move(controller)} {
1113
SetSetpoint(initialPosition);
1214
AddChild("PID Controller", &m_controller);
1315
}

cpp/frc2/command/RamseteCommand.cpp

Lines changed: 16 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@
44

55
#include "frc2/command/RamseteCommand.h"
66

7+
#include <utility>
8+
79
using namespace frc2;
810
using namespace units;
911

@@ -16,15 +18,15 @@ RamseteCommand::RamseteCommand(
1618
frc2::PIDController leftController, frc2::PIDController rightController,
1719
std::function<void(volt_t, volt_t)> output,
1820
std::initializer_list<Subsystem*> requirements)
19-
: m_trajectory(trajectory),
20-
m_pose(pose),
21+
: m_trajectory(std::move(trajectory)),
22+
m_pose(std::move(pose)),
2123
m_controller(controller),
2224
m_feedforward(feedforward),
2325
m_kinematics(kinematics),
24-
m_speeds(wheelSpeeds),
26+
m_speeds(std::move(wheelSpeeds)),
2527
m_leftController(std::make_unique<frc2::PIDController>(leftController)),
2628
m_rightController(std::make_unique<frc2::PIDController>(rightController)),
27-
m_outputVolts(output),
29+
m_outputVolts(std::move(output)),
2830
m_usePID(true) {
2931
AddRequirements(requirements);
3032
}
@@ -38,15 +40,15 @@ RamseteCommand::RamseteCommand(
3840
frc2::PIDController leftController, frc2::PIDController rightController,
3941
std::function<void(volt_t, volt_t)> output,
4042
wpi::ArrayRef<Subsystem*> requirements)
41-
: m_trajectory(trajectory),
42-
m_pose(pose),
43+
: m_trajectory(std::move(trajectory)),
44+
m_pose(std::move(pose)),
4345
m_controller(controller),
4446
m_feedforward(feedforward),
4547
m_kinematics(kinematics),
46-
m_speeds(wheelSpeeds),
48+
m_speeds(std::move(wheelSpeeds)),
4749
m_leftController(std::make_unique<frc2::PIDController>(leftController)),
4850
m_rightController(std::make_unique<frc2::PIDController>(rightController)),
49-
m_outputVolts(output),
51+
m_outputVolts(std::move(output)),
5052
m_usePID(true) {
5153
AddRequirements(requirements);
5254
}
@@ -58,11 +60,11 @@ RamseteCommand::RamseteCommand(
5860
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
5961
output,
6062
std::initializer_list<Subsystem*> requirements)
61-
: m_trajectory(trajectory),
62-
m_pose(pose),
63+
: m_trajectory(std::move(trajectory)),
64+
m_pose(std::move(pose)),
6365
m_controller(controller),
6466
m_kinematics(kinematics),
65-
m_outputVel(output),
67+
m_outputVel(std::move(output)),
6668
m_usePID(false) {
6769
AddRequirements(requirements);
6870
}
@@ -74,11 +76,11 @@ RamseteCommand::RamseteCommand(
7476
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
7577
output,
7678
wpi::ArrayRef<Subsystem*> requirements)
77-
: m_trajectory(trajectory),
78-
m_pose(pose),
79+
: m_trajectory(std::move(trajectory)),
80+
m_pose(std::move(pose)),
7981
m_controller(controller),
8082
m_kinematics(kinematics),
81-
m_outputVel(output),
83+
m_outputVel(std::move(output)),
8284
m_usePID(false) {
8385
AddRequirements(requirements);
8486
}

include/frc2/command/SelectCommand.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,8 @@ class SelectCommand : public CommandHelper<CommandBase, SelectCommand<Key>> {
9999
*
100100
* @param toRun a supplier providing the command to run
101101
*/
102-
explicit SelectCommand(std::function<Command*()> toRun) : m_toRun{toRun} {}
102+
explicit SelectCommand(std::function<Command*()> toRun)
103+
: m_toRun{std::move(toRun)} {}
103104

104105
SelectCommand(SelectCommand&& other) = default;
105106

0 commit comments

Comments
 (0)