Skip to content

Commit f573878

Browse files
Merge pull request #211 from Spikes-2212-Programming-Guild/dev
Dev
2 parents b0ce910 + 04c0a56 commit f573878

16 files changed

+964
-87
lines changed
Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
package com.spikes2212.command;
2+
3+
import com.spikes2212.dashboard.Namespace;
4+
import com.spikes2212.dashboard.RootNamespace;
5+
import edu.wpi.first.networktables.NetworkTable;
6+
import edu.wpi.first.wpilibj.DoubleSolenoid;
7+
import edu.wpi.first.wpilibj2.command.InstantCommand;
8+
import edu.wpi.first.wpilibj2.command.Subsystem;
9+
10+
/**
11+
* A {@link Subsystem} that controls a double solenoid.
12+
*
13+
* @author Camellia Lami
14+
* @see DashboardedSubsystem
15+
*/
16+
public class DoubleSolenoidSubsystem extends DashboardedSubsystem {
17+
18+
private final DoubleSolenoid doubleSolenoid;
19+
private final boolean inverted;
20+
21+
public DoubleSolenoidSubsystem(Namespace namespace, DoubleSolenoid doubleSolenoid, boolean inverted) {
22+
super(namespace);
23+
this.doubleSolenoid = doubleSolenoid;
24+
this.inverted = inverted;
25+
}
26+
27+
public DoubleSolenoidSubsystem(String namespaceName, DoubleSolenoid doubleSolenoid, boolean inverted) {
28+
this(new RootNamespace(namespaceName), doubleSolenoid, inverted);
29+
}
30+
31+
/**
32+
* Opens the double solenoid.
33+
*
34+
* @return an {@link InstantCommand} that opens the solenoid
35+
*/
36+
public InstantCommand openCommand() {
37+
if (inverted) {
38+
return new InstantCommand(() -> doubleSolenoid.set(DoubleSolenoid.Value.kForward), this);
39+
}
40+
return new InstantCommand(() -> doubleSolenoid.set(DoubleSolenoid.Value.kReverse), this);
41+
}
42+
43+
/**
44+
* Closes the double solenoid.
45+
*
46+
* @return an {@link InstantCommand} that closes the solenoid
47+
*/
48+
public InstantCommand closeCommand() {
49+
if (inverted) {
50+
return new InstantCommand(() -> doubleSolenoid.set(DoubleSolenoid.Value.kReverse), this);
51+
}
52+
return new InstantCommand(() -> doubleSolenoid.set(DoubleSolenoid.Value.kForward), this);
53+
}
54+
55+
/**
56+
* Adds any commands or data from this subsystem to the {@link NetworkTable}s.
57+
*/
58+
@Override
59+
public void configureDashboard() {
60+
}
61+
}

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

Lines changed: 70 additions & 30 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,62 +32,80 @@ 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 leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward
44+
* @param rightSpeed the speed to set to the right side (-1 to 1). Positive values move this side forward
4645
*/
47-
public void tankDrive(double speedLeft, double speedRight) {
48-
drive.tankDrive(speedLeft, speedRight);
46+
public void tankDrive(double leftSpeed, double rightSpeed) {
47+
drive.tankDrive(leftSpeed, rightSpeed, false);
4948
}
5049

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 leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward
54+
* @param rightSpeed 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
*/
60-
public void tankDrive(double speedLeft, double speedRight, boolean squareInputs) {
61-
drive.tankDrive(speedLeft, speedRight, squareInputs);
57+
public void tankDrive(double leftSpeed, double rightSpeed, boolean squareInputs) {
58+
drive.tankDrive(leftSpeed, rightSpeed, squareInputs);
59+
}
60+
61+
/**
62+
* Moves both sides of this drivetrain by the given voltages for each side.
63+
*
64+
* @param leftVoltage the voltage to set to the left side (-12 to 12). Positive values move this side forward
65+
* @param rightVoltage the voltage to set to the right side (-12 to 12). Positive values move this side forward
66+
*/
67+
public void tankDriveVoltages(double leftVoltage, double rightVoltage) {
68+
tankDrive(leftVoltage / RobotController.getBatteryVoltage(),
69+
rightVoltage / RobotController.getBatteryVoltage(), false);
6270
}
6371

6472
/**
65-
* Moves the drivetrain with the given forward and angular speed.
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) {
71-
drive.arcadeDrive(moveValue, rotateValue);
79+
drive.arcadeDrive(moveValue, rotateValue, false);
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

8593
/**
86-
* Moves the drivetrain while rotating it.
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(), false);
102+
}
103+
104+
/**
105+
* Moves the drivetrain while rotating it at a given curvature.
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 curvature of the robot's path (-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 leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward
99118
*/
100-
public void setLeft(double speedLeft) {
101-
leftController.set(speedLeft);
119+
public void setLeft(double leftSpeed) {
120+
leftController.set(leftSpeed);
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 rightSpeed the speed to set to the right side (-1 to 1). Positive values move this side forward
108127
*/
109-
public void setRight(double speedRight) {
110-
rightController.set(-speedRight);
128+
public void setRight(double rightSpeed) {
129+
rightController.set(-rightSpeed);
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+
setLeft(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+
setRight(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: 116 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,12 @@
11
package com.spikes2212.command.drivetrains.commands;
22

3-
import java.util.function.Supplier;
4-
53
import com.spikes2212.command.drivetrains.TankDrivetrain;
64
import edu.wpi.first.wpilibj2.command.CommandBase;
75

6+
import java.util.function.Supplier;
87

98
/**
10-
* This command moves a {@link TankDrivetrain} by linear and rotational speeds, using
11-
* the arcade control method written by WPILIB.
9+
* A command that moves a {@link TankDrivetrain} using linear and rotational speeds.
1210
*
1311
* @author Yuval Levy
1412
* @see TankDrivetrain
@@ -22,39 +20,142 @@ public class DriveArcade extends CommandBase {
2220
protected final Supplier<Boolean> isFinished;
2321

2422
/**
25-
* This constructs a new {@link DriveArcade} command that moves the given
23+
* Whether to square the velocity suppliers.
24+
*/
25+
protected final boolean squareInputs;
26+
27+
/**
28+
* Constructs a new {@link DriveArcade} command that moves the given
2629
* {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
2730
* for linear and rotational movements.
2831
*
29-
* @param drivetrain the tank drivetrain this command operates on.
30-
* @param moveValueSupplier the double {@link Supplier} supplying the linear velocity. Positive values go forwards.
31-
* @param rotateValueSupplier the double {@link Supplier} supplying the rotational velocity. Positive values go left.
32+
* @param drivetrain the tank drivetrain this command operates on
33+
* @param moveValueSupplier the Double {@link Supplier} supplying the linear speed (-1 to 1).
34+
* Positive values go forwards
35+
* @param rotateValueSupplier the Double {@link Supplier} supplying the rotational speed (-1 to 1).
36+
* Positive values go clockwise
37+
* @param isFinished when to finish the command
38+
* @param squareInputs whether to square the speed suppliers' values
3239
*/
3340
public DriveArcade(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier,
34-
Supplier<Double> rotateValueSupplier, Supplier<Boolean> isFinished) {
41+
Supplier<Double> rotateValueSupplier, Supplier<Boolean> isFinished, boolean squareInputs) {
3542
addRequirements(drivetrain);
3643
this.tankDrivetrain = drivetrain;
3744
this.moveValueSupplier = moveValueSupplier;
3845
this.rotateValueSupplier = rotateValueSupplier;
3946
this.isFinished = isFinished;
47+
this.squareInputs = squareInputs;
48+
}
49+
50+
/**
51+
* Constructs a new {@link DriveArcade} command that moves the given
52+
* {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
53+
* for linear and rotational movements. Does not square the inputs.
54+
*
55+
* @param drivetrain the tank drivetrain this command operates on
56+
* @param moveValueSupplier the Double {@link Supplier} supplying the linear speed (-1 to 1).
57+
* Positive values go forwards
58+
* @param rotateValueSupplier the Double {@link Supplier} supplying the rotational speed (-1 to 1).
59+
* Positive values go clockwise
60+
* @param isFinished when to finish the command
61+
*/
62+
public DriveArcade(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier,
63+
Supplier<Double> rotateValueSupplier, Supplier<Boolean> isFinished) {
64+
this(drivetrain, moveValueSupplier, rotateValueSupplier, isFinished, false);
4065
}
4166

67+
/**
68+
* Constructs a new {@link DriveArcade} command that moves the given
69+
* {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
70+
* for linear and rotational movements.
71+
*
72+
* @param drivetrain the tank drivetrain this command operates on
73+
* @param moveValueSupplier the Double {@link Supplier} supplying the linear speed (-1 to 1).
74+
* Positive values go forwards
75+
* @param rotateValueSupplier the Double {@link Supplier} supplying the rotational speed (-1 to 1).
76+
* Positive values go clockwise
77+
* @param squareInputs whether to square the speed suppliers' values
78+
*/
79+
public DriveArcade(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier,
80+
Supplier<Double> rotateValueSupplier, boolean squareInputs) {
81+
this(drivetrain, moveValueSupplier, rotateValueSupplier, () -> false, squareInputs);
82+
}
83+
84+
/**
85+
* Constructs a new {@link DriveArcade} command that moves the given
86+
* {@link TankDrivetrain} according to speed values from Double {@link Supplier}s
87+
* for linear and rotational movements. Does not square the inputs.
88+
*
89+
* @param drivetrain the tank drivetrain this command operates on
90+
* @param moveValueSupplier the Double {@link Supplier} supplying the linear speed (-1 to 1).
91+
* Positive values go forwards
92+
* @param rotateValueSupplier the Double {@link Supplier} supplying the rotational speed (-1 to 1).
93+
* Positive values go clockwise
94+
*/
4295
public DriveArcade(TankDrivetrain drivetrain, Supplier<Double> moveValueSupplier,
4396
Supplier<Double> rotateValueSupplier) {
44-
this(drivetrain, moveValueSupplier, rotateValueSupplier, () -> false);
97+
this(drivetrain, moveValueSupplier, rotateValueSupplier, () -> false, false);
4598
}
4699

47-
public DriveArcade(TankDrivetrain drivetrain, double moveValue, double rotateValue) {
48-
this(drivetrain, () -> moveValue, () -> rotateValue, () -> false);
100+
/**
101+
* Constructs a new {@link DriveArcade} command that moves the given
102+
* {@link TankDrivetrain} according to speed values for linear and rotational movements.
103+
*
104+
* @param drivetrain the tank drivetrain this command operates on
105+
* @param moveValue the linear speed (-1 to 1). Positive values go forwards
106+
* @param rotateValue the rotational speed (-1 to 1). Positive values go clockwise
107+
* @param isFinished when to finish the command
108+
* @param squareInputs whether to square the speed values
109+
*/
110+
public DriveArcade(TankDrivetrain drivetrain, double moveValue,
111+
double rotateValue, Supplier<Boolean> isFinished, boolean squareInputs) {
112+
this(drivetrain, () -> moveValue, () -> rotateValue, isFinished, squareInputs);
49113
}
50114

51-
public DriveArcade(TankDrivetrain drivetrain, double moveValue, double rotateValue, boolean isFinished) {
52-
this(drivetrain, () -> moveValue, () -> rotateValue, () -> isFinished);
115+
/**
116+
* Constructs a new {@link DriveArcade} command that moves the given
117+
* {@link TankDrivetrain} according to speed values for linear and rotational movements. Does not square the inputs.
118+
*
119+
* @param drivetrain the tank drivetrain this command operates on
120+
* @param moveValue the linear speed (-1 to 1). Positive values go forwards
121+
* @param rotateValue the rotational speed (-1 to 1). Positive values go clockwise
122+
* @param isFinished when to finish the command
123+
*/
124+
public DriveArcade(TankDrivetrain drivetrain, double moveValue,
125+
double rotateValue, Supplier<Boolean> isFinished) {
126+
this(drivetrain, moveValue, rotateValue, isFinished, false);
127+
}
128+
129+
/**
130+
* Constructs a new {@link DriveArcade} command that moves the given
131+
* {@link TankDrivetrain} according to speed values for linear and rotational movements.
132+
*
133+
* @param drivetrain the tank drivetrain this command operates on
134+
* @param moveValue the linear speed (-1 to 1). Positive values go forwards
135+
* @param rotateValue the rotational speed (-1 to 1). Positive values go clockwise
136+
* @param squareInputs whether to square the speed values
137+
*/
138+
public DriveArcade(TankDrivetrain drivetrain, double moveValue,
139+
double rotateValue, boolean squareInputs) {
140+
this(drivetrain, moveValue, rotateValue, () -> false, squareInputs);
141+
}
142+
143+
/**
144+
* Constructs a new {@link DriveArcade} command that moves the given
145+
* {@link TankDrivetrain} according to speed values for linear and rotational movements. Does not square the inputs.
146+
*
147+
* @param drivetrain the tank drivetrain this command operates on
148+
* @param moveValue the linear speed (-1 to 1). Positive values go forwards
149+
* @param rotateValue the rotational speed (-1 to 1). Positive values go clockwise
150+
*/
151+
public DriveArcade(TankDrivetrain drivetrain, double moveValue,
152+
double rotateValue) {
153+
this(drivetrain, moveValue, rotateValue, () -> false, false);
53154
}
54155

55156
@Override
56157
public void execute() {
57-
tankDrivetrain.arcadeDrive(moveValueSupplier.get(), rotateValueSupplier.get());
158+
tankDrivetrain.arcadeDrive(moveValueSupplier.get(), rotateValueSupplier.get(), squareInputs);
58159
}
59160

60161
@Override

0 commit comments

Comments
 (0)