Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix auto pickup, fix shooting-while-moving for blue alliance, fix odometry bugging out #141

Merged
merged 3 commits into from
Nov 27, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
55 changes: 23 additions & 32 deletions src/main/java/frc/robot/commands/CollectNote.java
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ public void initialize() {
Vision.K_DETECTOR_TY_D);
tyLimiter = new SlewRateLimiter(20, -20, 0);
txController.setSetpoint(0);
tyController.setSetpoint(0);
tyController.setSetpoint(2.5);
txController.setTolerance(3.5, 0.25);
tyController.setTolerance(1, 0.25);
detectorData = limelight.getNeuralDetectorValues();
Expand All @@ -64,44 +64,34 @@ public void initialize() {
public void execute() {
detectorData = limelight.getNeuralDetectorValues();

if (detectorData == null) {
drivetrain.stop();
System.err.println("nullDetectorData");
return;
}
if (!detectorData.isResultValid) {
if (runsInvalid <= 10) { // don't stop imediately, in case only a couple frames were missed
drivetrain.drive(new ChassisSpeeds(tyLimiter.calculate(0), 0, 0));
} else {
drivetrain.stop();
}
System.err.println("invalidDetectorData");
runsInvalid++;
return;
} else {
runsInvalid = 0;
}
// if (!detectorData.isResultValid) {
// if (runsInvalid <= 10) { // don't stop imediately, in case only a couple frames were missed
// drivetrain.drive(new ChassisSpeeds(tyLimiter.calculate(0), 0, 0));
// } else {
// drivetrain.stop();
// }
// System.err.println("invalidDetectorData");
// runsInvalid++;
// return;
// } else {
// runsInvalid = 0;
// }

ty = detectorData.ty;
if(!closeNote) {
tx = detectorData.tx;
double forwardSpeed = tyLimiter.calculate(-20/Math.abs(tx));
SmartDashboard.putNumber("CollectNote/forward speed limited", forwardSpeed);
if(Math.abs(forwardSpeed)>1) {forwardSpeed = -1;}
drivetrain.drive(new ChassisSpeeds(
forwardSpeed,
txController.calculate(-tx),
0));
} else if(detectorData.ty<=5.5){
tx = detectorData.tx;
if(detectorData.isResultValid){
tx = -detectorData.tx;
double forwardSpeed = tyLimiter.calculate(-20/Math.abs(tx));
if(Math.abs(forwardSpeed)>1) {forwardSpeed = -1;}
double sidewaysSpeed = txController.calculate(-tx);
if(sidewaysSpeed>1){sidewaysSpeed = 1;}
if(sidewaysSpeed<-1){sidewaysSpeed = -1;}
drivetrain.drive(new ChassisSpeeds(
forwardSpeed,
txController.calculate(-tx),
sidewaysSpeed,
0));
SmartDashboard.putNumber("CollectNote/forward speed limited", forwardSpeed);
} else {
}
else {
drivetrain.drive(new ChassisSpeeds(
-1, 0, 0));
runsInvalid++;
Expand All @@ -116,6 +106,7 @@ public void execute() {
SmartDashboard.putNumber("CollectNote/calculated radians per second", txController.calculate(tx));
SmartDashboard.putNumber("CollectNote/calculated forward meters per second", tyLimiter.calculate(-20/Math.abs(tx)));
SmartDashboard.putBoolean("CollectNote/closeNote", closeNote);
SmartDashboard.putBoolean("CollectNote/isNoteSeen", detectorData.isResultValid);
SmartDashboard.putNumber("CollectNote/runsInvalid", runsInvalid);
// drives the robot forward faster if the object is higher up on the screen, and turns it more based on how far away the object is from x=0
}
Expand All @@ -133,6 +124,6 @@ public void end(boolean interrupted) {
// Returns true when the command should end.
@Override
public boolean isFinished() {
return ((tyController.atSetpoint() && txController.atSetpoint()) || detectorData == null || runsInvalid>5);
return ((tyController.atSetpoint() && txController.atSetpoint()) || detectorData == null ||runsInvalid>5);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ public double calculateSpeakerAngle() {
offsetSpeakerX = Field.SHOOTER_RED_SPEAKER_X - targetOffset.getX();
offsetSpeakerY = Field.RED_SPEAKER_Y - targetOffset.getY();
} else {
offsetSpeakerX = Field.SHOOTER_BLUE_SPEAKER_X - targetOffset.getX();
offsetSpeakerX = Field.SHOOTER_BLUE_SPEAKER_X + targetOffset.getX();
offsetSpeakerY = Field.BLUE_SPEAKER_Y - targetOffset.getY();
}
double offsetDeltaX = Math.abs(dtvalues.getX() - offsetSpeakerX);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -324,7 +324,7 @@ public void updateOdometryWithVision() {
}
if(!doRejectUpdate) {
Logger.recordOutput("Vision/MergesPose", estimate.pose);
odometer.addVisionMeasurement(new Pose2d(estimate.pose.getX(), estimate.pose.getY(), getGyroscopeRotation()), estimate.timestampSeconds);
odometer.addVisionMeasurement(estimate.pose, estimate.timestampSeconds);
}
RobotState.getInstance().LimelightsUpdated = true;
} else {
Expand Down