Skip to content

Commit 472c131

Browse files
authored
Merge pull request #207 from Spikes-2212-Programming-Guild/rani-add-voltages
Created setVoltage and implemented for tankDrive and arcadeDrive
2 parents 83a722a + 6c3e31a commit 472c131

File tree

5 files changed

+280
-47
lines changed

5 files changed

+280
-47
lines changed

src/main/java/com/spikes2212/command/drivetrains/TankDrivetrain.java

Lines changed: 60 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
import com.spikes2212.command.DashboardedSubsystem;
44
import edu.wpi.first.networktables.NetworkTable;
5+
import edu.wpi.first.wpilibj.RobotController;
56
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
67
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
78

@@ -31,18 +32,16 @@ public TankDrivetrain(String namespaceName, MotorController left, MotorControlle
3132
rightController.setInverted(true);
3233
drive = new DifferentialDrive(leftController, rightController);
3334
}
34-
35+
3536
public TankDrivetrain(MotorController left, MotorController right) {
3637
this(getClassName(DEFAULT_NAMESPACE_NAME), left, right);
3738
}
3839

3940
/**
4041
* Moves both sides of this drivetrain by the given speeds for each side.
4142
*
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
4645
*/
4746
public void tankDrive(double speedLeft, double speedRight) {
4847
drive.tankDrive(speedLeft, speedRight);
@@ -51,42 +50,62 @@ public void tankDrive(double speedLeft, double speedRight) {
5150
/**
5251
* Moves both sides of this drivetrain by the given speeds for each side.
5352
*
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
5855
* @param squareInputs whether to square the given inputs before putting them in the speed controllers
5956
*/
6057
public void tankDrive(double speedLeft, double speedRight, boolean squareInputs) {
6158
drive.tankDrive(speedLeft, speedRight, squareInputs);
6259
}
6360

6461
/**
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.
6674
*
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
6977
*/
7078
public void arcadeDrive(double moveValue, double rotateValue) {
7179
drive.arcadeDrive(moveValue, rotateValue);
7280
}
7381

7482
/**
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.
7684
*
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
7987
* @param squareInputs whether to square the given inputs before putting them in the speed controllers
8088
*/
8189
public void arcadeDrive(double moveValue, double rotateValue, boolean squareInputs) {
8290
drive.arcadeDrive(moveValue, rotateValue, squareInputs);
8391
}
8492

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+
85104
/**
86105
* Moves the drivetrain while rotating it.
87106
*
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
90109
*/
91110
public void curvatureDrive(double speed, double curvature) {
92111
drive.curvatureDrive(speed, curvature, true);
@@ -95,21 +114,42 @@ public void curvatureDrive(double speed, double curvature) {
95114
/**
96115
* Moves the left side of this drivetrain by a given speed.
97116
*
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
99118
*/
100119
public void setLeft(double speedLeft) {
101120
leftController.set(speedLeft);
102121
}
103122

104123
/**
105-
* Moves the right side of this drivetrain with a given speed.
124+
* Moves the right side of this drivetrain by a given speed.
106125
*
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
108127
*/
109128
public void setRight(double speedRight) {
110129
rightController.set(-speedRight);
111130
}
112131

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+
*/
113153
public void stop() {
114154
leftController.stopMotor();
115155
rightController.stopMotor();

src/main/java/com/spikes2212/command/drivetrains/commands/DriveArcade.java

Lines changed: 10 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,7 @@
66
import java.util.function.Supplier;
77

88
/**
9-
* This command moves a {@link TankDrivetrain} by linear and rotational speeds, using
10-
* the arcade control method written by WPILIB.
9+
* A command that moves a {@link TankDrivetrain} using linear and rotational speeds.
1110
*
1211
* @author Yuval Levy
1312
* @see TankDrivetrain
@@ -26,7 +25,7 @@ public class DriveArcade extends CommandBase {
2625
protected final boolean squareInputs;
2726

2827
/**
29-
* This constructs a new {@link DriveArcade} command that moves the given
28+
* Constructs a new {@link DriveArcade} command that moves the given
3029
* {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
3130
* for linear and rotational movements.
3231
*
@@ -49,7 +48,7 @@ public DriveArcade(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier
4948
}
5049

5150
/**
52-
* This constructs a new {@link DriveArcade} command that moves the given
51+
* Constructs a new {@link DriveArcade} command that moves the given
5352
* {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
5453
* for linear and rotational movements. Does not square the inputs.
5554
*
@@ -66,7 +65,7 @@ public DriveArcade(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier
6665
}
6766

6867
/**
69-
* This constructs a new {@link DriveArcade} command that moves the given
68+
* Constructs a new {@link DriveArcade} command that moves the given
7069
* {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
7170
* for linear and rotational movements.
7271
*
@@ -83,7 +82,7 @@ public DriveArcade(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier
8382
}
8483

8584
/**
86-
* This constructs a new {@link DriveArcade} command that moves the given
85+
* Constructs a new {@link DriveArcade} command that moves the given
8786
* {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
8887
* for linear and rotational movements. Does not square the inputs.
8988
*
@@ -99,7 +98,7 @@ public DriveArcade(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier
9998
}
10099

101100
/**
102-
* This constructs a new {@link DriveArcade} command that moves the given
101+
* Constructs a new {@link DriveArcade} command that moves the given
103102
* {@link TankDrivetrain} according to speed values for linear and rotational movements.
104103
*
105104
* @param drivetrain the tank drivetrain this command operates on
@@ -114,7 +113,7 @@ public DriveArcade(TankDrivetrain drivetrain, double moveValue,
114113
}
115114

116115
/**
117-
* This constructs a new {@link DriveArcade} command that moves the given
116+
* Constructs a new {@link DriveArcade} command that moves the given
118117
* {@link TankDrivetrain} according to speed values for linear and rotational movements. Does not square the inputs.
119118
*
120119
* @param drivetrain the tank drivetrain this command operates on
@@ -128,7 +127,7 @@ public DriveArcade(TankDrivetrain drivetrain, double moveValue,
128127
}
129128

130129
/**
131-
* This constructs a new {@link DriveArcade} command that moves the given
130+
* Constructs a new {@link DriveArcade} command that moves the given
132131
* {@link TankDrivetrain} according to speed values for linear and rotational movements.
133132
*
134133
* @param drivetrain the tank drivetrain this command operates on
@@ -142,7 +141,7 @@ public DriveArcade(TankDrivetrain drivetrain, double moveValue,
142141
}
143142

144143
/**
145-
* This constructs a new {@link DriveArcade} command that moves the given
144+
* Constructs a new {@link DriveArcade} command that moves the given
146145
* {@link TankDrivetrain} according to speed values for linear and rotational movements. Does not square the inputs.
147146
*
148147
* @param drivetrain the tank drivetrain this command operates on
@@ -156,7 +155,7 @@ public DriveArcade(TankDrivetrain drivetrain, double moveValue,
156155

157156
@Override
158157
public void execute() {
159-
tankDrivetrain.arcadeDrive(moveValueSupplier.get(), rotateValueSupplier.get());
158+
tankDrivetrain.arcadeDrive(moveValueSupplier.get(), rotateValueSupplier.get(), squareInputs);
160159
}
161160

162161
@Override
Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
package com.spikes2212.command.drivetrains.commands;
2+
3+
import java.util.function.Supplier;
4+
5+
import com.spikes2212.command.drivetrains.TankDrivetrain;
6+
import edu.wpi.first.wpilibj2.command.CommandBase;
7+
8+
/**
9+
* A command that moves a {@link TankDrivetrain} using linear and rotational voltages.
10+
*
11+
* @author Yuval Levy
12+
* @see TankDrivetrain
13+
*/
14+
15+
public class DriveArcadeWithVoltages extends CommandBase {
16+
17+
protected final TankDrivetrain tankDrivetrain;
18+
protected final Supplier<Double> moveValueSupplier;
19+
protected final Supplier<Double> rotateValueSupplier;
20+
protected final Supplier<Boolean> isFinished;
21+
22+
/**
23+
* Constructs a new {@link DriveArcade} command that moves the given
24+
* {@link TankDrivetrain} according to voltage values from Double {@link Supplier}s
25+
* for linear and rotational movements.
26+
*
27+
* @param drivetrain the tank drivetrain this command operates on
28+
* @param moveValueSupplier the double {@link Supplier} supplying the linear voltage (-12 to 12).
29+
* Positive values go forwards
30+
* @param rotateValueSupplier the double {@link Supplier} supplying the rotational voltage (-12 to 12).
31+
* Positive values go clockwise
32+
* @param isFinished when to finish the command
33+
*/
34+
public DriveArcadeWithVoltages(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier,
35+
Supplier<Double> rotateValueSupplier, Supplier<Boolean> isFinished) {
36+
addRequirements(drivetrain);
37+
this.tankDrivetrain = drivetrain;
38+
this.moveValueSupplier = moveValueSupplier;
39+
this.rotateValueSupplier = rotateValueSupplier;
40+
this.isFinished = isFinished;
41+
}
42+
43+
/**
44+
* Constructs a new {@link DriveArcade} command that moves the given
45+
* {@link TankDrivetrain} according to voltage values from Double {@link Supplier}s
46+
* for linear and rotational movements.
47+
*
48+
* @param drivetrain the tank drivetrain this command operates on
49+
* @param moveValueSupplier the double {@link Supplier} supplying the linear voltage (-12 to 12).
50+
* Positive values go forwards
51+
* @param rotateValueSupplier the double {@link Supplier} supplying the rotational voltage (-12 to 12).
52+
* Positive values go clockwise
53+
*/
54+
public DriveArcadeWithVoltages(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier,
55+
Supplier<Double> rotateValueSupplier) {
56+
this(drivetrain, moveValueSupplier, rotateValueSupplier, () -> false);
57+
}
58+
59+
/**
60+
* Constructs a new {@link DriveArcade} command that moves the given
61+
* {@link TankDrivetrain} according to voltage values for linear and rotational movements.
62+
*
63+
* @param drivetrain the tank drivetrain this command operates on
64+
* @param moveValue the linear voltage (-12 to 12). Positive values go forwards
65+
* @param rotateValue the rotational voltage (-12 to 12). Positive values go clockwise
66+
* @param isFinished when to finish the command
67+
*/
68+
public DriveArcadeWithVoltages(TankDrivetrain drivetrain, double moveValue, double rotateValue,
69+
Supplier<Boolean> isFinished) {
70+
this(drivetrain, () -> moveValue, () -> rotateValue, isFinished);
71+
}
72+
73+
/**
74+
* Constructs a new {@link DriveArcade} command that moves the given
75+
* {@link TankDrivetrain} according to voltage values for linear and rotational movements.
76+
*
77+
* @param drivetrain the tank drivetrain this command operates on
78+
* @param moveValue the linear voltage (-12 to 12). Positive values go forwards
79+
* @param rotateValue the rotational voltage (-12 to 12). Positive values go clockwise
80+
*/
81+
public DriveArcadeWithVoltages(TankDrivetrain drivetrain, double moveValue, double rotateValue) {
82+
this(drivetrain, () -> moveValue, () -> rotateValue, () -> false);
83+
}
84+
85+
@Override
86+
public void execute() {
87+
tankDrivetrain.arcadeDriveVoltages(moveValueSupplier.get(), rotateValueSupplier.get());
88+
}
89+
90+
@Override
91+
public boolean isFinished() {
92+
return isFinished.get();
93+
}
94+
95+
@Override
96+
public void end(boolean interrupted) {
97+
tankDrivetrain.stop();
98+
}
99+
}

0 commit comments

Comments
 (0)