Skip to content

Commit d3d6e65

Browse files
authored
Merge pull request #70 from DeepBlueRobotics/issue-63
Add wobbleDrive feature
2 parents f6b8439 + 41b1053 commit d3d6e65

5 files changed

Lines changed: 83 additions & 6 deletions

File tree

Robot2019/src/main/java/frc/robot/OI.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,11 @@
1212
import edu.wpi.first.wpilibj.Joystick;
1313
import edu.wpi.first.wpilibj.buttons.JoystickButton;
1414
import frc.robot.commands.ActuateClimberRails;
15-
import frc.robot.commands.NormalDrive;
1615
import frc.robot.commands.Climb;
1716
import frc.robot.commands.EjectCargo;
1817
import frc.robot.commands.IntakeOnlyCargo;
18+
import frc.robot.commands.NormalDrive;
19+
import frc.robot.commands.ResetWobble;
1920
import frc.robot.commands.SetArcadeOrTank;
2021
import frc.robot.commands.SlowDrive;
2122
import frc.robot.commands.ToggleCamera;
@@ -54,7 +55,8 @@ public class OI {
5455
rightSlowBtn = new JoystickButton(rightJoy, 1);
5556
rightSlowBtn.whileHeld(new SlowDrive(SlowDrive.Side.RIGHT));
5657
wobbleDriveBtn = new JoystickButton(rightJoy, 4); // TODO: confirm button with drivers
57-
wobbleDriveBtn.whileHeld(new WobbleDrive(dt));
58+
wobbleDriveBtn.whenPressed(new WobbleDrive(dt));
59+
wobbleDriveBtn.whenReleased(new ResetWobble(dt));
5860

5961
arcadeOrTankBtn = new JoystickButton(leftJoy, 4);
6062
arcadeOrTankBtn.whenPressed(new SetArcadeOrTank());
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
/*----------------------------------------------------------------------------*/
2+
/* Copyright (c) 2018 FIRST. All Rights Reserved. */
3+
/* Open Source Software - may be modified and shared by FRC teams. The code */
4+
/* must be accompanied by the FIRST BSD license file in the root directory of */
5+
/* the project. */
6+
/*----------------------------------------------------------------------------*/
7+
8+
package frc.robot.commands;
9+
10+
import edu.wpi.first.wpilibj.command.InstantCommand;
11+
import frc.robot.subsystems.Drivetrain;
12+
13+
/**
14+
* Add your docs here.
15+
*/
16+
public class ResetWobble extends InstantCommand {
17+
/**
18+
* Add your docs here.
19+
*/
20+
Drivetrain dt;
21+
public ResetWobble(Drivetrain dt) {
22+
super();
23+
// Use requires() here to declare subsystem dependencies
24+
// eg. requires(chassis);
25+
this.dt = dt;
26+
}
27+
28+
// Called once when the command executes
29+
@Override
30+
protected void initialize() {
31+
dt.setWobbleDone(true);
32+
}
33+
34+
}

Robot2019/src/main/java/frc/robot/commands/SetArcadeOrTank.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@ public SetArcadeOrTank() {
88

99
}
1010

11+
@Override
1112
protected void initialize() {
1213
if (SmartDashboard.getBoolean("Arcade Drive", true)) {
1314
SmartDashboard.putBoolean("Arcade Drive", false);

Robot2019/src/main/java/frc/robot/commands/WobbleDrive.java

Lines changed: 33 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,15 +9,20 @@
99

1010
import edu.wpi.first.wpilibj.Timer;
1111
import edu.wpi.first.wpilibj.command.Command;
12+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1213
import frc.robot.subsystems.Drivetrain;
1314
import frc.robot.subsystems.Drivetrain.Side;
1415

1516
public class WobbleDrive extends Command {
1617
Drivetrain dt;
1718
Side side = Side.LEFT; // We start with left side. TODO: confirm this
1819
Timer tim;
19-
private final double wobbleTime = 0.75; // TODO: Set to actual number
20-
private final double driveSpeed = 0.5; // TODO: Set to actual number
20+
boolean leftSideDone;
21+
boolean rightSideDone;
22+
private final double minTime = 0.2;
23+
private final double wobbleTime = 0.3; // TODO: Set to actual number
24+
private final double driveSpeed = 0.3; // TODO: Set to actual number
25+
private final double encRateTolerance = 1; // TODO: Set to actual number
2126

2227
public WobbleDrive(Drivetrain dt) {
2328
// Use requires() here to declare subsystem dependencies
@@ -32,12 +37,35 @@ protected void initialize() {
3237
tim = new Timer();
3338
tim.reset();
3439
tim.start();
40+
dt.setWobbleDone(false);
41+
leftSideDone = false;
42+
rightSideDone = false;
43+
SmartDashboard.putBoolean("Wobble drive done", false);
3544
}
3645

3746
// Called repeatedly when this Command is scheduled to run
3847
@Override
3948
protected void execute() {
40-
if (tim.get() > wobbleTime) {
49+
boolean done = dt.getEncRate(Side.LEFT) < encRateTolerance && dt.getEncRate(Side.RIGHT) < encRateTolerance;
50+
if (tim.get() > minTime) {
51+
if (side == Side.LEFT) {
52+
leftSideDone = done;
53+
} else {
54+
rightSideDone = done;
55+
}
56+
}
57+
if (leftSideDone) {
58+
tim.reset();
59+
tim.start();
60+
side = Side.RIGHT;
61+
}
62+
if (rightSideDone) {
63+
tim.reset();
64+
tim.start();
65+
side = Side.LEFT;
66+
}
67+
68+
if (tim.get() > wobbleTime && (!leftSideDone && !rightSideDone)) {
4169
if (side == Side.LEFT) {
4270
side = Side.RIGHT;
4371
} else {
@@ -54,13 +82,14 @@ protected void execute() {
5482
// Make this return true when this Command no longer needs to run execute()
5583
@Override
5684
protected boolean isFinished() {
57-
return false;
85+
return dt.wobbleDone() || (leftSideDone && rightSideDone);
5886
}
5987

6088
// Called once after isFinished returns true
6189
@Override
6290
protected void end() {
6391
dt.stop();
92+
SmartDashboard.putBoolean("Wobble drive done", true);
6493
}
6594

6695
// Called when another command which requires one or more of the same

Robot2019/src/main/java/frc/robot/subsystems/Drivetrain.java

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,8 @@ public enum Direction {
4040
private double blKV, blKA, blVI;
4141
private double brKV, brKA, brVI;
4242

43+
private boolean wobbleDone;
44+
4345
public Drivetrain(WPI_TalonSRX leftMaster, BaseMotorController leftSlave1, BaseMotorController leftSlave2,
4446
WPI_TalonSRX rightMaster, BaseMotorController rightSlave1, BaseMotorController rightSlave2, Encoder leftEnc,
4547
Encoder rightEnc, AHRS ahrs) {
@@ -71,6 +73,7 @@ public Drivetrain(WPI_TalonSRX leftMaster, BaseMotorController leftSlave1, BaseM
7173
updateDrivetrainParameters();
7274

7375
maxVoltage = 12.0;
76+
wobbleDone = false;
7477
}
7578

7679
/**
@@ -125,6 +128,14 @@ public double getGyroAngle() {
125128
return ahrs.getYaw();
126129
}
127130

131+
public void setWobbleDone(boolean set) {
132+
wobbleDone = set;
133+
}
134+
135+
public boolean wobbleDone() {
136+
return wobbleDone;
137+
}
138+
128139
public double getMaxSpeed() { // Return must be adjusted in the future;
129140
return 13 * 12;
130141
}

0 commit comments

Comments
 (0)