before selectino
This commit is contained in:
parent
e98b3a585e
commit
c75554dfc5
@ -226,8 +226,8 @@ public class RobotContainer {
|
|||||||
operator.back().onTrue(elevator.homeCommand());
|
operator.back().onTrue(elevator.homeCommand());
|
||||||
|
|
||||||
operator.start().toggleOnTrue(
|
operator.start().toggleOnTrue(
|
||||||
climberPivot.runPivot(() -> -operator.getRightY()*0.5)
|
climberPivot.runPivot(() -> -operator.getRightY())
|
||||||
.alongWith(climberRollers.runRoller(() -> operator.getLeftY()*0.5)));
|
.alongWith(climberRollers.runRoller(() -> operator.getLeftY())));
|
||||||
|
|
||||||
operator.a().onTrue(
|
operator.a().onTrue(
|
||||||
safeMoveManipulator(ElevatorConstants.kCoralIntakePosition, ManipulatorPivotConstants.kStartingPosition)
|
safeMoveManipulator(ElevatorConstants.kCoralIntakePosition, ManipulatorPivotConstants.kStartingPosition)
|
||||||
|
@ -188,8 +188,6 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.2, 0.2, Units.degreesToRadians(360)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.2, 0.2, Units.degreesToRadians(360)));
|
||||||
}else if(vision.getOrangeDist() < 100 && Math.abs(getVelocity()) > 3){
|
}else if(vision.getOrangeDist() < 100 && Math.abs(getVelocity()) > 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.3, 0.3, Units.degreesToRadians(360)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.3, 0.3, Units.degreesToRadians(360)));
|
||||||
}else if(getVelocity() < 1.5){
|
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.06, 0.06, Units.degreesToRadians(360)));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// if the detected tags match your alliances reef tags use their pose estimates
|
// if the detected tags match your alliances reef tags use their pose estimates
|
||||||
@ -216,8 +214,6 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.2, 0.2, Units.degreesToRadians(360)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.2, 0.2, Units.degreesToRadians(360)));
|
||||||
}else if(vision.getBlackDist() < 100 && Math.abs(getVelocity()) > 3){
|
}else if(vision.getBlackDist() < 100 && Math.abs(getVelocity()) > 3){
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.3, 0.3, Units.degreesToRadians(360)));
|
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.3, 0.3, Units.degreesToRadians(360)));
|
||||||
}else if(getVelocity() < 1.5){
|
|
||||||
m_estimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.06, 0.06, Units.degreesToRadians(360)));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if(vision.getBlackClosestTag() >= 6 && vision.getBlackClosestTag() <= 11 && DriverStation.getAlliance().get().equals(Alliance.Red) && vision.getBlackTagDetected()){
|
if(vision.getBlackClosestTag() >= 6 && vision.getBlackClosestTag() <= 11 && DriverStation.getAlliance().get().equals(Alliance.Red) && vision.getBlackTagDetected()){
|
||||||
|
Loading…
Reference in New Issue
Block a user