5
5
# pragma once
6
6
7
7
# include <memory>
8
+ # include <utility>
9
+
10
+ # include "frc2/command/SwerveControllerCommand.h"
8
11
9
12
namespace frc2 {
10
13
@@ -17,11 +20,11 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
17
20
std ::function< frc ::Rotation2d ()> desiredRotation,
18
21
std ::function< void (std ::array< frc ::SwerveModuleState, NumModules> )> output,
19
22
std ::initializer_list< Subsystem* > requirements)
20
- : m_trajectory (trajectory),
21
- m_pose (pose),
23
+ : m_trajectory (std :: move ( trajectory) ),
24
+ m_pose (std :: move ( pose) ),
22
25
m_kinematics (kinematics),
23
26
m_controller (xController, yController, thetaController),
24
- m_desiredRotation (desiredRotation),
27
+ m_desiredRotation (std :: move ( desiredRotation) ),
25
28
m_outputStates (output) {
26
29
this - > AddRequirements (requirements);
27
30
}
@@ -34,8 +37,8 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
34
37
frc ::ProfiledPIDController< units ::radians> thetaController,
35
38
std ::function< void (std ::array< frc ::SwerveModuleState, NumModules> )> output,
36
39
std ::initializer_list< Subsystem* > requirements)
37
- : m_trajectory (trajectory),
38
- m_pose (pose),
40
+ : m_trajectory (std :: move ( trajectory) ),
41
+ m_pose (std :: move ( pose) ),
39
42
m_kinematics (kinematics),
40
43
m_controller (xController, yController, thetaController),
41
44
m_outputStates (output) {
@@ -54,11 +57,11 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
54
57
std ::function< frc ::Rotation2d ()> desiredRotation,
55
58
std ::function< void (std ::array< frc ::SwerveModuleState, NumModules> )> output,
56
59
wpi ::ArrayRef< Subsystem* > requirements)
57
- : m_trajectory (trajectory),
58
- m_pose (pose),
60
+ : m_trajectory (std :: move ( trajectory) ),
61
+ m_pose (std :: move ( pose) ),
59
62
m_kinematics (kinematics),
60
63
m_controller (xController, yController, thetaController),
61
- m_desiredRotation (desiredRotation),
64
+ m_desiredRotation (std :: move ( desiredRotation) ),
62
65
m_outputStates (output) {
63
66
this - > AddRequirements (requirements);
64
67
}
@@ -71,8 +74,8 @@ SwerveControllerCommand<NumModules>::SwerveControllerCommand(
71
74
frc ::ProfiledPIDController< units ::radians> thetaController,
72
75
std ::function< void (std ::array< frc ::SwerveModuleState, NumModules> )> output,
73
76
wpi ::ArrayRef< Subsystem* > requirements)
74
- : m_trajectory (trajectory),
75
- m_pose (pose),
77
+ : m_trajectory (std :: move ( trajectory) ),
78
+ m_pose (std :: move ( pose) ),
76
79
m_kinematics (kinematics),
77
80
m_controller (xController, yController, thetaController),
78
81
m_outputStates (output) {
0 commit comments