Skip to content

Commit

Permalink
Merge pull request #174 from frc937/heading-snapping-speed
Browse files Browse the repository at this point in the history
Miscellaneous testing fixes
  • Loading branch information
willitcode authored Mar 27, 2024
2 parents a1e55dc + 164700e commit 01e0889
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 8 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ public RobotContainer() {

startIntakeCamera.schedule();

drive.setDefaultCommand(driveFieldOriented);
drive.setDefaultCommand(driveFieldOrientedHeadingSnapping);
}

private void configureAuto() {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ public Drive() {
/* HolonomicPathFollowerConfig, this should likely live in your Constants class */
Constants.Drive.TRANSLATION_DRIVE_PID, /* Translation PID constants */
Constants.Drive.ROTATION_DRIVE_PID, /* Rotation PID constants */
Constants.Drive.MAX_SPEED, /* Max module speed, in m/s */
getMaximumSpeed(), /* Max module speed, in m/s */
Constants.Drive
.DISTANCE_ROBOT_CENTER_TO_SWERVE_MODULE, /* Drive base radius in meters. Distance from robot center to furthest module. */
new ReplanningConfig() /* Default path replanning config. See the API for the options here */),
Expand Down Expand Up @@ -168,7 +168,7 @@ public ChassisSpeeds getTargetSpeeds(
headingX,
headingY,
drive.getPose().getRotation().getRadians(),
Constants.Drive.MAX_SPEED);
getMaximumSpeed());
}

/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ public Intake() {
intakeLower.burnFlash();
intakeUpper.burnFlash();

Shuffleboard.getTab("Driver").add("Note in intake", false).getEntry();
noteIsInIntake = Shuffleboard.getTab("Driver").add("Note in intake", false).getEntry();
}

/** Runs the intake motors. */
Expand Down
7 changes: 3 additions & 4 deletions src/main/java/frc/robot/subsystems/Limelight.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
import edu.wpi.first.networktables.DoubleTopic;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.shuffleboard.SendableCameraWrapper;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

Expand Down Expand Up @@ -65,9 +64,9 @@ public Limelight(String name) {
.getDoubleArrayTopic(fmtPath("botpose"))
.subscribe(defaultBotpos);

Shuffleboard.getTab("Driver")
.add(SendableCameraWrapper.wrap(name, "http://" + name + ".local:5800/stream.mjpg"))
.withSize(4, 4);
/* Shuffleboard.getTab("Driver")
.add(SendableCameraWrapper.wrap(name, "http://" + name + ".local:5800/stream.mjpg"))
.withSize(4, 4); */

/* TODO: CONSTANTS */
limelightHasTarget = Shuffleboard.getTab("Driver").add(name + "has target", false).getEntry();
Expand Down

0 comments on commit 01e0889

Please sign in to comment.