code works gooda pine tree
This commit is contained in:
parent
798dda7809
commit
d828d5c110
@ -226,8 +226,8 @@ public class RobotContainer {
|
|||||||
|
|
||||||
drivetrain.setDefaultCommand(
|
drivetrain.setDefaultCommand(
|
||||||
drivetrain.teleopCommand(
|
drivetrain.teleopCommand(
|
||||||
() -> { return driver.getLeftY() * (invertXYDrive ? -1 : 1); },
|
() -> { return driver.getLeftY() /* * (invertXYDrive ? -1 : 1)*/; },
|
||||||
() -> { return driver.getLeftX() * (invertXYDrive ? -1 : 1); },
|
() -> { return driver.getLeftX() /* * (invertXYDrive ? -1 : 1)*/; },
|
||||||
() -> { return -driver.getRightX(); },
|
() -> { return -driver.getRightX(); },
|
||||||
OIConstants.kTeleopDriveDeadband
|
OIConstants.kTeleopDriveDeadband
|
||||||
)
|
)
|
||||||
@ -311,7 +311,7 @@ public class RobotContainer {
|
|||||||
indexer.setDefaultCommand(indexer.shootNote(
|
indexer.setDefaultCommand(indexer.shootNote(
|
||||||
() -> {
|
() -> {
|
||||||
if (driver.getRightTriggerAxis() > .25) {
|
if (driver.getRightTriggerAxis() > .25) {
|
||||||
return -1.0;
|
return 1.0;
|
||||||
}else {
|
}else {
|
||||||
return 0.0;
|
return 0.0;
|
||||||
}
|
}
|
||||||
@ -381,6 +381,8 @@ public class RobotContainer {
|
|||||||
// This was originally a run while held, not sure that's really necessary, change it if need be
|
// This was originally a run while held, not sure that's really necessary, change it if need be
|
||||||
driver.rightBumper().onTrue(drivetrain.setXCommand());
|
driver.rightBumper().onTrue(drivetrain.setXCommand());
|
||||||
|
|
||||||
|
operator.rightTrigger().whileTrue(indexer.shootNote(() -> -1.0));
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* This has been added because interest has been expressed in trying field relative vs
|
* This has been added because interest has been expressed in trying field relative vs
|
||||||
* robot relative control. This should <i>default</i> to field relative, but give the option
|
* robot relative control. This should <i>default</i> to field relative, but give the option
|
||||||
@ -419,7 +421,7 @@ public class RobotContainer {
|
|||||||
|
|
||||||
driver.povDown().whileTrue(indexer.shootNote(() -> -1.0));
|
driver.povDown().whileTrue(indexer.shootNote(() -> -1.0));
|
||||||
|
|
||||||
operator.start().onTrue(shooter.zeroEncoder());
|
operator.start().toggleOnTrue(intake.manualPivot(() -> -operator.getRightY()*0.2, () -> driver.getLeftTriggerAxis()));
|
||||||
|
|
||||||
//operator.povDown().whileTrue(intake.intakeDownCommand());
|
//operator.povDown().whileTrue(intake.intakeDownCommand());
|
||||||
//operator.povUp().whileTrue(intake.intakeUpCommand());
|
//operator.povUp().whileTrue(intake.intakeUpCommand());
|
||||||
|
@ -20,8 +20,10 @@ import java.util.function.DoubleSupplier;
|
|||||||
import com.kauailabs.navx.frc.AHRS;
|
import com.kauailabs.navx.frc.AHRS;
|
||||||
import com.pathplanner.lib.auto.AutoBuilder;
|
import com.pathplanner.lib.auto.AutoBuilder;
|
||||||
|
|
||||||
|
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||||
import edu.wpi.first.wpilibj.DriverStation;
|
import edu.wpi.first.wpilibj.DriverStation;
|
||||||
import edu.wpi.first.wpilibj.SPI;
|
import edu.wpi.first.wpilibj.SPI;
|
||||||
|
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||||
import frc.robot.constants.AutoConstants;
|
import frc.robot.constants.AutoConstants;
|
||||||
import frc.robot.constants.DrivetrainConstants;
|
import frc.robot.constants.DrivetrainConstants;
|
||||||
import frc.robot.utilities.MAXSwerveModule;
|
import frc.robot.utilities.MAXSwerveModule;
|
||||||
@ -43,6 +45,7 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
|
|
||||||
// The gyro sensor
|
// The gyro sensor
|
||||||
private final AHRS m_gyro;
|
private final AHRS m_gyro;
|
||||||
|
//private final ADXRS450_Gyro m_gyro;
|
||||||
|
|
||||||
private final SlewRateLimiter m_magLimiter;
|
private final SlewRateLimiter m_magLimiter;
|
||||||
private final SlewRateLimiter m_rotLimiter;
|
private final SlewRateLimiter m_rotLimiter;
|
||||||
@ -92,6 +95,8 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
|
|
||||||
// TODO The NavX is not centered in the robot, it's output probably needs to be translated
|
// TODO The NavX is not centered in the robot, it's output probably needs to be translated
|
||||||
m_gyro = new AHRS(SPI.Port.kMXP);
|
m_gyro = new AHRS(SPI.Port.kMXP);
|
||||||
|
// m_gyro = new ADXRS450_Gyro();
|
||||||
|
//m_gyro.calibrate();
|
||||||
|
|
||||||
m_magLimiter = new SlewRateLimiter(DrivetrainConstants.kMagnitudeSlewRate);
|
m_magLimiter = new SlewRateLimiter(DrivetrainConstants.kMagnitudeSlewRate);
|
||||||
m_rotLimiter = new SlewRateLimiter(DrivetrainConstants.kRotationalSlewRate);
|
m_rotLimiter = new SlewRateLimiter(DrivetrainConstants.kRotationalSlewRate);
|
||||||
|
@ -40,6 +40,7 @@ public class Intake extends SubsystemBase{
|
|||||||
|
|
||||||
intakePivot.setIdleMode(IdleMode.kBrake);
|
intakePivot.setIdleMode(IdleMode.kBrake);
|
||||||
intakePivot.setSmartCurrentLimit(IntakeConstants.kPivotCurrentLimit);
|
intakePivot.setSmartCurrentLimit(IntakeConstants.kPivotCurrentLimit);
|
||||||
|
intakePivot.setInverted(true);
|
||||||
intakePivot.burnFlash();
|
intakePivot.burnFlash();
|
||||||
|
|
||||||
intakeFeedForward = new ArmFeedforward(
|
intakeFeedForward = new ArmFeedforward(
|
||||||
|
Loading…
Reference in New Issue
Block a user