Skip to content
This repository has been archived by the owner on Jan 8, 2025. It is now read-only.

Drive wheel testing function #73

Merged
merged 9 commits into from
Oct 27, 2023
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/ArmPresets.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@ public enum ArmPresets {
76.3),

// Human Player Station = HPS
HPS_PICKUP(0, 77,
72),
HPS_PICKUP(0, 76.3,
71.3),

ARM_STOWED(1, 2, 1),

Expand Down
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/Auto.java
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,14 @@ public CommandBase prepareToScoreCone() {
armRotate.moveTo(ArmPresets.HIGH_SCORE));
}

public CommandBase testDriveDriver() {
return sequence(
drive.moveForDirectional(0, 1, 5),
drive.moveForDirectional(1, 0, 5),
drive.moveForDirectional(0, -1, 5),
drive.moveForDirectional(-1, 0, 5));
}
Comment on lines +131 to +137
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Doesn't look like this is used anywhere either, can we remove it?


public CommandBase stowArmCloseIntake() {
return sequence(
armExtend.moveTo(ArmPresets.ARM_STOWED),
Expand Down
20 changes: 16 additions & 4 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -154,11 +154,12 @@ public CommandBase rumbleAndIntakeSpinningOff() {
public CommandBase pickUpGamePiece = sequence(
new ConditionalCommand(
sequence(
armRotate.moveTo(ArmPresets.CONE_PICKUP), armExtend.moveTo(ArmPresets.CONE_PICKUP)),
armRotate.moveTo(ArmPresets.CONE_PICKUP), armExtend.moveTo(ArmPresets.CONE_PICKUP),
intake.toggle()),
sequence(
armRotate.moveTo(ArmPresets.CUBE_PICKUP), armExtend.moveTo(
ArmPresets.CUBE_PICKUP),
intake.coneRelease()),
intake.coneRelease(), intake.toggle()),
() -> {
return gamePieceSub.get() == "Cone";
}));
Expand Down Expand Up @@ -225,8 +226,19 @@ public void configureButtonBindings() {
driveController.x().whileTrue(drive.rotateToAngle(Rotation2d.fromDegrees(180), () -> 0, () -> 0));
driveController.a().whileTrue(drive.rotateToAngle(Rotation2d.fromDegrees(0), () -> 0, () -> 0));

(new Trigger(() -> driveController.getRightTriggerAxis() > 0.5))
.onTrue(balanceArm.pushDown()).onFalse(balanceArm.pushUp());
driveController.povDown().onTrue(drive.moveForDirectional(0, 1, 5));
driveController.povRight().onTrue(drive.moveForDirectional(1, 0, 5));
driveController.povUp().onTrue(drive.moveForDirectional(0, -1, 5));
driveController.povLeft().onTrue(drive.moveForDirectional(-1, 0, 5));
Comment on lines +229 to +232
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm a bit nervous about having these mappings on the drive controller. It's pretty dangerous to have a command that can cause the robot to take off in a direction without a way to easily stop it.
And if this happens during a match at the very least it'll cause lost time.

I think these would be best on the dashboard (https://docs.wpilib.org/en/stable/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-commands-subsystems.html#displaying-commands).
Or at the very least make these whileTrue instead of onTrue.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We can probably slow this down a bit too, not sure it needs to be at 1m/s, maybe 0.5?
We should also make sure we put the units of values in argument names.

/*
* public CommandBase testDriveDriver() {
* return sequence(
* moveForDirectional(0, 1, 5),
* moveForDirectional(1, 0, 5),
* moveForDirectional(0, -1, 5),
* moveForDirectional(-1, 0, 5));
* }
*/
Comment on lines +233 to +241
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We generally don't want to keep commented code

// Arm

// COPILOT CONTROLLER
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/maps/FrostBiteMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ public ArmRotateMap getArmRotateMap() {
absEncoder.setDutyCycleRange(1.0 / 1025.0, 1024.0 / 1025.0);
absEncoder.setDistancePerRotation(-360);
// Adjust this to move the encoder zero point to the retracted position
absEncoder.setPositionOffset(91.89780758483522 - 7);
absEncoder.setPositionOffset(54.8);

CSFusedEncoder fusedEncoder = new CSFusedEncoder(encoder, absEncoder);

Expand Down
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/subsystems/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
import com.chopshop166.chopshoplib.commands.FunctionalWaitCommand;
import com.chopshop166.chopshoplib.commands.SmartSubsystemBase;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;
Expand Down Expand Up @@ -395,6 +394,12 @@ public CommandBase balance() {

}

public CommandBase moveForDirectional(double xSpeed, double ySpeed, double seconds) {
return race(
driveRaw(() -> xSpeed, () -> ySpeed, () -> 0),
new FunctionalWaitCommand(() -> seconds)).andThen(safeStateCmd());
}

public CommandBase resetGyroCommand() {
return cmd().onInitialize(() -> {
resetGyro();
Expand Down