Drivetrain teleop drive and basic auto seems to be ok now
This commit is contained in:
parent
5f15633044
commit
51f2ad4c30
@ -157,7 +157,7 @@ public class RobotContainer {
|
|||||||
);
|
);
|
||||||
|
|
||||||
//intake.setDefaultCommand(intake.intakeUpCommand());
|
//intake.setDefaultCommand(intake.intakeUpCommand());
|
||||||
intake.setDefaultCommand(intake.manualPivot(operator::getLeftY, operator::getRightY));
|
intake.setDefaultCommand(intake.manualPivot(() -> -operator.getLeftY(), operator::getRightY));
|
||||||
|
|
||||||
shooter.setDefaultCommand(
|
shooter.setDefaultCommand(
|
||||||
shooter.angleSpeedsSetpoints(
|
shooter.angleSpeedsSetpoints(
|
||||||
|
@ -420,7 +420,17 @@ public class Drivetrain extends SubsystemBase {
|
|||||||
|
|
||||||
/** Zeroes the heading of the robot. */
|
/** Zeroes the heading of the robot. */
|
||||||
public void zeroHeading() {
|
public void zeroHeading() {
|
||||||
m_gyro.reset();
|
Pose2d tempPose = m_poseEstimator.getEstimatedPosition();
|
||||||
|
|
||||||
|
Rotation2d tempRotation = Rotation2d.fromDegrees(0);
|
||||||
|
|
||||||
|
resetOdometry(
|
||||||
|
new Pose2d(
|
||||||
|
tempPose.getX(),
|
||||||
|
tempPose.getY(),
|
||||||
|
tempRotation
|
||||||
|
)
|
||||||
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
public Command zeroHeadingCommand() {
|
public Command zeroHeadingCommand() {
|
||||||
|
Loading…
Reference in New Issue
Block a user