Compare commits
2 Commits
a8833aaf5b
...
d29acde2df
| Author | SHA1 | Date | |
|---|---|---|---|
| d29acde2df | |||
| 048c7158ee |
@@ -6,6 +6,7 @@ package frc.robot;
|
|||||||
|
|
||||||
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
import edu.wpi.first.wpilibj.DriverStation.Alliance;
|
||||||
|
|
||||||
|
import java.util.Optional;
|
||||||
import java.util.OptionalDouble;
|
import java.util.OptionalDouble;
|
||||||
|
|
||||||
import org.littletonrobotics.junction.Logger;
|
import org.littletonrobotics.junction.Logger;
|
||||||
@@ -15,8 +16,12 @@ import com.pathplanner.lib.auto.NamedCommands;
|
|||||||
import com.pathplanner.lib.events.EventTrigger;
|
import com.pathplanner.lib.events.EventTrigger;
|
||||||
import com.pathplanner.lib.path.EventMarker;
|
import com.pathplanner.lib.path.EventMarker;
|
||||||
|
|
||||||
|
import edu.wpi.first.math.MathUtil;
|
||||||
import edu.wpi.first.math.geometry.Pose2d;
|
import edu.wpi.first.math.geometry.Pose2d;
|
||||||
|
import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap;
|
||||||
import edu.wpi.first.math.util.Units;
|
import edu.wpi.first.math.util.Units;
|
||||||
|
import edu.wpi.first.util.sendable.Sendable;
|
||||||
|
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||||
import edu.wpi.first.wpilibj.Timer;
|
import edu.wpi.first.wpilibj.Timer;
|
||||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||||
@@ -62,6 +67,8 @@ public class RobotContainer {
|
|||||||
|
|
||||||
private Timer shiftTimer;
|
private Timer shiftTimer;
|
||||||
|
|
||||||
|
private boolean resetOdometryToVisualPose;
|
||||||
|
|
||||||
public RobotContainer() {
|
public RobotContainer() {
|
||||||
vision = new PhotonVision();
|
vision = new PhotonVision();
|
||||||
drivetrain = new Drivetrain(null);
|
drivetrain = new Drivetrain(null);
|
||||||
@@ -73,6 +80,7 @@ public class RobotContainer {
|
|||||||
//climber = new Climber();
|
//climber = new Climber();
|
||||||
configureNamedCommands();
|
configureNamedCommands();
|
||||||
|
|
||||||
|
resetOdometryToVisualPose = false;
|
||||||
|
|
||||||
//vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
|
//vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
|
||||||
vision.addPoseEstimateConsumer((vp) -> {
|
vision.addPoseEstimateConsumer((vp) -> {
|
||||||
@@ -81,6 +89,12 @@ public class RobotContainer {
|
|||||||
vp.visualPose()
|
vp.visualPose()
|
||||||
);
|
);
|
||||||
});
|
});
|
||||||
|
vision.addPoseEstimateConsumer((vp) -> {
|
||||||
|
if(resetOdometryToVisualPose) {
|
||||||
|
drivetrain.resetOdometry(vp.visualPose());
|
||||||
|
resetOdometryToVisualPose = false;
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
|
||||||
driver = new CommandXboxController(OIConstants.kDriverControllerPort);
|
driver = new CommandXboxController(OIConstants.kDriverControllerPort);
|
||||||
@@ -96,7 +110,6 @@ public class RobotContainer {
|
|||||||
if(AutoConstants.kAutoConfigOk) {
|
if(AutoConstants.kAutoConfigOk) {
|
||||||
autoChooser = AutoBuilder.buildAutoChooser();
|
autoChooser = AutoBuilder.buildAutoChooser();
|
||||||
SmartDashboard.putData("Auto Chooser", autoChooser);
|
SmartDashboard.putData("Auto Chooser", autoChooser);
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -258,6 +271,7 @@ public class RobotContainer {
|
|||||||
|
|
||||||
intakePivot.setDefaultCommand(intakePivot.manualSpeed(() -> secondary.getLeftY()));
|
intakePivot.setDefaultCommand(intakePivot.manualSpeed(() -> secondary.getLeftY()));
|
||||||
|
|
||||||
|
driver.a().onTrue(new InstantCommand(() -> resetOdometryToVisualPose = true));
|
||||||
driver.y().whileTrue(drivetrain.zeroHeading());
|
driver.y().whileTrue(drivetrain.zeroHeading());
|
||||||
|
|
||||||
driver.leftTrigger().whileTrue(
|
driver.leftTrigger().whileTrue(
|
||||||
@@ -288,36 +302,38 @@ public class RobotContainer {
|
|||||||
secondary.a().toggleOnTrue(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed));
|
secondary.a().toggleOnTrue(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed));
|
||||||
secondary.x().toggleOnTrue(shooter.maintainSpeed(ShooterSpeeds.kFeedSpeed));
|
secondary.x().toggleOnTrue(shooter.maintainSpeed(ShooterSpeeds.kFeedSpeed));
|
||||||
|
|
||||||
secondary.y().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(40)));
|
//hood.setDefaultCommand(hood.trackToAngle(() -> Units.degreesToRadians(MathUtil.clamp(hoodAngle, 0, 40))));
|
||||||
|
//secondary.y().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(40)));
|
||||||
//40 good for feeding
|
//40 good for feeding
|
||||||
secondary.b().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(30)));
|
//secondary.b().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(30)));
|
||||||
//30 degrees good for shooter far near outpost
|
//30 degrees good for shooter far near outpost
|
||||||
secondary.rightBumper().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(10)));
|
secondary.rightBumper().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(10)));
|
||||||
//10 degrees good for shooting ~33in away from hub
|
//10 degrees good for shooting ~33in away from hub
|
||||||
|
|
||||||
/*
|
|
||||||
hood.setDefaultCommand(hood.trackToAngle(() -> {
|
hood.setDefaultCommand(hood.trackToAngle(() -> {
|
||||||
Pose2d drivetrainPose = drivetrain.getPose();
|
Pose2d drivetrainPose = drivetrain.getPose();
|
||||||
Pose2d hubPose = Utilities.getHubPose();
|
Pose2d hubPose = Utilities.getHubPose();
|
||||||
|
|
||||||
double distance = drivetrainPose.getTranslation()
|
double distance = drivetrainPose.getTranslation()
|
||||||
.plus(CompetitionConstants.kRobotToShooter.getTranslation().toTranslation2d())
|
|
||||||
.getDistance(hubPose.getTranslation());
|
.getDistance(hubPose.getTranslation());
|
||||||
|
|
||||||
|
Logger.recordOutput("Hood/DistanceToHub", distance);
|
||||||
|
|
||||||
|
Optional<ShooterSpeeds> currentSpeeds = shooter.getTargetSpeeds();
|
||||||
|
|
||||||
if(HoodConstants.kUseInterpolatorForAngle) {
|
if(currentSpeeds.isPresent()) {
|
||||||
return HoodConstants.kDistanceToAngle.get(distance);
|
InterpolatingDoubleTreeMap map = HoodConstants.kHoodInterpolators.get(currentSpeeds.get());
|
||||||
|
|
||||||
|
if(map != null) {
|
||||||
|
return MathUtil.clamp(map.get(distance), 0, 40);
|
||||||
|
} else {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
// TODO The average actual speeds isn't <i>really</i> the exit velocity of the ball
|
return 0;
|
||||||
// on a hooded shooter, based on documentation, it's more like 30-50% depending on
|
|
||||||
// hood material, surface friction, etc.
|
|
||||||
return Utilities.shotAngle(
|
|
||||||
shooter.getAverageActualSpeeds(),
|
|
||||||
distance,
|
|
||||||
CompetitionConstants.kHubGoalHeightMeters - ShooterConstants.kShooterHeightMeters,
|
|
||||||
false
|
|
||||||
);
|
|
||||||
}
|
}
|
||||||
}));*/
|
}));
|
||||||
}
|
}
|
||||||
|
|
||||||
private void configureNamedCommands() {
|
private void configureNamedCommands() {
|
||||||
|
|||||||
@@ -24,8 +24,6 @@ public class AutoConstants {
|
|||||||
public static final double kPXYController = 3.5;
|
public static final double kPXYController = 3.5;
|
||||||
public static final double kPThetaController = 5;
|
public static final double kPThetaController = 5;
|
||||||
|
|
||||||
public static final double kYawPIDTolerance = Units.degreesToRadians(2);
|
|
||||||
|
|
||||||
public static final double kAlignPXYController = 2;
|
public static final double kAlignPXYController = 2;
|
||||||
public static final double kAlignPThetaController = 5;
|
public static final double kAlignPThetaController = 5;
|
||||||
|
|
||||||
|
|||||||
@@ -38,9 +38,10 @@ public class DrivetrainConstants {
|
|||||||
public static final boolean kGyroReversed = true;
|
public static final boolean kGyroReversed = true;
|
||||||
|
|
||||||
// TODO Hold over from 2025, adjust?
|
// TODO Hold over from 2025, adjust?
|
||||||
public static final double kHeadingP = .1;
|
public static final double kHeadingP = .65;
|
||||||
public static final double kXTranslationP = .5;
|
public static final double kXTranslationP = .5;
|
||||||
public static final double kYTranslationP = .5;
|
public static final double kYTranslationP = .5;
|
||||||
|
public static final double kYawPIDTolerance = Units.degreesToRadians(1);
|
||||||
|
|
||||||
// TODO How much do we trust gyro and encoders vs vision estimates.
|
// TODO How much do we trust gyro and encoders vs vision estimates.
|
||||||
// NOTE: Bigger values indicate LESS trust. Generally all three values for a given matrix should be the same
|
// NOTE: Bigger values indicate LESS trust. Generally all three values for a given matrix should be the same
|
||||||
|
|||||||
@@ -5,6 +5,7 @@ import java.io.File;
|
|||||||
import java.io.FileReader;
|
import java.io.FileReader;
|
||||||
import java.io.IOException;
|
import java.io.IOException;
|
||||||
import java.nio.file.Path;
|
import java.nio.file.Path;
|
||||||
|
import java.util.Map;
|
||||||
|
|
||||||
import com.revrobotics.spark.ClosedLoopSlot;
|
import com.revrobotics.spark.ClosedLoopSlot;
|
||||||
import com.revrobotics.spark.FeedbackSensor;
|
import com.revrobotics.spark.FeedbackSensor;
|
||||||
@@ -12,7 +13,9 @@ import com.revrobotics.spark.config.SparkMaxConfig;
|
|||||||
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
|
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
|
||||||
|
|
||||||
import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap;
|
import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap;
|
||||||
|
import edu.wpi.first.math.util.Units;
|
||||||
import edu.wpi.first.wpilibj.Filesystem;
|
import edu.wpi.first.wpilibj.Filesystem;
|
||||||
|
import frc.robot.constants.ShooterConstants.ShooterSpeeds;
|
||||||
|
|
||||||
public class HoodConstants {
|
public class HoodConstants {
|
||||||
// TODO Real Values
|
// TODO Real Values
|
||||||
@@ -43,9 +46,9 @@ public class HoodConstants {
|
|||||||
|
|
||||||
public static final IdleMode kIdleMode = IdleMode.kBrake;
|
public static final IdleMode kIdleMode = IdleMode.kBrake;
|
||||||
|
|
||||||
// TODO This needs to be filled in from some source
|
public static final Map<ShooterSpeeds, InterpolatingDoubleTreeMap> kHoodInterpolators = Map.of(
|
||||||
public static final InterpolatingDoubleTreeMap kDistanceToAngle = new InterpolatingDoubleTreeMap();
|
ShooterSpeeds.kHubSpeed, new InterpolatingDoubleTreeMap()
|
||||||
|
);
|
||||||
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A CONFIGURATION ITEM
|
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A CONFIGURATION ITEM
|
||||||
|
|
||||||
public static final SparkMaxConfig kConfig = new SparkMaxConfig();
|
public static final SparkMaxConfig kConfig = new SparkMaxConfig();
|
||||||
@@ -66,27 +69,24 @@ public class HoodConstants {
|
|||||||
.feedForward
|
.feedForward
|
||||||
.sva(kS, kV, kA);
|
.sva(kS, kV, kA);
|
||||||
|
|
||||||
|
kHoodInterpolators.get(ShooterSpeeds.kHubSpeed).put(
|
||||||
|
Double.valueOf(Units.inchesToMeters(22.2 + 40)),
|
||||||
|
Double.valueOf(Units.degreesToRadians(10)));
|
||||||
|
|
||||||
File interpolatorFile = Path.of(
|
kHoodInterpolators.get(ShooterSpeeds.kHubSpeed).put(
|
||||||
Filesystem.getDeployDirectory().getAbsolutePath().toString(),
|
Double.valueOf(Units.inchesToMeters(22.2 + 60)),
|
||||||
"interpolatorData.csv"
|
Double.valueOf(Units.degreesToRadians(13)));
|
||||||
).toFile();
|
|
||||||
|
|
||||||
if(interpolatorFile.exists()) {
|
kHoodInterpolators.get(ShooterSpeeds.kHubSpeed).put(
|
||||||
try (BufferedReader reader = new BufferedReader(new FileReader(interpolatorFile))) {
|
Double.valueOf(Units.inchesToMeters(22.2 + 80)),
|
||||||
reader.lines().forEach((s) -> {
|
Double.valueOf(Units.degreesToRadians(17)));
|
||||||
if(s.trim() != "") { //Empty or whitespace line protection
|
|
||||||
String[] lineSplit = s.split(",");
|
|
||||||
|
|
||||||
kDistanceToAngle.put(
|
kHoodInterpolators.get(ShooterSpeeds.kHubSpeed).put(
|
||||||
Double.valueOf(lineSplit[0].replace("\"", "")),
|
Double.valueOf(Units.inchesToMeters(22.2 + 100)),
|
||||||
Double.valueOf(lineSplit[1].replace("\"", ""))
|
Double.valueOf(Units.degreesToRadians(21)));
|
||||||
);
|
|
||||||
}
|
kHoodInterpolators.get(ShooterSpeeds.kHubSpeed).put(
|
||||||
});
|
Double.valueOf(Units.inchesToMeters(22.2 + 120)),
|
||||||
} catch (IOException e) {
|
Double.valueOf(Units.degreesToRadians(24)));
|
||||||
// This condition is never reached because of the if exists line above
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -18,7 +18,7 @@ public class PhotonConstants {
|
|||||||
Units.inchesToMeters(28.5),
|
Units.inchesToMeters(28.5),
|
||||||
new Rotation3d(
|
new Rotation3d(
|
||||||
Units.degreesToRadians(0),
|
Units.degreesToRadians(0),
|
||||||
Units.degreesToRadians(24.0),
|
Units.degreesToRadians(-24.0),
|
||||||
Units.degreesToRadians(30.0)
|
Units.degreesToRadians(30.0)
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
@@ -28,7 +28,7 @@ public class PhotonConstants {
|
|||||||
Units.inchesToMeters(28.5),
|
Units.inchesToMeters(28.5),
|
||||||
new Rotation3d(
|
new Rotation3d(
|
||||||
Units.degreesToRadians(0.0),
|
Units.degreesToRadians(0.0),
|
||||||
Units.degreesToRadians(24.0),
|
Units.degreesToRadians(-24.0),
|
||||||
Units.degreesToRadians(-10.0)
|
Units.degreesToRadians(-10.0)
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|||||||
@@ -82,12 +82,12 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
gyro = new AHRS(NavXComType.kMXP_SPI);
|
gyro = new AHRS(NavXComType.kMXP_SPI);
|
||||||
|
|
||||||
yawRotationController = new PIDController(
|
yawRotationController = new PIDController(
|
||||||
AutoConstants.kPThetaController,
|
DrivetrainConstants.kHeadingP,
|
||||||
0,
|
0,
|
||||||
0
|
0
|
||||||
);
|
);
|
||||||
yawRotationController.enableContinuousInput(-Math.PI, Math.PI);
|
yawRotationController.enableContinuousInput(-Math.PI, Math.PI);
|
||||||
yawRotationController.setTolerance(AutoConstants.kYawPIDTolerance);
|
yawRotationController.setTolerance(DrivetrainConstants.kYawPIDTolerance);
|
||||||
|
|
||||||
// TODO 2025 used non-standard deviations for encoder/gyro inputs and vision, will need to be tuned for 2026 in the future
|
// TODO 2025 used non-standard deviations for encoder/gyro inputs and vision, will need to be tuned for 2026 in the future
|
||||||
estimator = new SwerveDrivePoseEstimator(
|
estimator = new SwerveDrivePoseEstimator(
|
||||||
@@ -262,10 +262,17 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
targetRotation = targetRotation.rotateBy(Rotation2d.k180deg);
|
targetRotation = targetRotation.rotateBy(Rotation2d.k180deg);
|
||||||
}
|
}
|
||||||
|
|
||||||
return yawRotationController.calculate(
|
Logger.recordOutput("/HubAutoAlign/CurrentHeader", getHeading().getRadians());
|
||||||
|
Logger.recordOutput("/HubAutoAlign/Setpoint", targetRotation.getRadians());
|
||||||
|
|
||||||
|
double outputPower = -yawRotationController.calculate(
|
||||||
getHeading().getRadians(),
|
getHeading().getRadians(),
|
||||||
targetRotation.getRadians()
|
targetRotation.getRadians()
|
||||||
);
|
);
|
||||||
|
|
||||||
|
Logger.recordOutput("/HubAutoAlign/OutputPower", outputPower);
|
||||||
|
|
||||||
|
return outputPower;
|
||||||
},
|
},
|
||||||
() -> true
|
() -> true
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -13,6 +13,7 @@ import org.photonvision.PhotonPoseEstimator.PoseStrategy;
|
|||||||
import org.photonvision.targeting.PhotonPipelineResult;
|
import org.photonvision.targeting.PhotonPipelineResult;
|
||||||
import org.photonvision.targeting.PhotonTrackedTarget;
|
import org.photonvision.targeting.PhotonTrackedTarget;
|
||||||
|
|
||||||
|
import edu.wpi.first.math.geometry.Pose2d;
|
||||||
import edu.wpi.first.math.geometry.Pose3d;
|
import edu.wpi.first.math.geometry.Pose3d;
|
||||||
import edu.wpi.first.math.geometry.Transform3d;
|
import edu.wpi.first.math.geometry.Transform3d;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
|
|||||||
Reference in New Issue
Block a user