2
2
3
3
import com .spikes2212 .command .DashboardedSubsystem ;
4
4
import edu .wpi .first .networktables .NetworkTable ;
5
+ import edu .wpi .first .wpilibj .RobotController ;
5
6
import edu .wpi .first .wpilibj .drive .DifferentialDrive ;
6
7
import edu .wpi .first .wpilibj .motorcontrol .MotorController ;
7
8
@@ -31,18 +32,16 @@ public TankDrivetrain(String namespaceName, MotorController left, MotorControlle
31
32
rightController .setInverted (true );
32
33
drive = new DifferentialDrive (leftController , rightController );
33
34
}
34
-
35
+
35
36
public TankDrivetrain (MotorController left , MotorController right ) {
36
37
this (getClassName (DEFAULT_NAMESPACE_NAME ), left , right );
37
38
}
38
39
39
40
/**
40
41
* Moves both sides of this drivetrain by the given speeds for each side.
41
42
*
42
- * @param speedLeft the speed to set to the left side. Positive values move this side
43
- * forward.
44
- * @param speedRight the speed to set to the right side. Positive values move this side
45
- * forward.
43
+ * @param speedLeft the speed to set to the left side (-1 to 1). Positive values move this side forward
44
+ * @param speedRight the speed to set to the right side (-1 to 1). Positive values move this side forward
46
45
*/
47
46
public void tankDrive (double speedLeft , double speedRight ) {
48
47
drive .tankDrive (speedLeft , speedRight );
@@ -51,42 +50,62 @@ public void tankDrive(double speedLeft, double speedRight) {
51
50
/**
52
51
* Moves both sides of this drivetrain by the given speeds for each side.
53
52
*
54
- * @param speedLeft the speed to set to the left side. Positive values move this side
55
- * forward.
56
- * @param speedRight the speed to set to the right side. Positive values move this side
57
- * forward.
53
+ * @param speedLeft the speed to set to the left side (-1 to 1). Positive values move this side forward
54
+ * @param speedRight the speed to set to the right side (-1 to 1). Positive values move this side forward
58
55
* @param squareInputs whether to square the given inputs before putting them in the speed controllers
59
56
*/
60
57
public void tankDrive (double speedLeft , double speedRight , boolean squareInputs ) {
61
58
drive .tankDrive (speedLeft , speedRight , squareInputs );
62
59
}
63
60
64
61
/**
65
- * Moves the drivetrain with the given forward and angular speed.
62
+ * Moves both sides of this drivetrain by the given voltages for each side.
63
+ *
64
+ * @param leftVoltage the voltage to the left side (-1 to 1). Positive values move this side forward
65
+ * @param rightVoltage the voltage to the right side (-1 to 1). Positive values move this side forward
66
+ */
67
+ public void tankDriveVoltages (double leftVoltage , double rightVoltage ) {
68
+ tankDrive (leftVoltage / RobotController .getBatteryVoltage (),
69
+ rightVoltage / RobotController .getBatteryVoltage ());
70
+ }
71
+
72
+ /**
73
+ * Moves the drivetrain by the given forward and angular speed.
66
74
*
67
- * @param moveValue the forward movement speed.
68
- * @param rotateValue the angular movement speed. Positive values go clockwise.
75
+ * @param moveValue the forward movement speed (-1 to 1)
76
+ * @param rotateValue the angular movement speed (-1 to 1) . Positive values go clockwise
69
77
*/
70
78
public void arcadeDrive (double moveValue , double rotateValue ) {
71
79
drive .arcadeDrive (moveValue , rotateValue );
72
80
}
73
81
74
82
/**
75
- * Moves both sides of this drivetrain by the given speeds for each side .
83
+ * Moves the drivetrain by the given forward and angular speed .
76
84
*
77
- * @param moveValue the forward movement speed.
78
- * @param rotateValue the angular movement speed. Positive values go clockwise.
85
+ * @param moveValue the forward movement speed (-1 to 1)
86
+ * @param rotateValue the angular movement speed (-1 to 1) . Positive values go clockwise
79
87
* @param squareInputs whether to square the given inputs before putting them in the speed controllers
80
88
*/
81
89
public void arcadeDrive (double moveValue , double rotateValue , boolean squareInputs ) {
82
90
drive .arcadeDrive (moveValue , rotateValue , squareInputs );
83
91
}
84
92
93
+ /**
94
+ * Moves the drivetrain by the given forward and angular voltage.
95
+ *
96
+ * @param moveVoltage the forward movement voltage (-12 to 12)
97
+ * @param rotateVoltage the angular movement voltage (-12 to 12). Positive values go clockwise
98
+ */
99
+ public void arcadeDriveVoltages (double moveVoltage , double rotateVoltage ) {
100
+ arcadeDrive (moveVoltage / RobotController .getBatteryVoltage (),
101
+ rotateVoltage / RobotController .getBatteryVoltage ());
102
+ }
103
+
85
104
/**
86
105
* Moves the drivetrain while rotating it.
87
106
*
88
- * @param speed the forward movement speed.
89
- * @param curvature the rotational movement speed. Positive values go clockwise.
107
+ * @param speed the forward movement speed (-1 to 1)
108
+ * @param curvature the rotational movement speed (-1 to 1) . Positive values go clockwise
90
109
*/
91
110
public void curvatureDrive (double speed , double curvature ) {
92
111
drive .curvatureDrive (speed , curvature , true );
@@ -95,21 +114,42 @@ public void curvatureDrive(double speed, double curvature) {
95
114
/**
96
115
* Moves the left side of this drivetrain by a given speed.
97
116
*
98
- * @param speedLeft the speed to set to the left side. Positive values move this side forward.
117
+ * @param speedLeft the speed to set to the left side (-1 to 1) . Positive values move this side forward
99
118
*/
100
119
public void setLeft (double speedLeft ) {
101
120
leftController .set (speedLeft );
102
121
}
103
122
104
123
/**
105
- * Moves the right side of this drivetrain with a given speed.
124
+ * Moves the right side of this drivetrain by a given speed.
106
125
*
107
- * @param speedRight the speed to set to the right side. Positive values move this side forward.
126
+ * @param speedRight the speed to set to the right side (-1 to 1) . Positive values move this side forward
108
127
*/
109
128
public void setRight (double speedRight ) {
110
129
rightController .set (-speedRight );
111
130
}
112
131
132
+ /**
133
+ * Moves the left side of this drivetrain by a given voltage.
134
+ *
135
+ * @param leftVoltage the voltage to set to the left side (-12 to 12). Positive values move this side forward
136
+ */
137
+ public void setLeftVoltage (double leftVoltage ) {
138
+ leftController .set (leftVoltage / RobotController .getBatteryVoltage ());
139
+ }
140
+
141
+ /**
142
+ * Moves the right side of this drivetrain by a given voltage.
143
+ *
144
+ * @param rightVoltage the voltage to set to the right side (-12 to 12). Positive values move this side forward
145
+ */
146
+ public void setRightVoltage (double rightVoltage ) {
147
+ rightController .set (rightVoltage / RobotController .getBatteryVoltage ());
148
+ }
149
+
150
+ /**
151
+ * Stops the drivetrain.
152
+ */
113
153
public void stop () {
114
154
leftController .stopMotor ();
115
155
rightController .stopMotor ();
0 commit comments