From 43d9e8aa992cc5080385bee61ac08e49305ae11f Mon Sep 17 00:00:00 2001 From: aarav18 Date: Fri, 7 Feb 2020 20:03:13 -0700 Subject: [PATCH 1/4] Make Position PID workie Co-Authored-By: Keenan D. Buckley --- .../java/frc4388/robot/RobotContainer.java | 25 +++++++++---------- .../commands/DriveStraightToPositionPID.java | 21 +++++++++++----- .../java/frc4388/robot/subsystems/Drive.java | 6 ++--- 3 files changed, 30 insertions(+), 22 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index d9c82a3..9fb7762 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -16,6 +16,7 @@ import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.button.JoystickButton; import frc4388.robot.Constants.*; import frc4388.robot.commands.DriveStraightAtVelocityPID; +import frc4388.robot.commands.DriveStraightToPositionPID; import frc4388.robot.commands.DriveWithJoystick; import frc4388.robot.commands.RunIntakeWithTriggers; import frc4388.robot.subsystems.Drive; @@ -65,16 +66,8 @@ public class RobotContainer { */ private void configureButtonBindings() { /* Driver Buttons */ - //new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON) - // .whenPressed(new DriveStraightToPositionPID(m_robotDrive, 36)); - - /* Operator Buttons */ - // activates "Lit Mode" - new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON) - .whenPressed(() -> m_robotLED.setPattern(LEDPatterns.LAVA_RAINBOW)) - .whenReleased(() -> m_robotLED.setPattern(LEDConstants.DEFAULT_PATTERN)); - - /* PID Test Command */ + new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON) + .whenPressed(new DriveStraightToPositionPID(m_robotDrive, 144)); // runs velocity PID while driving straight new JoystickButton(getDriverJoystick(), XboxController.B_BUTTON) .whenPressed(new DriveStraightAtVelocityPID(m_robotDrive, 500)) @@ -82,12 +75,18 @@ public class RobotContainer { // resets the yaw of the pigeon new JoystickButton(getDriverJoystick(), XboxController.X_BUTTON) .whenPressed(new InstantCommand(() -> m_robotDrive.resetGyroYaw(), m_robotDrive)); - - //new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) - // .whenPressed(new RunCommand(() -> m_robotDrive.runMotionMagicPID(5000, 0), m_robotDrive)); + // turn 45 degrees + new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) + .whenPressed(new RunCommand(() -> m_robotDrive.runTurningPID(45), m_robotDrive)); // interrupts any running command new JoystickButton(getDriverJoystick(), XboxController.LEFT_JOYSTICK_BUTTON) .whenPressed(new InstantCommand(() -> System.out.print("Gamer"), m_robotDrive)); + + /* Operator Buttons */ + // activates "Lit Mode" + new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON) + .whenPressed(() -> m_robotLED.setPattern(LEDPatterns.LAVA_RAINBOW)) + .whenReleased(() -> m_robotLED.setPattern(LEDConstants.DEFAULT_PATTERN)); } /** diff --git a/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java b/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java index 67d78b3..0b9b998 100644 --- a/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java +++ b/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java @@ -14,8 +14,10 @@ import frc4388.robot.subsystems.Drive; public class DriveStraightToPositionPID extends CommandBase { Drive m_drive; - double m_targetPos; + double m_targetPosIn; + double m_targetPosOut; double m_targetGyro; + int i; /** * Creates a new DriveToDistancePID. @@ -25,22 +27,27 @@ public class DriveStraightToPositionPID extends CommandBase { public DriveStraightToPositionPID(Drive subsystem, double targetPos) { // Use addRequirements() here to declare subsystem dependencies. m_drive = subsystem; - m_targetPos = targetPos * DriveConstants.TICKS_PER_INCH; + m_targetPosIn = targetPos * DriveConstants.TICKS_PER_INCH; addRequirements(m_drive); - SmartDashboard.putNumber("Distance Target Inches", targetPos); + //SmartDashboard.putNumber("Distance Target Inches", targetPos); } // Called when the command is initially scheduled. @Override public void initialize() { + //System.err.println("PID START \n | \n |"); m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + m_targetPosOut = m_targetPosIn + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY); + i = 0; } // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - //System.err.println(m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); - m_drive.runDriveStraightPositionPID(m_targetPos, m_targetGyro); + //System.err.println("| \n Sensor Pos \n" + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY)); + //System.err.println("Sensor Error \n" + m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); + //System.err.println("Sensor Target \n" + m_drive.m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_PRIMARY)); + m_drive.runDriveStraightPositionPID(m_targetPosOut, m_targetGyro); } // Called once the command ends or is interrupted. @@ -51,9 +58,11 @@ public class DriveStraightToPositionPID extends CommandBase { // Returns true when the command should end. @Override public boolean isFinished() { - if (Math.abs(m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() - m_targetPos) < 500){ + if (Math.abs((int)m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY)) < 5 && i > 5){ return true; } else { + i++; + //System.err.println(i); return false; } } diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index ee725ad..faf161e 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -130,8 +130,8 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.configSensorTerm(SensorTerm.Sum1, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS); /* Diff Signal */ - m_rightFrontMotor.configSensorTerm(SensorTerm.Diff0, FeedbackDevice.RemoteSensor0, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configSensorTerm(SensorTerm.Diff1, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSensorTerm(SensorTerm.Diff1, FeedbackDevice.RemoteSensor0, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSensorTerm(SensorTerm.Diff0, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS); /* Configure Sum [Sum of both QuadEncoders] to be used for Primary PID Index */ m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.SensorDifference, @@ -329,7 +329,7 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); - targetPos *= 2; + targetPos *= 1; m_rightFrontMotor.set(TalonFXControlMode.Position, targetPos, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); From 148ea4e941312b1a11060a72a408e4d0ee7d9500 Mon Sep 17 00:00:00 2001 From: keenandbuckley Date: Fri, 7 Feb 2020 21:49:04 -0700 Subject: [PATCH 2/4] Add Motion Magic (Aux PID acting up) - Aux PID drifting and causing robot to slam into walls (Aux PID works everywhere else) --- src/main/java/frc4388/robot/Constants.java | 4 +- .../java/frc4388/robot/RobotContainer.java | 3 +- .../commands/DriveStraightToPositionMM.java | 70 +++++++++++++++++++ .../java/frc4388/robot/subsystems/Drive.java | 21 ++++-- 4 files changed, 88 insertions(+), 10 deletions(-) create mode 100644 src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 27d5359..f4b73dc 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -32,8 +32,8 @@ public final class Constants { public static final Gains DRIVE_VELOCITY_GAINS = new Gains(0.0, 0.0, 0.0, 0.1, 0, 1.0); public static final Gains DRIVE_TURNING_GAINS = new Gains(0.4, 0.0, 0.0, 0.0, 0, 0.3); public static final Gains DRIVE_MOTION_MAGIC_GAINS = new Gains(0.2, 0.0, 0.0, 0.0, 0, 1.0); - public static final int DRIVE_CRUISE_VELOCITY = 2000; - public static final int DRIVE_ACCELERATION = 1000; + public static final int DRIVE_CRUISE_VELOCITY = 20000; + public static final int DRIVE_ACCELERATION = 7000; /* Remote Sensors */ public final static int REMOTE_0 = 0; diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 9fb7762..f343dbb 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -16,6 +16,7 @@ import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.button.JoystickButton; import frc4388.robot.Constants.*; import frc4388.robot.commands.DriveStraightAtVelocityPID; +import frc4388.robot.commands.DriveStraightToPositionMM; import frc4388.robot.commands.DriveStraightToPositionPID; import frc4388.robot.commands.DriveWithJoystick; import frc4388.robot.commands.RunIntakeWithTriggers; @@ -74,7 +75,7 @@ public class RobotContainer { .whenReleased(new InstantCommand(() -> System.out.print("Gamer"), m_robotDrive)); // resets the yaw of the pigeon new JoystickButton(getDriverJoystick(), XboxController.X_BUTTON) - .whenPressed(new InstantCommand(() -> m_robotDrive.resetGyroYaw(), m_robotDrive)); + .whenPressed(new DriveStraightToPositionMM(m_robotDrive, 400)); // turn 45 degrees new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) .whenPressed(new RunCommand(() -> m_robotDrive.runTurningPID(45), m_robotDrive)); diff --git a/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java b/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java new file mode 100644 index 0000000..69bf200 --- /dev/null +++ b/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java @@ -0,0 +1,70 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package frc4388.robot.commands; + +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc4388.robot.Constants.DriveConstants; +import frc4388.robot.subsystems.Drive; + +public class DriveStraightToPositionMM extends CommandBase { + Drive m_drive; + double m_targetPosIn; + double m_targetPosOut; + double m_targetGyro; + boolean isGoneFast; + + /** + * Creates a new DriveToDistancePID. + * @param subsystem drive subsystem + * @param targetPos distance to travel in inches + */ + public DriveStraightToPositionMM(Drive subsystem, double targetPos) { + // Use addRequirements() here to declare subsystem dependencies. + m_drive = subsystem; + m_targetPosIn = targetPos * DriveConstants.TICKS_PER_INCH; + addRequirements(m_drive); + //SmartDashboard.putNumber("Distance Target Inches", targetPos); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + System.err.println("PID START \n | \n |"); + m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + m_targetPosOut = m_targetPosIn + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY); + isGoneFast = false; + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + System.err.println("| \n Sensor Pos \n" + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); + System.err.println("Sensor Error \n" + m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); + System.err.println("Sensor Target \n" + m_drive.m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN)); + m_drive.runMotionMagicPID(m_targetPosOut, m_targetGyro); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + if (Math.abs((int)m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY)) < 5 && isGoneFast){ + return true; + } else { + if (m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY) > 100) { + isGoneFast = true; + } + return false; + } + } +} diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index faf161e..2f4c2e0 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -7,6 +7,7 @@ package frc4388.robot.subsystems; +import com.ctre.phoenix.motorcontrol.ControlMode; import com.ctre.phoenix.motorcontrol.DemandType; import com.ctre.phoenix.motorcontrol.FeedbackDevice; import com.ctre.phoenix.motorcontrol.FollowerType; @@ -100,6 +101,15 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.config_kD(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_MOTION_MAGIC, DriveConstants.PID_PRIMARY); + m_rightFrontMotor.config_kF(DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.config_kP(DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.config_kI(DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.config_kD(DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configMotionCruiseVelocity(DriveConstants.DRIVE_CRUISE_VELOCITY, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configMotionAcceleration(DriveConstants.DRIVE_ACCELERATION, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configMotionSCurveStrength(0, DriveConstants.DRIVE_TIMEOUT_MS); + /* Setup Sensors for WPI_TalonFXs */ m_leftFrontMotor.setSelectedSensorPosition(0, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.setSelectedSensorPosition(0, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS); @@ -321,7 +331,7 @@ public class Drive extends SubsystemBase { } /** - * Runs a position PID while driving straight (has not been tested) + * Runs a position PID while driving straight * @param targetPos The position to drive to in units * @param targetGyro The angle to drive at in units */ @@ -329,7 +339,6 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); - targetPos *= 1; m_rightFrontMotor.set(TalonFXControlMode.Position, targetPos, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); @@ -344,8 +353,6 @@ public class Drive extends SubsystemBase { public void runDriveStraightVelocityPID(double targetVel, double targetGyro) { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); - - targetVel *= 2; m_rightFrontMotor.set(TalonFXControlMode.Velocity, targetVel, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); @@ -360,10 +367,10 @@ public class Drive extends SubsystemBase { public void runMotionMagicPID(double targetPos, double targetGyro){ m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_MOTION_MAGIC, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); - - m_rightFrontMotor.set(TalonFXControlMode.MotionMagic, targetPos, DemandType.AuxPID, targetGyro); + + m_rightFrontMotor.set(ControlMode.MotionMagic, targetPos, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); - + m_driveTrain.feedWatchdog(); } From 71bd46cc8518c4e9bf3bd70d2213098d21f52f79 Mon Sep 17 00:00:00 2001 From: keenandbuckley Date: Sat, 8 Feb 2020 09:27:40 -0700 Subject: [PATCH 3/4] Tested Motion Magic and commented out unnecessary data prints --- src/main/java/frc4388/robot/RobotContainer.java | 2 +- .../frc4388/robot/commands/DriveStraightToPositionMM.java | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index f343dbb..2e159df 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -75,7 +75,7 @@ public class RobotContainer { .whenReleased(new InstantCommand(() -> System.out.print("Gamer"), m_robotDrive)); // resets the yaw of the pigeon new JoystickButton(getDriverJoystick(), XboxController.X_BUTTON) - .whenPressed(new DriveStraightToPositionMM(m_robotDrive, 400)); + .whenPressed(new DriveStraightToPositionMM(m_robotDrive, 72)); // turn 45 degrees new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) .whenPressed(new RunCommand(() -> m_robotDrive.runTurningPID(45), m_robotDrive)); diff --git a/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java b/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java index 69bf200..259c571 100644 --- a/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java +++ b/src/main/java/frc4388/robot/commands/DriveStraightToPositionMM.java @@ -44,9 +44,9 @@ public class DriveStraightToPositionMM extends CommandBase { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - System.err.println("| \n Sensor Pos \n" + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); - System.err.println("Sensor Error \n" + m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); - System.err.println("Sensor Target \n" + m_drive.m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN)); + //System.err.println("| \n Sensor Pos \n" + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); + //System.err.println("Sensor Error \n" + m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); + //System.err.println("Sensor Target \n" + m_drive.m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN)); m_drive.runMotionMagicPID(m_targetPosOut, m_targetGyro); } From ea632f626fa95253d1df602b2a24e2b890004e50 Mon Sep 17 00:00:00 2001 From: keenandbuckley Date: Sat, 8 Feb 2020 12:37:48 -0700 Subject: [PATCH 4/4] Added DriveWithJoystickAuxPID Has been tested, does work but it stalled a falcon. --- .../java/frc4388/robot/RobotContainer.java | 4 + .../robot/commands/DriveToDistanceMM.java | 60 -------------- .../commands/DriveWithJoystickAuxPID.java | 79 +++++++++++++++++++ .../java/frc4388/robot/subsystems/Drive.java | 9 +++ 4 files changed, 92 insertions(+), 60 deletions(-) delete mode 100644 src/main/java/frc4388/robot/commands/DriveToDistanceMM.java create mode 100644 src/main/java/frc4388/robot/commands/DriveWithJoystickAuxPID.java diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 2e159df..9e4f64d 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -19,6 +19,7 @@ import frc4388.robot.commands.DriveStraightAtVelocityPID; import frc4388.robot.commands.DriveStraightToPositionMM; import frc4388.robot.commands.DriveStraightToPositionPID; import frc4388.robot.commands.DriveWithJoystick; +import frc4388.robot.commands.DriveWithJoystickAuxPID; import frc4388.robot.commands.RunIntakeWithTriggers; import frc4388.robot.subsystems.Drive; import frc4388.robot.subsystems.Intake; @@ -73,6 +74,9 @@ public class RobotContainer { new JoystickButton(getDriverJoystick(), XboxController.B_BUTTON) .whenPressed(new DriveStraightAtVelocityPID(m_robotDrive, 500)) .whenReleased(new InstantCommand(() -> System.out.print("Gamer"), m_robotDrive)); + + new JoystickButton(getDriverJoystick(), XboxController.RIGHT_BUMPER_BUTTON) + .whileHeld(new DriveWithJoystickAuxPID(m_robotDrive, getDriverController())); // resets the yaw of the pigeon new JoystickButton(getDriverJoystick(), XboxController.X_BUTTON) .whenPressed(new DriveStraightToPositionMM(m_robotDrive, 72)); diff --git a/src/main/java/frc4388/robot/commands/DriveToDistanceMM.java b/src/main/java/frc4388/robot/commands/DriveToDistanceMM.java deleted file mode 100644 index 625e522..0000000 --- a/src/main/java/frc4388/robot/commands/DriveToDistanceMM.java +++ /dev/null @@ -1,60 +0,0 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 FIRST. All Rights Reserved. */ -/* Open Source Software - may be modified and shared by FRC teams. The code */ -/* must be accompanied by the FIRST BSD license file in the root directory of */ -/* the project. */ -/*----------------------------------------------------------------------------*/ - -package frc4388.robot.commands; - -import edu.wpi.first.wpilibj2.command.CommandBase; -import frc4388.robot.Constants.DriveConstants; -import frc4388.robot.subsystems.Drive; - -public class DriveToDistanceMM extends CommandBase { - Drive m_drive; - double m_distance; - double m_leftTarget; - double m_rightTarget; - - /** - * Creates a new DriveToDistancePID. - * @param subsystem drive subsystem - * @param distance distance to travel in inches - */ - public DriveToDistanceMM(Drive subsystem, double distance) { - // Use addRequirements() here to declare subsystem dependencies. - m_drive = subsystem; - m_distance = distance * DriveConstants.TICKS_PER_INCH; - addRequirements(m_drive); - } - - // Called when the command is initially scheduled. - @Override - public void initialize() { - m_leftTarget = m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() + m_distance; - m_rightTarget = -(m_drive.m_rightFrontMotor.getActiveTrajectoryPosition() + m_distance); - } - - // Called every time the scheduler runs while the command is scheduled. - @Override - public void execute() { - //m_drive.runMotionMagicPID(m_drive.m_leftFrontMotor, m_leftTarget); - //m_drive.runMotionMagicPID(m_drive.m_rightFrontMotor, m_rightTarget); - } - - // Called once the command ends or is interrupted. - @Override - public void end(boolean interrupted) { - } - - // Returns true when the command should end. - @Override - public boolean isFinished() { - if (Math.abs(m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() - m_leftTarget) < 100){ - return true; - } else { - return false; - } - } -} diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickAuxPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickAuxPID.java new file mode 100644 index 0000000..2531847 --- /dev/null +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickAuxPID.java @@ -0,0 +1,79 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package frc4388.robot.commands; + +import com.ctre.phoenix.motorcontrol.TalonFXControlMode; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import edu.wpi.first.wpiutil.math.MathUtil; +import frc4388.robot.Constants.DriveConstants; +import frc4388.robot.subsystems.Drive; +import frc4388.utility.controller.IHandController; + +public class DriveWithJoystickAuxPID extends CommandBase { + Drive m_drive; + double m_targetGyro; + long lastTime; + IHandController m_controller; + + /** + * Creates a new DriveWithJoystickAuxPID. + */ + public DriveWithJoystickAuxPID(Drive subsystem, IHandController controller) { + // Use addRequirements() here to declare subsystem dependencies. + m_drive = subsystem; + m_controller = controller; + addRequirements(m_drive); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() { + m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + lastTime = System.currentTimeMillis(); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + double currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + double moveInput = m_controller.getLeftYAxis(); + double steerInput = m_controller.getRightXAxis(); + double moveOutput = 0; + long deltaTime = System.currentTimeMillis() - lastTime; + lastTime = System.currentTimeMillis(); + if (moveInput >= 0){ + moveOutput = -Math.cos(1.571*moveInput)+1; + } else { + moveOutput = Math.cos(1.571*moveInput)-1; + } + + m_targetGyro += 2 * steerInput * deltaTime; + + m_targetGyro = MathUtil.clamp(m_targetGyro, + currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/4), + currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/4)); + + m_drive.driveWithInputAux(moveOutput, m_targetGyro); + + System.err.println("Target: " + m_targetGyro); + System.err.println("Current: " + currentGyro); + System.err.println(); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 2f4c2e0..e629ab8 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -330,6 +330,15 @@ public class Drive extends SubsystemBase { m_driveTrain.arcadeDrive(move, steer); } + public void driveWithInputAux(double move, double targetGyro) { + m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); + + m_rightFrontMotor.set(TalonFXControlMode.PercentOutput, move, DemandType.AuxPID, targetGyro); + m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); + + m_driveTrain.feedWatchdog(); + } + /** * Runs a position PID while driving straight * @param targetPos The position to drive to in units