pose localization trouble

This commit is contained in:
2026-03-14 15:56:08 -04:00
parent a6dca0925f
commit 47606ade0f
6 changed files with 31 additions and 14 deletions

View File

@@ -43,7 +43,7 @@ import frc.robot.utilities.Elastic;
import frc.robot.utilities.Utilities; import frc.robot.utilities.Utilities;
public class RobotContainer { public class RobotContainer {
// private PhotonVision vision; private PhotonVision vision;
private Drivetrain drivetrain; private Drivetrain drivetrain;
private Hood hood; private Hood hood;
private Shooter shooter; private Shooter shooter;
@@ -60,7 +60,7 @@ public class RobotContainer {
private Timer shiftTimer; private Timer shiftTimer;
public RobotContainer() { public RobotContainer() {
//vision = new PhotonVision(); vision = new PhotonVision();
drivetrain = new Drivetrain(null); drivetrain = new Drivetrain(null);
hood = new Hood(); hood = new Hood();
shooter = new Shooter(); shooter = new Shooter();
@@ -70,7 +70,7 @@ public class RobotContainer {
//climber = new Climber(); //climber = new Climber();
configureNamedCommands(); configureNamedCommands();
/*
vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose); vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
vision.addPoseEstimateConsumer((vp) -> { vision.addPoseEstimateConsumer((vp) -> {
Logger.recordOutput( Logger.recordOutput(
@@ -78,7 +78,7 @@ public class RobotContainer {
vp.visualPose() vp.visualPose()
); );
}); });
*/
driver = new CommandXboxController(OIConstants.kDriverControllerPort); driver = new CommandXboxController(OIConstants.kDriverControllerPort);
secondary = new CommandXboxController(OIConstants.kOperatorControllerPort); secondary = new CommandXboxController(OIConstants.kOperatorControllerPort);

View File

@@ -10,8 +10,8 @@ public class IntakeRollerConstants {
public static final int kCurrentLimit = 65; public static final int kCurrentLimit = 65;
public static final boolean kInvertLeftMotor = true; public static final boolean kInvertLeftMotor = false;
public static final boolean kInvertRightMotor = false; public static final boolean kInvertRightMotor = true;
public static final double kSpeed = 1; public static final double kSpeed = 1;
@@ -31,6 +31,6 @@ public class IntakeRollerConstants {
.idleMode(kIdleMode) .idleMode(kIdleMode)
.smartCurrentLimit(kCurrentLimit) .smartCurrentLimit(kCurrentLimit)
.inverted(kInvertRightMotor) .inverted(kInvertRightMotor)
.follow(kLeftMotorCANID); ;
} }
} }

View File

@@ -12,15 +12,24 @@ public class PhotonConstants {
public static final String kCamera2Name = "CameraPV2"; public static final String kCamera2Name = "CameraPV2";
// TODO Need actual values for all of this // TODO Need actual values for all of this
public static final Transform3d kCamera1RobotToCam = new Transform3d(); public static final Transform3d kCamera1RobotToCam = new Transform3d(
Units.inchesToMeters(1.5),
Units.inchesToMeters(-8.5),
Units.inchesToMeters(28.5),
new Rotation3d(
Units.degreesToRadians(0),
Units.degreesToRadians(24.0),
Units.degreesToRadians(30.0)
)
);
public static final Transform3d kCamera2RobotToCam = new Transform3d( public static final Transform3d kCamera2RobotToCam = new Transform3d(
Units.inchesToMeters(1.5), Units.inchesToMeters(1.5),
Units.inchesToMeters(-10.5), Units.inchesToMeters(-10.5),
Units.inchesToMeters(28.5), Units.inchesToMeters(28.5),
new Rotation3d( new Rotation3d(
Units.degreesToRadians(0), Units.degreesToRadians(0.0),
Units.degreesToRadians(24), Units.degreesToRadians(24.0),
Units.degreesToRadians(-10) Units.degreesToRadians(-10.0)
) )
); );
@@ -32,7 +41,7 @@ public class PhotonConstants {
// 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 List<PhotonVisionConfig> configs = List.of( public static final List<PhotonVisionConfig> configs = List.of(
//new PhotonVisionConfig(kCamera1Name, kCamera1RobotToCam, kCamera1HeightMeters, kCamera1PitchRadians), new PhotonVisionConfig(kCamera1Name, kCamera1RobotToCam, kCamera1HeightMeters, kCamera1PitchRadians),
new PhotonVisionConfig(kCamera2Name, kCamera2RobotToCam, kCamera2HeightMeters, kCamera2PitchRadians) new PhotonVisionConfig(kCamera2Name, kCamera2RobotToCam, kCamera2HeightMeters, kCamera2PitchRadians)
); );
} }

View File

@@ -19,7 +19,7 @@ public class SpindexerConstants {
public static final double kSpindexerSpeed = 1; public static final double kSpindexerSpeed = 1;
public static final double kFeederSpeed = 1; public static final double kFeederSpeed = 1;
public static final boolean kFeederMotorInverted = true; public static final boolean kFeederMotorInverted = false;
public static final InvertedValue kSpindexerInversionState = InvertedValue.Clockwise_Positive; public static final InvertedValue kSpindexerInversionState = InvertedValue.Clockwise_Positive;
public static final NeutralModeValue kSpindexerIdleMode = NeutralModeValue.Coast; public static final NeutralModeValue kSpindexerIdleMode = NeutralModeValue.Coast;

View File

@@ -332,6 +332,10 @@ public class Drivetrain extends SubsystemBase {
} }
public void consumeVisualPose(VisualPose pose) { public void consumeVisualPose(VisualPose pose) {
if(Math.abs(pose.visualPose().minus(getPose()).getTranslation().getNorm()) > 1) {
return;
}
estimator.addVisionMeasurement( estimator.addVisionMeasurement(
pose.visualPose(), pose.visualPose(),
pose.timestamp() pose.timestamp()
@@ -376,7 +380,8 @@ public class Drivetrain extends SubsystemBase {
SwerveModuleState[] swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates( SwerveModuleState[] swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
fieldRelative ? fieldRelative ?
ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered, ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered,
estimator.getEstimatedPosition().getRotation()) : //estimator.getEstimatedPosition().getRotation()) :
Rotation2d.fromDegrees(getGyroValue())) :
new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered) new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotationDelivered)
); );

View File

@@ -33,18 +33,21 @@ public class IntakeRoller extends SubsystemBase {
public Command runIn() { public Command runIn() {
return run(() -> { return run(() -> {
leftMotor.set(IntakeRollerConstants.kSpeed*0.8); leftMotor.set(IntakeRollerConstants.kSpeed*0.8);
rightMotor.set(IntakeRollerConstants.kSpeed*0.8);
}); });
} }
public Command runOut() { public Command runOut() {
return run(() -> { return run(() -> {
leftMotor.set(-IntakeRollerConstants.kSpeed); leftMotor.set(-IntakeRollerConstants.kSpeed);
rightMotor.set(-IntakeRollerConstants.kSpeed);
}); });
} }
public Command stop() { public Command stop() {
return run(() -> { return run(() -> {
leftMotor.set(0); leftMotor.set(0);
rightMotor.set(0);
}); });
} }