From 27824bdcfc5a069c0e6fc0544e1f22afe9bdaff1 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Mon, 10 Feb 2020 20:13:15 -0700 Subject: [PATCH 01/44] Added Odometry and Baseplate for Trajectory Need to still add Autonomous Command for actual Trajectory. --- src/main/java/frc4388/robot/Constants.java | 8 +- .../java/frc4388/robot/RobotContainer.java | 2 + .../java/frc4388/robot/subsystems/Drive.java | 298 ++++++++++++------ 3 files changed, 202 insertions(+), 106 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index f4f8c2b..00674f4 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -50,16 +50,16 @@ public final class Constants { public final static int SLOT_MOTION_MAGIC = 3; /* Drive Train Characteristics */ - public static final double TICKS_PER_MOTOR_REV = 2048*2; - public static final double MOTOR_TO_WHEEL_GEAR_RATIO = 12.5; + public static final double TICKS_PER_MOTOR_REV = 2048; + public static final double MOTOR_ROT_PER_WHEEL_ROT = 5.13; public static final double WHEEL_DIAMETER_INCHES = 6; public static final double TICKS_PER_GYRO_REV = 8192; /* Ratio Calculation */ public static final double TICK_TIME_TO_SECONDS = 0.1; public static final double SECONDS_TO_TICK_TIME = 1/TICK_TIME_TO_SECONDS; - public static final double WHEEL_TO_MOTOR_GEAR_RATIO = 1/MOTOR_TO_WHEEL_GEAR_RATIO; - public static final double TICKS_PER_WHEEL_REV = TICKS_PER_MOTOR_REV * MOTOR_TO_WHEEL_GEAR_RATIO; + public static final double WHEEL_ROT_PER_MOTOR_ROT = 1/MOTOR_ROT_PER_WHEEL_ROT; + public static final double TICKS_PER_WHEEL_REV = TICKS_PER_MOTOR_REV * MOTOR_ROT_PER_WHEEL_ROT; public static final double INCHES_PER_WHEEL_REV = WHEEL_DIAMETER_INCHES * Math.PI; public static final double TICKS_PER_INCH = TICKS_PER_WHEEL_REV/INCHES_PER_WHEEL_REV; public static final double INCHES_PER_TICK = 1/TICKS_PER_INCH; diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 4ca2bc8..0cd20ac 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -10,6 +10,8 @@ package frc4388.robot; import com.ctre.phoenix.motorcontrol.NeutralMode; import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward; +import edu.wpi.first.wpilibj.trajectory.constraint.DifferentialDriveVoltageConstraint; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.RunCommand; diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index ee725ad..a583e33 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -21,6 +21,10 @@ import com.ctre.phoenix.sensors.PigeonIMU; import com.ctre.phoenix.sensors.PigeonIMU_StatusFrame; import edu.wpi.first.wpilibj.drive.DifferentialDrive; +import edu.wpi.first.wpilibj.geometry.Pose2d; +import edu.wpi.first.wpilibj.geometry.Rotation2d; +import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry; +import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -49,6 +53,8 @@ public class Drive extends SubsystemBase { public static Gains m_gainsTurning = DriveConstants.DRIVE_TURNING_GAINS; public static Gains m_gainsMotionMagic = DriveConstants.DRIVE_MOTION_MAGIC_GAINS; + public final DifferentialDriveOdometry m_odometry; + /** * Add your docs here. */ @@ -61,6 +67,8 @@ public class Drive extends SubsystemBase { m_pigeon.configFactoryDefault(); resetGyroYaw(); + m_odometry = new DifferentialDriveOdometry(Rotation2d.fromDegrees(getHeading())); + /* set back motors as followers */ m_leftBackMotor.follow(m_leftFrontMotor); m_rightBackMotor.follow(m_rightFrontMotor); @@ -69,7 +77,8 @@ public class Drive extends SubsystemBase { /* deadbands */ m_leftBackMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // DO NOT CHANGE - m_rightBackMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); //Ensures motors run at the same speed + m_rightBackMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // Ensures motors run at the same + // speed /* flip input so forward becomes back, etc */ m_leftFrontMotor.setInverted(false); @@ -78,148 +87,154 @@ public class Drive extends SubsystemBase { m_leftBackMotor.setInverted(InvertType.FollowMaster); m_rightBackMotor.setInverted(InvertType.FollowMaster); - m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); m_rightFrontMotor.config_kF(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kP(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kD(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kPeakOutput, + DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); m_rightFrontMotor.config_kF(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kP(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kD(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); - + m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kPeakOutput, + DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY); m_rightFrontMotor.config_kF(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kP(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); 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.configClosedLoopPeakOutput(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kPeakOutput, + 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); + resetEncoders(); /* Configure the left Talon's selected sensor as local QuadEncoder */ - m_leftFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.IntegratedSensor, // Local Feedback Source - DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] - DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout - - /*m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.IntegratedSensor, // Local Feedback Source - DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] - DriveConstants.DRIVE_TIMEOUT_MS);*/ // Configuration Timeout + m_leftFrontMotor.configSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor, // Local Feedback Source + DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] + DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout - /* Configure the Remote Talon's selected sensor as a remote sensor for the right Talon */ - m_rightFrontMotor.configRemoteFeedbackFilter( m_leftFrontMotor.getDeviceID(), // Device ID of Source - RemoteSensorSource.TalonSRX_SelectedSensor, - DriveConstants.REMOTE_0, // Source number [0, 1] - DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout + /* + * m_rightFrontMotor.configSelectedFeedbackSensor( + * FeedbackDevice.IntegratedSensor, // Local Feedback Source + * DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] + * DriveConstants.DRIVE_TIMEOUT_MS); + */ // Configuration Timeout - /* Configure the Pigeon IMU to the other Remote Slot available on the right Talon */ - m_rightFrontMotor.configRemoteFeedbackFilter( m_pigeon.getDeviceID(), - RemoteSensorSource.Pigeon_Yaw, - DriveConstants.REMOTE_1, - DriveConstants.DRIVE_TIMEOUT_MS); + /* + * Configure the Remote Talon's selected sensor as a remote sensor for the right + * Talon + */ + m_rightFrontMotor.configRemoteFeedbackFilter(m_leftFrontMotor.getDeviceID(), // Device ID of Source + RemoteSensorSource.TalonSRX_SelectedSensor, DriveConstants.REMOTE_0, // Source number [0, 1] + DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout + + /* + * Configure the Pigeon IMU to the other Remote Slot available on the right + * Talon + */ + m_rightFrontMotor.configRemoteFeedbackFilter(m_pigeon.getDeviceID(), RemoteSensorSource.Pigeon_Yaw, + DriveConstants.REMOTE_1, DriveConstants.DRIVE_TIMEOUT_MS); /* Setup Sum signal to be used for Distance */ m_rightFrontMotor.configSensorTerm(SensorTerm.Sum0, FeedbackDevice.RemoteSensor0, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configSensorTerm(SensorTerm.Sum1, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS); + 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.IntegratedSensor, + DriveConstants.DRIVE_TIMEOUT_MS); /* Configure Sum [Sum of both QuadEncoders] to be used for Primary PID Index */ - m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.SensorDifference, - DriveConstants.PID_PRIMARY, - DriveConstants.DRIVE_TIMEOUT_MS); - - /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ - m_rightFrontMotor.configSelectedFeedbackCoefficient( 1, // Coefficient - DriveConstants.PID_PRIMARY, // PID Slot of Source - DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout - - m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.RemoteSensor1, - DriveConstants.PID_TURN, - DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSelectedFeedbackSensor(FeedbackDevice.SensorDifference, DriveConstants.PID_PRIMARY, + DriveConstants.DRIVE_TIMEOUT_MS); /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ - m_rightFrontMotor.configSelectedFeedbackCoefficient( 1, - DriveConstants.PID_TURN, - DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSelectedFeedbackCoefficient(1, // Coefficient + DriveConstants.PID_PRIMARY, // PID Slot of Source + DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout + + m_rightFrontMotor.configSelectedFeedbackSensor(FeedbackDevice.RemoteSensor1, DriveConstants.PID_TURN, + DriveConstants.DRIVE_TIMEOUT_MS); /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ - m_leftFrontMotor.configSelectedFeedbackCoefficient( 1, - DriveConstants.PID_PRIMARY, - DriveConstants.DRIVE_TIMEOUT_MS); - - /* Set status frame periods to ensure we don't have stale data */ - m_rightFrontMotor.setStatusFramePeriod(StatusFrame.Status_12_Feedback1, 20, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.setStatusFramePeriod(StatusFrame.Status_13_Base_PIDF0, 20, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.setStatusFramePeriod(StatusFrame.Status_14_Turn_PIDF1, 20, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSelectedFeedbackCoefficient(1, DriveConstants.PID_TURN, DriveConstants.DRIVE_TIMEOUT_MS); + + /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ + m_leftFrontMotor.configSelectedFeedbackCoefficient(1, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS); + + /* Set status frame periods to ensure we don't have stale data */ + m_rightFrontMotor.setStatusFramePeriod(StatusFrame.Status_12_Feedback1, 20, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.setStatusFramePeriod(StatusFrame.Status_13_Base_PIDF0, 20, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.setStatusFramePeriod(StatusFrame.Status_14_Turn_PIDF1, 20, DriveConstants.DRIVE_TIMEOUT_MS); m_leftFrontMotor.setStatusFramePeriod(StatusFrame.Status_2_Feedback0, 5, DriveConstants.DRIVE_TIMEOUT_MS); m_pigeon.setStatusFramePeriod(PigeonIMU_StatusFrame.CondStatus_9_SixDeg_YPR, 5, DriveConstants.DRIVE_TIMEOUT_MS); /* Smart Dashboard Initial Values */ - /* Set up Chooser */ + /* Set up Chooser */ m_chooser.setDefaultOption("Distance PID", m_gainsDistance); - //setDriveTrainGains("Distance PID", m_gainsDistance); + // setDriveTrainGains("Distance PID", m_gainsDistance); m_chooser.addOption("Velocity PID", m_gainsVelocity); - //setDriveTrainGains("Velocity PID", m_gainsVelocity); + // setDriveTrainGains("Velocity PID", m_gainsVelocity); m_chooser.addOption("Turning PID", m_gainsTurning); - //setDriveTrainGains("Turning PID", m_gainsTurning); + // setDriveTrainGains("Turning PID", m_gainsTurning); m_chooser.addOption("Motion Magic PID", m_gainsMotionMagic); - //setDriveTrainGains("Motion Magic PID", m_gainsMotionMagic); + // setDriveTrainGains("Motion Magic PID", m_gainsMotionMagic); Shuffleboard.getTab("PID").add(m_chooser); - /* Gyro */ + /* Gyro */ SmartDashboard.putNumber("Pigeon Yaw", getGyroYaw()); SmartDashboard.putNumber("Pigeon Pitch", getGyroPitch()); SmartDashboard.putNumber("Pigeon Roll", getGyroRoll()); - /* Sensor Values */ + /* Sensor Values */ SmartDashboard.putNumber("Left Motor Velocity Raw", m_leftFrontMotor.getSelectedSensorVelocity(0)); SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition(0)); SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition()); - /* PID */ + /* PID */ Gains gains = m_chooser.getSelected(); Shuffleboard.getTab("PID").add("P Value Drive", gains.m_kP); Shuffleboard.getTab("PID").add("I Value Drive", gains.m_kI); Shuffleboard.getTab("PID").add("D Value Drive", gains.m_kD); Shuffleboard.getTab("PID").add("F Value Drive", gains.m_kF); - - /** - * Max out the peak output (for all modes). - * However you can limit the output of a given PID object with configClosedLoopPeakOutput(). - */ - m_leftFrontMotor.configPeakOutputForward(+1, DriveConstants.DRIVE_TIMEOUT_MS); - m_leftFrontMotor.configPeakOutputReverse(-1, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configPeakOutputForward(+1, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configPeakOutputReverse(-1, DriveConstants.DRIVE_TIMEOUT_MS); + /** + * Max out the peak output (for all modes). However you can limit the output of + * a given PID object with configClosedLoopPeakOutput(). + */ + m_leftFrontMotor.configPeakOutputForward(+1, DriveConstants.DRIVE_TIMEOUT_MS); + m_leftFrontMotor.configPeakOutputReverse(-1, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configPeakOutputForward(+1, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configPeakOutputReverse(-1, DriveConstants.DRIVE_TIMEOUT_MS); /** - * 1ms per loop. PID loop can be slowed down if need be. - * For example, - * - if sensor updates are too slow - * - sensor deltas are very small per update, so derivative error never gets large enough to be useful. - * - sensor movement is very slow causing the derivative error to be near zero. - */ + * 1ms per loop. PID loop can be slowed down if need be. For example, - if + * sensor updates are too slow - sensor deltas are very small per update, so + * derivative error never gets large enough to be useful. - sensor movement is + * very slow causing the derivative error to be near zero. + */ int closedLoopTimeMs = 1; - m_rightFrontMotor.configClosedLoopPeriod(DriveConstants.PID_PRIMARY, closedLoopTimeMs, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeriod(DriveConstants.PID_TURN, closedLoopTimeMs, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configClosedLoopPeriod( DriveConstants.PID_PRIMARY, + closedLoopTimeMs, + DriveConstants.DRIVE_TIMEOUT_MS); + + m_rightFrontMotor.configClosedLoopPeriod( DriveConstants.PID_TURN, + closedLoopTimeMs, + DriveConstants.DRIVE_TIMEOUT_MS); /** - * configAuxPIDPolarity(boolean invert, int timeoutMs) - * false means talon's local output is PID0 + PID1, and other side Talon is PID0 - PID1 - * true means talon's local output is PID0 - PID1, and other side Talon is PID0 + PID1 - */ + * configAuxPIDPolarity(boolean invert, int timeoutMs) false means talon's local + * output is PID0 + PID1, and other side Talon is PID0 - PID1 true means talon's + * local output is PID0 - PID1, and other side Talon is PID0 + PID1 + */ m_rightFrontMotor.configAuxPIDPolarity(false, DriveConstants.DRIVE_TIMEOUT_MS); } @@ -234,8 +249,10 @@ public class Drive extends SubsystemBase { SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition()); SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition(0)); - SmartDashboard.putNumber("Right Motor Velocity Int Sensor", m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); - SmartDashboard.putNumber("Left Motor Velocity Int Sensor", m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + SmartDashboard.putNumber("Right Motor Velocity Int Sensor", + m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + SmartDashboard.putNumber("Left Motor Velocity Int Sensor", + m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); SmartDashboard.putNumber("Right Front Motor Current", m_rightFrontMotor.getSupplyCurrent()); SmartDashboard.putNumber("Left Front Motor Current", m_leftFrontMotor.getSupplyCurrent()); @@ -251,12 +268,18 @@ public class Drive extends SubsystemBase { } catch (Exception e) { System.err.println("Error in the Drive Subsystem"); - //e.printStackTrace(System.err); + // e.printStackTrace(System.err); } + + m_odometry.update(Rotation2d.fromDegrees(getHeading()), + m_leftFrontMotor.getSensorCollection().getIntegratedSensorPosition(), + m_rightFrontMotor.getSensorCollection().getIntegratedSensorPosition()); + } /** * Sets Motors to a NeutralMode. + * * @param mode NeutralMode to set motors to */ public void setDriveTrainNeutralMode(NeutralMode mode) { @@ -268,10 +291,12 @@ public class Drive extends SubsystemBase { /** * Initializes the drive train gains kP, kI, kD, and kF - * @param slot Either "Distance PID", "Velocity PID", "Motion Magic PID", or "Turning PID" + * + * @param slot Either "Distance PID", "Velocity PID", "Motion Magic PID", or + * "Turning PID" * @param gains A gains object which is the gains that are set for the slot */ - public void setDriveTrainGains(String slot, Gains gains){ + public void setDriveTrainGains(String slot, Gains gains) { /* Distance */ if (slot.equals("Distance PID")) { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY); @@ -288,7 +313,8 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.config_kP(DriveConstants.SLOT_VELOCITY, gains.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_VELOCITY, gains.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kD(DriveConstants.SLOT_VELOCITY, gains.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, gains.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, gains.m_kPeakOutput, + DriveConstants.DRIVE_TIMEOUT_MS); } /* Turning */ if (slot.equals("Turning PID")) { @@ -297,7 +323,8 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.config_kP(DriveConstants.SLOT_TURNING, gains.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_TURNING, gains.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kD(DriveConstants.SLOT_TURNING, gains.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_TURNING, gains.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_TURNING, gains.m_kPeakOutput, + DriveConstants.DRIVE_TIMEOUT_MS); } /* Motion Magic */ @@ -307,8 +334,9 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.config_kP(DriveConstants.SLOT_MOTION_MAGIC, gains.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_MOTION_MAGIC, gains.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kD(DriveConstants.SLOT_MOTION_MAGIC, gains.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - - m_rightFrontMotor.configMotionCruiseVelocity(DriveConstants.DRIVE_CRUISE_VELOCITY, 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); } } @@ -316,13 +344,14 @@ public class Drive extends SubsystemBase { /** * Add your docs here. */ - public void driveWithInput(double move, double steer){ + public void driveWithInput(double move, double steer) { m_driveTrain.arcadeDrive(move, steer); } /** * Runs a position PID while driving straight (has not been tested) - * @param targetPos The position to drive to in units + * + * @param targetPos The position to drive to in units * @param targetGyro The angle to drive at in units */ public void runDriveStraightPositionPID(double targetPos, double targetGyro) { @@ -338,7 +367,8 @@ public class Drive extends SubsystemBase { /** * Runs velocity PID while driving straight - * @param targetVel The velocity to drive at in units + * + * @param targetVel The velocity to drive at in units * @param targetGyro The angle to drive at in units */ public void runDriveStraightVelocityPID(double targetVel, double targetGyro) { @@ -354,26 +384,28 @@ public class Drive extends SubsystemBase { /** * Runs motion magic PID while driving straight (has not been tested) - * @param targetPos The position to drive to in units + * + * @param targetPos The position to drive to in units * @param targetGyro The angle to drive at in units */ - public void runMotionMagicPID(double targetPos, double targetGyro){ + 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_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); - + m_driveTrain.feedWatchdog(); } /** * Runs a Turning PID to rotate a to a target angle + * * @param targetAngle target angle in degrees */ - public void runTurningPID(double targetAngle){ - double targetGyro = (targetAngle/360)*DriveConstants.TICKS_PER_GYRO_REV; - + public void runTurningPID(double targetAngle) { + double targetGyro = (targetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV; + runDriveStraightVelocityPID(0, targetGyro); } @@ -382,7 +414,7 @@ public class Drive extends SubsystemBase { */ public double getGyroYaw() { double[] ypr = new double[3]; - + m_pigeon.getYawPitchRoll(ypr); return ypr[0]; } @@ -392,7 +424,7 @@ public class Drive extends SubsystemBase { */ public double getGyroPitch() { double[] ypr = new double[3]; - + m_pigeon.getYawPitchRoll(ypr); return ypr[1]; } @@ -402,7 +434,7 @@ public class Drive extends SubsystemBase { */ public double getGyroRoll() { double[] ypr = new double[3]; - + m_pigeon.getYawPitchRoll(ypr); return ypr[2]; } @@ -414,4 +446,66 @@ public class Drive extends SubsystemBase { m_pigeon.setYaw(0); m_pigeon.setAccumZAngle(0); } -} + + /** + * Returns the heading of the robot + * + * @return The robot's heading in degrees, from -180 to 180 + */ + public double getHeading() { + return Math.IEEEremainder(getGyroYaw(), 360); + } + + /** + * Returns the currently-estimated pose of the robot. + * @return The pose. + */ + public Pose2d getPose() { + return m_odometry.getPoseMeters(); + } + + /** + * Returns current wheel speeds of robot. + * @return The current wheel speeds. + */ + public DifferentialDriveWheelSpeeds getWheelSpeeds() { + return new DifferentialDriveWheelSpeeds( m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity(), + m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + } + + /** + * Resets the encoders for both motors. + */ + public void resetEncoders() { + m_leftFrontMotor.getSensorCollection().setIntegratedSensorPosition(0, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.getSensorCollection().setIntegratedSensorPosition(0, DriveConstants.DRIVE_TIMEOUT_MS); + } + + /** + * Resets the odometry to the specified pose. + * + * @param pose The pose to which to set the odometry. + */ + public void setOdometry(Pose2d pose) { + resetEncoders(); + m_odometry.resetPosition(pose, Rotation2d.fromDegrees(getHeading())); + } + + /** + * Gets the encoder value (position) of a motor + * @param falcon The motor to get the position of + * @return The position of the motor in inches + */ + public double getDistanceInches(WPI_TalonFX falcon) { + return ticksToInches(falcon.getSensorCollection().getIntegratedSensorPosition()); + } + + /** + * Converts a value in ticks to inches. + * @param ticks The value in ticks to convert + * @return The converted value in inches + */ + public double ticksToInches(double ticks) { + return ticks * DriveConstants.INCHES_PER_TICK; + } +} \ No newline at end of file From 0e5427cb60ff80eb2d5409e5fd8cdc401309477a Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Tue, 11 Feb 2020 16:03:25 -0700 Subject: [PATCH 02/44] Added Trajectory Command Need to figure out how to make it work --- .../java/frc4388/robot/RobotContainer.java | 59 ++++++++++++++++++- .../java/frc4388/robot/subsystems/Drive.java | 6 ++ 2 files changed, 64 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 0cd20ac..8daeb93 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -7,13 +7,24 @@ package frc4388.robot; +import java.util.List; + import com.ctre.phoenix.motorcontrol.NeutralMode; import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.controller.PIDController; +import edu.wpi.first.wpilibj.controller.RamseteController; import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward; +import edu.wpi.first.wpilibj.geometry.Pose2d; +import edu.wpi.first.wpilibj.geometry.Rotation2d; +import edu.wpi.first.wpilibj.geometry.Translation2d; +import edu.wpi.first.wpilibj.trajectory.Trajectory; +import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig; +import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator; import edu.wpi.first.wpilibj.trajectory.constraint.DifferentialDriveVoltageConstraint; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.RamseteCommand; import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.button.JoystickButton; import frc4388.robot.Constants.*; @@ -121,7 +132,53 @@ public class RobotContainer { */ public Command getAutonomousCommand() { // no auto - return new InstantCommand(); + var autoVoltageConstraint = + new DifferentialDriveVoltageConstraint( + new SimpleMotorFeedforward( DriveConstants.ksVolts, + DriveConstants.kvVoltSecondsPerMeter, + DriveConstants.kaVoltSecondsSquaredPerMeter), + DriveConstants.kDriveKinematics, + 10); + + TrajectoryConfig config = + new TrajectoryConfig( DriveConstants.kMaxSpeedMetersPerSecond, + DriveConstants.kMaxAccelerationMetersPerSecondSquared) + + .setKinematics(DriveConstants.kDriveKinematics) + + .addConstraint(autoVoltageConstraint); + + Trajectory exampleTrajectory = TrajectoryGenerator.generateTrajectory( + + new Pose2d(0, 0, new Rotation2d(0)), + + List.of( + new Translation2d(1, 1), + new Translation2d(2, -1) + ), + + new Pose2d(3, 0, new Rotation2d(0)), + + config + ); + + RamseteCommand ramseteCommand = new RamseteCommand( + exampleTrajectory, + m_robotDrive::getPose, + new RamseteController(DriveConstants.kRamseteB, DriveConstants.kRamseteZeta), + new SimpleMotorFeedforward( DriveConstants.ksVolts, + DriveConstants.kvVoltSecondsPerMeter, + DriveConstants.kaVoltSecondsSquaredPerMeter), + DriveConstants.kDriveKinematics, + m_robotDrive::getWheelSpeeds, + new PIDController(DriveConstants.kPDriveVel, 0, 0), + new PIDController(DriveConstants.kPDriveVel, 0, 0), + + m_robotDrive::tankDriveVolts, + m_robotDrive + ); + + return ramseteCommand.andThen(() -> m_robotDrive.tankDriveVolts(0, 0)); } /** diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index a583e33..3d4cd7b 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -508,4 +508,10 @@ public class Drive extends SubsystemBase { public double ticksToInches(double ticks) { return ticks * DriveConstants.INCHES_PER_TICK; } + + public void tankDriveVolts(double leftVolts, double rightVolts) { + m_leftFrontMotor.setVoltage(leftVolts); + m_rightFrontMotor.setVoltage(-rightVolts); + m_driveTrain.feedWatchdog(); + } } \ No newline at end of file From 80868d1fd7704393bd3abfdbaf3be2247157f301 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Wed, 12 Feb 2020 21:00:54 -0700 Subject: [PATCH 03/44] Fix build error from merge --- src/main/java/frc4388/robot/subsystems/Drive.java | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index e14a238..02d1e3f 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -375,6 +375,10 @@ public class Drive extends SubsystemBase { m_driveTrain.feedWatchdog(); } + /** + * Runs position PID while driving straight. + * Position is absolute and displacement should be handled on the command side. + * @param targetPos The position to drive to in units * @param targetGyro The angle to drive at in units */ public void runDriveStraightPositionPID(double targetPos, double targetGyro) { From bff9793caf514b67dbc26c9d25f1ac6eaea7884f Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Wed, 12 Feb 2020 21:32:33 -0700 Subject: [PATCH 04/44] Fix odometry to use meters as units --- src/main/java/frc4388/robot/Constants.java | 1 + .../java/frc4388/robot/subsystems/Drive.java | 30 ++++++++++++++----- 2 files changed, 24 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 0e614cb..34eecf2 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -63,6 +63,7 @@ public final class Constants { public static final double INCHES_PER_WHEEL_REV = WHEEL_DIAMETER_INCHES * Math.PI; public static final double TICKS_PER_INCH = TICKS_PER_WHEEL_REV/INCHES_PER_WHEEL_REV; public static final double INCHES_PER_TICK = 1/TICKS_PER_INCH; + public static final double INCHES_PER_METER = 39.370; } public static final class IntakeConstants { diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 02d1e3f..103a4a2 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -283,10 +283,9 @@ public class Drive extends SubsystemBase { // e.printStackTrace(System.err); } - m_odometry.update(Rotation2d.fromDegrees(getHeading()), - m_leftFrontMotor.getSensorCollection().getIntegratedSensorPosition(), - m_rightFrontMotor.getSensorCollection().getIntegratedSensorPosition()); - + m_odometry.update(Rotation2d.fromDegrees( getHeading()), + inchesToMeters(getDistanceInches(m_leftFrontMotor)), + inchesToMeters(getDistanceInches(m_rightFrontMotor))); } /** @@ -472,7 +471,6 @@ public class Drive extends SubsystemBase { /** * Returns the heading of the robot - * * @return The robot's heading in degrees, from -180 to 180 */ public double getHeading() { @@ -492,8 +490,8 @@ public class Drive extends SubsystemBase { * @return The current wheel speeds. */ public DifferentialDriveWheelSpeeds getWheelSpeeds() { - return new DifferentialDriveWheelSpeeds( m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity(), - m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + return new DifferentialDriveWheelSpeeds( inchesToMeters(getVelocityInchesPerSecond(m_leftFrontMotor)), + inchesToMeters(getVelocityInchesPerSecond(m_rightFrontMotor))); } /** @@ -523,6 +521,15 @@ public class Drive extends SubsystemBase { return ticksToInches(falcon.getSensorCollection().getIntegratedSensorPosition()); } + /** + * Gets the encoder value (velocity) of a motor + * @param falcon The motor to get the velocity of + * @return The velocity of the motor in inches per second + */ + public double getVelocityInchesPerSecond(WPI_TalonFX falcon) { + return ticksToInches(falcon.getSensorCollection().getIntegratedSensorPosition()/DriveConstants.TICK_TIME_TO_SECONDS); + } + /** * Converts a value in ticks to inches. * @param ticks The value in ticks to convert @@ -531,6 +538,15 @@ public class Drive extends SubsystemBase { public double ticksToInches(double ticks) { return ticks * DriveConstants.INCHES_PER_TICK; } + + /** + * Converts a value in inches to meters. + * @param inches The value in inches to convert + * @return The converted value in meters + */ + public double inchesToMeters(double inches) { + return inches / DriveConstants.INCHES_PER_METER; + } /* * Set to high or low gear based on boolean state, true = high, false = low From e8a00f533bc1b91d2b7345ef2969cba99b7035cf Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Wed, 12 Feb 2020 21:42:48 -0700 Subject: [PATCH 05/44] Cleanup SmartDashboard and Motor Setup --- .../java/frc4388/robot/subsystems/Drive.java | 88 +++++++++---------- 1 file changed, 40 insertions(+), 48 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 103a4a2..47e5f3f 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -98,30 +98,28 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.config_kP(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kD(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kPeakOutput, - DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); m_rightFrontMotor.config_kF(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kP(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kD(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kPeakOutput, - DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY); m_rightFrontMotor.config_kF(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kP(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kI(DriveConstants.SLOT_DISTANCE, m_gainsDistance.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); 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.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.configClosedLoopPeakOutput( DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kPeakOutput, 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); @@ -130,52 +128,44 @@ public class Drive extends SubsystemBase { resetEncoders(); /* Configure the left Talon's selected sensor as local QuadEncoder */ - m_leftFrontMotor.configSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor, // Local Feedback Source - DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] - DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout - - /* - * m_rightFrontMotor.configSelectedFeedbackSensor( - * FeedbackDevice.IntegratedSensor, // Local Feedback Source - * DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] - * DriveConstants.DRIVE_TIMEOUT_MS); - */ // Configuration Timeout + m_leftFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.IntegratedSensor, // Local Feedback Source + DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] + DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout /* * Configure the Remote Talon's selected sensor as a remote sensor for the right * Talon */ - m_rightFrontMotor.configRemoteFeedbackFilter(m_leftFrontMotor.getDeviceID(), // Device ID of Source - RemoteSensorSource.TalonSRX_SelectedSensor, DriveConstants.REMOTE_0, // Source number [0, 1] - DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout + m_rightFrontMotor.configRemoteFeedbackFilter( m_leftFrontMotor.getDeviceID(), // Device ID of Source + RemoteSensorSource.TalonSRX_SelectedSensor, DriveConstants.REMOTE_0, // Source number [0, 1] + DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout /* * Configure the Pigeon IMU to the other Remote Slot available on the right * Talon */ - m_rightFrontMotor.configRemoteFeedbackFilter(m_pigeon.getDeviceID(), RemoteSensorSource.Pigeon_Yaw, - DriveConstants.REMOTE_1, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configRemoteFeedbackFilter( m_pigeon.getDeviceID(), RemoteSensorSource.Pigeon_Yaw, + DriveConstants.REMOTE_1, DriveConstants.DRIVE_TIMEOUT_MS); /* Setup Sum signal to be used for Distance */ m_rightFrontMotor.configSensorTerm(SensorTerm.Sum0, FeedbackDevice.RemoteSensor0, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configSensorTerm(SensorTerm.Sum1, FeedbackDevice.IntegratedSensor, - DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSensorTerm(SensorTerm.Sum1, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS); /* Diff Signal */ 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, DriveConstants.PID_PRIMARY, - DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.SensorDifference, DriveConstants.PID_PRIMARY, + DriveConstants.DRIVE_TIMEOUT_MS); /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ - m_rightFrontMotor.configSelectedFeedbackCoefficient(1, // Coefficient - DriveConstants.PID_PRIMARY, // PID Slot of Source - DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout + m_rightFrontMotor.configSelectedFeedbackCoefficient( 1, // Coefficient + DriveConstants.PID_PRIMARY, // PID Slot of Source + DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout - m_rightFrontMotor.configSelectedFeedbackSensor(FeedbackDevice.RemoteSensor1, DriveConstants.PID_TURN, - DriveConstants.DRIVE_TIMEOUT_MS); + m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.RemoteSensor1, DriveConstants.PID_TURN, + DriveConstants.DRIVE_TIMEOUT_MS); /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ m_rightFrontMotor.configSelectedFeedbackCoefficient(1, DriveConstants.PID_TURN, DriveConstants.DRIVE_TIMEOUT_MS); @@ -256,27 +246,29 @@ public class Drive extends SubsystemBase { public void periodic() { try { SmartDashboard.putNumber("Pigeon Yaw", getGyroYaw()); - SmartDashboard.putNumber("Pigeon Pitch", getGyroPitch()); - SmartDashboard.putNumber("Pigeon Roll", getGyroRoll()); + //SmartDashboard.putNumber("Pigeon Pitch", getGyroPitch()); + //SmartDashboard.putNumber("Pigeon Roll", getGyroRoll()); - SmartDashboard.putNumber("Left Motor Velocity Raw", m_leftFrontMotor.getSelectedSensorVelocity(0)); - SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); - SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition()); - SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition(0)); - SmartDashboard.putNumber("Right Motor Velocity Int Sensor", m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); - SmartDashboard.putNumber("Left Motor Velocity Int Sensor", m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + //SmartDashboard.putNumber("Left Motor Velocity Raw", m_leftFrontMotor.getSelectedSensorVelocity(0)); + //SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); + //SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition()); + //SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition(0)); + //SmartDashboard.putNumber("Right Motor Velocity Int Sensor", m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + //SmartDashboard.putNumber("Left Motor Velocity Int Sensor", m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); - SmartDashboard.putNumber("Right Front Motor Current", m_rightFrontMotor.getSupplyCurrent()); - SmartDashboard.putNumber("Left Front Motor Current", m_leftFrontMotor.getSupplyCurrent()); - SmartDashboard.putNumber("Right Back Motor Current", m_rightFrontMotor.getSupplyCurrent()); - SmartDashboard.putNumber("Left Back Motor Current", m_leftFrontMotor.getSupplyCurrent()); + //SmartDashboard.putNumber("Right Front Motor Current", m_rightFrontMotor.getSupplyCurrent()); + //SmartDashboard.putNumber("Left Front Motor Current", m_leftFrontMotor.getSupplyCurrent()); + //SmartDashboard.putNumber("Right Back Motor Current", m_rightFrontMotor.getSupplyCurrent()); + //SmartDashboard.putNumber("Left Back Motor Current", m_leftFrontMotor.getSupplyCurrent()); - SmartDashboard.putNumber("PID 0 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); - SmartDashboard.putNumber("PID 1 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); - SmartDashboard.putNumber("PID 0 Target", m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_PRIMARY)); - SmartDashboard.putNumber("PID 1 Target", m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN)); - SmartDashboard.putNumber("PID 0 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY)); - SmartDashboard.putNumber("PID 1 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); + //SmartDashboard.putNumber("PID 0 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); + //SmartDashboard.putNumber("PID 1 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); + //SmartDashboard.putNumber("PID 0 Target", m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_PRIMARY)); + //SmartDashboard.putNumber("PID 1 Target", m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN)); + //SmartDashboard.putNumber("PID 0 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY)); + //SmartDashboard.putNumber("PID 1 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); + + SmartDashboard.putString("Odometry Values", getPose().toString()); } catch (Exception e) { System.err.println("Error in the Drive Subsystem"); From f7782c8acd5dda7d1f1fe10f340c2c89dd3fc0c5 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Wed, 12 Feb 2020 21:46:38 -0700 Subject: [PATCH 06/44] Remove unused Smartdashboard PID Tuner --- .../java/frc4388/robot/subsystems/Drive.java | 82 ++----------------- 1 file changed, 6 insertions(+), 76 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 47e5f3f..cab720d 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -182,34 +182,16 @@ public class Drive extends SubsystemBase { /* Smart Dashboard Initial Values */ - /* Set up Chooser */ - m_chooser.setDefaultOption("Distance PID", m_gainsDistance); - // setDriveTrainGains("Distance PID", m_gainsDistance); - m_chooser.addOption("Velocity PID", m_gainsVelocity); - // setDriveTrainGains("Velocity PID", m_gainsVelocity); - m_chooser.addOption("Turning PID", m_gainsTurning); - // setDriveTrainGains("Turning PID", m_gainsTurning); - m_chooser.addOption("Motion Magic PID", m_gainsMotionMagic); - // setDriveTrainGains("Motion Magic PID", m_gainsMotionMagic); - Shuffleboard.getTab("PID").add(m_chooser); - /* Gyro */ SmartDashboard.putNumber("Pigeon Yaw", getGyroYaw()); - SmartDashboard.putNumber("Pigeon Pitch", getGyroPitch()); - SmartDashboard.putNumber("Pigeon Roll", getGyroRoll()); + //SmartDashboard.putNumber("Pigeon Pitch", getGyroPitch()); + //SmartDashboard.putNumber("Pigeon Roll", getGyroRoll()); /* Sensor Values */ - SmartDashboard.putNumber("Left Motor Velocity Raw", m_leftFrontMotor.getSelectedSensorVelocity(0)); - SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); - SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition(0)); - SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition()); - - /* PID */ - Gains gains = m_chooser.getSelected(); - Shuffleboard.getTab("PID").add("P Value Drive", gains.m_kP); - Shuffleboard.getTab("PID").add("I Value Drive", gains.m_kI); - Shuffleboard.getTab("PID").add("D Value Drive", gains.m_kD); - Shuffleboard.getTab("PID").add("F Value Drive", gains.m_kF); + //SmartDashboard.putNumber("Left Motor Velocity Raw", m_leftFrontMotor.getSelectedSensorVelocity(0)); + //SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); + //SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition(0)); + //SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition()); /** * Max out the peak output (for all modes). However you can limit the output of @@ -292,58 +274,6 @@ public class Drive extends SubsystemBase { m_rightBackMotor.setNeutralMode(mode); } - /** - * Initializes the drive train gains kP, kI, kD, and kF - * - * @param slot Either "Distance PID", "Velocity PID", "Motion Magic PID", or - * "Turning PID" - * @param gains A gains object which is the gains that are set for the slot - */ - public void setDriveTrainGains(String slot, Gains gains) { - /* Distance */ - if (slot.equals("Distance PID")) { - m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY); - m_rightFrontMotor.config_kF(DriveConstants.SLOT_DISTANCE, gains.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kP(DriveConstants.SLOT_DISTANCE, gains.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kI(DriveConstants.SLOT_DISTANCE, gains.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kD(DriveConstants.SLOT_DISTANCE, gains.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - } - - /* Velocity */ - if (slot.equals("Velocity PID")) { - m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); - m_rightFrontMotor.config_kF(DriveConstants.SLOT_VELOCITY, gains.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kP(DriveConstants.SLOT_VELOCITY, gains.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kI(DriveConstants.SLOT_VELOCITY, gains.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kD(DriveConstants.SLOT_VELOCITY, gains.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, gains.m_kPeakOutput, - DriveConstants.DRIVE_TIMEOUT_MS); - } - /* Turning */ - if (slot.equals("Turning PID")) { - m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); - m_rightFrontMotor.config_kF(DriveConstants.SLOT_TURNING, gains.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kP(DriveConstants.SLOT_TURNING, gains.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kI(DriveConstants.SLOT_TURNING, gains.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kD(DriveConstants.SLOT_TURNING, gains.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_TURNING, gains.m_kPeakOutput, - DriveConstants.DRIVE_TIMEOUT_MS); - } - - /* Motion Magic */ - if (slot.equals("Motion Magic PID")) { - m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_MOTION_MAGIC, DriveConstants.PID_PRIMARY); - m_rightFrontMotor.config_kF(DriveConstants.SLOT_MOTION_MAGIC, gains.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kP(DriveConstants.SLOT_MOTION_MAGIC, gains.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kI(DriveConstants.SLOT_MOTION_MAGIC, gains.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kD(DriveConstants.SLOT_MOTION_MAGIC, gains.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); - } - } - /** * Runs percent output control on the moving and steering of the drive train, * using the Differential Drive class to manage the two inputs From 3a40b44ff6a83de9f26338cfbc3d25fae38102d5 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Wed, 12 Feb 2020 22:15:50 -0700 Subject: [PATCH 07/44] Setup Turn Rate and Constants to be used in Ramsete --- src/main/java/frc4388/robot/Constants.java | 7 ++++++ .../java/frc4388/robot/subsystems/Drive.java | 25 ++++++++++++++++++- 2 files changed, 31 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 34eecf2..35672cc 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -7,6 +7,7 @@ package frc4388.robot; +import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics; import frc4388.utility.LEDPatterns; /** @@ -35,6 +36,12 @@ public final class Constants { public static final int DRIVE_CRUISE_VELOCITY = 20000; public static final int DRIVE_ACCELERATION = 7000; + /* Trajectory Constants */ + public static final double kMaxSpeedMetersPerSecond = 3; + public static final double kMaxAccelerationMetersPerSecondSquared = 3; + public static final double kTrackwidthMeters = 0.69; ///TODO: SET THIS SOON! + public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(kTrackwidthMeters); + /* Remote Sensors */ public final static int REMOTE_0 = 0; public final static int REMOTE_1 = 1; diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index cab720d..f8fdd37 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -59,6 +59,10 @@ public class Drive extends SubsystemBase { public DoubleSolenoid speedShift; + public long m_lastTime, m_deltaTime; //in milliseconds + + public double m_lastAngleYaw, m_currentAngleYaw; + /** * Add your docs here. */ @@ -222,10 +226,17 @@ public class Drive extends SubsystemBase { * local output is PID0 - PID1, and other side Talon is PID0 + PID1 */ m_rightFrontMotor.configAuxPIDPolarity(false, DriveConstants.DRIVE_TIMEOUT_MS); + + m_lastTime = System.currentTimeMillis(); } @Override public void periodic() { + m_deltaTime = System.currentTimeMillis() - m_lastTime; + m_lastTime = System.currentTimeMillis(); + m_lastAngleYaw = m_currentAngleYaw; + m_currentAngleYaw = getGyroYaw(); + try { SmartDashboard.putNumber("Pigeon Yaw", getGyroYaw()); //SmartDashboard.putNumber("Pigeon Pitch", getGyroPitch()); @@ -250,7 +261,7 @@ public class Drive extends SubsystemBase { //SmartDashboard.putNumber("PID 0 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY)); //SmartDashboard.putNumber("PID 1 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); - SmartDashboard.putString("Odometry Values", getPose().toString()); + SmartDashboard.putString("Odometry Values Meters", getPose().toString()); } catch (Exception e) { System.err.println("Error in the Drive Subsystem"); @@ -389,6 +400,8 @@ public class Drive extends SubsystemBase { public void resetGyroYaw() { m_pigeon.setYaw(0); m_pigeon.setAccumZAngle(0); + m_lastAngleYaw = 0; + m_currentAngleYaw = 0; } /** @@ -399,6 +412,16 @@ public class Drive extends SubsystemBase { return Math.IEEEremainder(getGyroYaw(), 360); } + /** + * Returns the turn rate of the robot. + * + * @return The turn rate of the robot, in degrees per second + */ + public double getTurnRate() { + double deltaYaw = m_currentAngleYaw - m_lastAngleYaw; + return deltaYaw / (m_deltaTime/1000); + } + /** * Returns the currently-estimated pose of the robot. * @return The pose. From b466afe548d33947a5b269bd7d92ddf71ebb2b03 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Thu, 13 Feb 2020 00:28:55 -0700 Subject: [PATCH 08/44] Add Ramsete Controller and Everything Needed to Run it --- src/main/java/frc4388/robot/Robot.java | 2 + .../java/frc4388/robot/RobotContainer.java | 52 +++++++++++++++++- .../java/frc4388/robot/subsystems/Drive.java | 53 ++++++++++++++++++- 3 files changed, 104 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc4388/robot/Robot.java b/src/main/java/frc4388/robot/Robot.java index 86b1d84..b23b040 100644 --- a/src/main/java/frc4388/robot/Robot.java +++ b/src/main/java/frc4388/robot/Robot.java @@ -75,6 +75,8 @@ public class Robot extends TimedRobot { m_autonomousCommand = m_robotContainer.getAutonomousCommand(); m_robotContainer.setDriveNeutralMode(NeutralMode.Brake); + m_robotContainer.resetOdometry(); + /* * String autoSelected = SmartDashboard.getString("Auto Selector", * "Default"); switch(autoSelected) { case "My Auto": autonomousCommand diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index d77076e..408712f 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -7,13 +7,26 @@ package frc4388.robot; +import java.util.List; +import java.util.function.BiConsumer; + import com.ctre.phoenix.motorcontrol.NeutralMode; import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.controller.RamseteController; import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward; +import edu.wpi.first.wpilibj.geometry.Pose2d; +import edu.wpi.first.wpilibj.geometry.Rotation2d; +import edu.wpi.first.wpilibj.geometry.Translation2d; +import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds; +import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds; +import edu.wpi.first.wpilibj.trajectory.Trajectory; +import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig; +import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator; import edu.wpi.first.wpilibj.trajectory.constraint.DifferentialDriveVoltageConstraint; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.RamseteCommand; import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.button.JoystickButton; import frc4388.robot.Constants.*; @@ -146,14 +159,49 @@ public class RobotContainer { m_robotDrive.setDriveTrainNeutralMode(mode); } + public void resetOdometry() { + m_robotDrive.resetGyroAngles(); + m_robotDrive.setOdometry(new Pose2d()); + } + /** * Use this to pass the autonomous command to the main {@link Robot} class. * * @return the command to run in autonomous */ public Command getAutonomousCommand() { - // no auto - return new InstantCommand(); + + var wheelSpeeds = new ChassisSpeeds(); + + // Create config for trajectory + TrajectoryConfig config = new TrajectoryConfig( DriveConstants.kMaxSpeedMetersPerSecond, + DriveConstants.kMaxAccelerationMetersPerSecondSquared) + // Add kinematics to ensure max speed is actually obeyed + .setKinematics(DriveConstants.kDriveKinematics); + + Trajectory exampleTrajectory = TrajectoryGenerator.generateTrajectory( + // Start at the origin facing the +X direction + new Pose2d(0, 0, new Rotation2d(0)), + // Pass through these two interior waypoints, making an 's' curve path + List.of( + new Translation2d(1, 1), + new Translation2d(2, -1) + ), + // End 3 meters straight ahead of where we started, facing forward + new Pose2d(3, 0, new Rotation2d(0)), + // Pass config + config); + + RamseteCommand ramseteCommand = new RamseteCommand( + exampleTrajectory, + m_robotDrive::getPose, + new RamseteController(), + DriveConstants.kDriveKinematics, + m_robotDrive::tankDriveVelocity, + m_robotDrive); + + // Run path following command, then stop at the end. + return ramseteCommand.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0)); } /** diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index f8fdd37..73a358d 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -25,12 +25,14 @@ import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.geometry.Pose2d; import edu.wpi.first.wpilibj.geometry.Rotation2d; +import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry; import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpiutil.math.MathUtil; import frc4388.robot.Constants.DriveConstants; import frc4388.robot.Gains; @@ -61,7 +63,7 @@ public class Drive extends SubsystemBase { public long m_lastTime, m_deltaTime; //in milliseconds - public double m_lastAngleYaw, m_currentAngleYaw; + public double m_lastAngleYaw, m_currentAngleYaw, m_kinematicsTargetAngle; /** * Add your docs here. @@ -364,6 +366,29 @@ public class Drive extends SubsystemBase { runDriveStraightVelocityPID(0, targetGyro); } + /** + * Controls the left and right sides of the drive with velocity targets. + * + * @param leftSpeed the commanded left output + * @param rightSpeed the commanded right output + */ + public void tankDriveVelocity(double leftSpeed, double rightSpeed) { + DifferentialDriveWheelSpeeds wheelSpeeds = new DifferentialDriveWheelSpeeds(leftSpeed, rightSpeed); + ChassisSpeeds chassisSpeeds = DriveConstants.kDriveKinematics.toChassisSpeeds(wheelSpeeds); + double moveVelMPS = chassisSpeeds.vxMetersPerSecond; + double angleVelRad = chassisSpeeds.omegaRadiansPerSecond; + double angleVelDeg = Math.toDegrees(angleVelRad); + + m_kinematicsTargetAngle += angleVelDeg * (m_deltaTime/1000); + m_kinematicsTargetAngle = MathUtil.clamp( m_kinematicsTargetAngle, + m_currentAngleYaw-(360), + m_currentAngleYaw+(360)); + double targetGyro = (m_kinematicsTargetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV; + double moveVel = inchesToMeters(metersToInches(moveVelMPS))/DriveConstants.SECONDS_TO_TICK_TIME; + + runDriveStraightVelocityPID(moveVel, targetGyro); + } + /** * Returns the current yaw of the pigeon */ @@ -400,8 +425,16 @@ public class Drive extends SubsystemBase { public void resetGyroYaw() { m_pigeon.setYaw(0); m_pigeon.setAccumZAngle(0); + resetGyroAngles(); + } + + /** + * Add docs here + */ + public void resetGyroAngles() { m_lastAngleYaw = 0; m_currentAngleYaw = 0; + m_kinematicsTargetAngle = 0; } /** @@ -484,6 +517,15 @@ public class Drive extends SubsystemBase { return ticks * DriveConstants.INCHES_PER_TICK; } + /** + * Converts a value in inches to ticks. + * @param inches The value in inches to convert + * @return The converted value in ticks + */ + public double inchesToTicks(double inches) { + return inches * DriveConstants.TICKS_PER_INCH; + } + /** * Converts a value in inches to meters. * @param inches The value in inches to convert @@ -492,6 +534,15 @@ public class Drive extends SubsystemBase { public double inchesToMeters(double inches) { return inches / DriveConstants.INCHES_PER_METER; } + + /** + * Converts a value in meters to inches. + * @param meters The value in meters to convert + * @return The converted value in inches + */ + public double metersToInches(double meters) { + return meters * DriveConstants.INCHES_PER_METER; + } /* * Set to high or low gear based on boolean state, true = high, false = low From 294f58727d081fed0ccc0891dbad2abc6d890459 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Thu, 13 Feb 2020 00:30:08 -0700 Subject: [PATCH 09/44] Cleanup Imports in RobotContainer --- src/main/java/frc4388/robot/RobotContainer.java | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 408712f..090c0a3 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -8,27 +8,24 @@ package frc4388.robot; import java.util.List; -import java.util.function.BiConsumer; import com.ctre.phoenix.motorcontrol.NeutralMode; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.controller.RamseteController; -import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward; import edu.wpi.first.wpilibj.geometry.Pose2d; import edu.wpi.first.wpilibj.geometry.Rotation2d; import edu.wpi.first.wpilibj.geometry.Translation2d; import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds; -import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.wpilibj.trajectory.Trajectory; import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig; import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator; -import edu.wpi.first.wpilibj.trajectory.constraint.DifferentialDriveVoltageConstraint; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.RamseteCommand; 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; From 4ea924ebe650a8c1e9235fdd29f72a0b48e7ec02 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Thu, 13 Feb 2020 00:35:49 -0700 Subject: [PATCH 10/44] Remove unneeded line of code --- src/main/java/frc4388/robot/RobotContainer.java | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 090c0a3..fbdc8bb 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -168,8 +168,6 @@ public class RobotContainer { */ public Command getAutonomousCommand() { - var wheelSpeeds = new ChassisSpeeds(); - // Create config for trajectory TrajectoryConfig config = new TrajectoryConfig( DriveConstants.kMaxSpeedMetersPerSecond, DriveConstants.kMaxAccelerationMetersPerSecondSquared) From 9014d00798ff509333088ac9a2b19e5516b0f8a4 Mon Sep 17 00:00:00 2001 From: ryan123rudder <42309874+ryan123rudder@users.noreply.github.com> Date: Thu, 13 Feb 2020 17:08:41 -0700 Subject: [PATCH 11/44] setup code to fix broken dead assist --- src/main/java/frc4388/robot/RobotContainer.java | 3 ++- .../commands/DriveWithJoystickUsingDeadAssistPID.java | 11 +++++++++++ 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index a431921..22455f3 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -18,6 +18,7 @@ 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.DriveWithJoystickUsingDeadAssistPID; import frc4388.robot.commands.RunClimberWithTriggers; import frc4388.robot.commands.RunExtenderOutIn; @@ -64,7 +65,7 @@ public class RobotContainer { /* Default Commands */ // drives the robot with a two-axis input from the driver controller - m_robotDrive.setDefaultCommand(new DriveWithJoystickUsingDeadAssistPID(m_robotDrive, getDriverController())); + m_robotDrive.setDefaultCommand(new DriveWithJoystick(m_robotDrive, getDriverController())); // drives intake with input from triggers on the opperator controller m_robotIntake.setDefaultCommand(new RunIntakeWithTriggers(m_robotIntake, getOperatorController())); // drives climber with input from triggers on the opperator controller diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index 0a7938e..352030b 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -86,21 +86,32 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { steerOutput = cosMultiplier*Math.cos(1.571*steerInput)-(cosMultiplier+deadzone); } m_drive.driveWithInput(moveOutput, steerOutput); + System.out.println("Driving With Input"); isAuxPIDEnabled = false; } /* If only the move stick is being used */ else { m_drive.driveWithInputAux(moveOutput, m_targetGyro); + System.out.println("Driving with Input Aux with Target: " + m_targetGyro); isAuxPIDEnabled = true; } } /* If the move stick is not being used */ else { m_drive.runDriveStraightVelocityPID(0, m_targetGyro); + System.out.println("Driving with Velocity PID with Target: " + m_targetGyro); isAuxPIDEnabled = true; } } + private void updateGyroTarget() { + + } + + private void resetGyroTarget() { + + } + // Called once the command ends or is interrupted. @Override public void end(boolean interrupted) { From 328380b9e49577066f6b982d0fd8fdd9c01d60d1 Mon Sep 17 00:00:00 2001 From: ryan123rudder <42309874+ryan123rudder@users.noreply.github.com> Date: Thu, 13 Feb 2020 17:11:54 -0700 Subject: [PATCH 12/44] invert move input --- src/main/java/frc4388/robot/commands/DriveWithJoystick.java | 2 +- .../robot/commands/DriveWithJoystickUsingDeadAssistPID.java | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystick.java b/src/main/java/frc4388/robot/commands/DriveWithJoystick.java index e663fdb..5387e8d 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystick.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystick.java @@ -38,7 +38,7 @@ public class DriveWithJoystick extends CommandBase { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - double moveInput = m_controller.getLeftYAxis(); + double moveInput = -m_controller.getLeftYAxis(); double steerInput = m_controller.getRightXAxis(); double moveOutput = 0; double steerOutput = 0; diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index 352030b..5cfb24d 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -46,7 +46,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { @Override public void execute() { double currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); - double moveInput = m_controller.getLeftYAxis(); + double moveInput = -m_controller.getLeftYAxis(); double steerInput = m_controller.getRightXAxis(); double moveOutput = 0; double steerOutput = 0; From 9ae3ff611fb9b5a50eab800f8af7a80804afff2e Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 13 Feb 2020 17:17:01 -0700 Subject: [PATCH 13/44] Revert "Added Trajectory Command" This reverts commit 0e5427cb60ff80eb2d5409e5fd8cdc401309477a. --- .../java/frc4388/robot/RobotContainer.java | 59 +------------------ .../java/frc4388/robot/subsystems/Drive.java | 6 -- 2 files changed, 1 insertion(+), 64 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 8daeb93..0cd20ac 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -7,24 +7,13 @@ package frc4388.robot; -import java.util.List; - import com.ctre.phoenix.motorcontrol.NeutralMode; import edu.wpi.first.wpilibj.Joystick; -import edu.wpi.first.wpilibj.controller.PIDController; -import edu.wpi.first.wpilibj.controller.RamseteController; import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward; -import edu.wpi.first.wpilibj.geometry.Pose2d; -import edu.wpi.first.wpilibj.geometry.Rotation2d; -import edu.wpi.first.wpilibj.geometry.Translation2d; -import edu.wpi.first.wpilibj.trajectory.Trajectory; -import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig; -import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator; import edu.wpi.first.wpilibj.trajectory.constraint.DifferentialDriveVoltageConstraint; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; -import edu.wpi.first.wpilibj2.command.RamseteCommand; import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.button.JoystickButton; import frc4388.robot.Constants.*; @@ -132,53 +121,7 @@ public class RobotContainer { */ public Command getAutonomousCommand() { // no auto - var autoVoltageConstraint = - new DifferentialDriveVoltageConstraint( - new SimpleMotorFeedforward( DriveConstants.ksVolts, - DriveConstants.kvVoltSecondsPerMeter, - DriveConstants.kaVoltSecondsSquaredPerMeter), - DriveConstants.kDriveKinematics, - 10); - - TrajectoryConfig config = - new TrajectoryConfig( DriveConstants.kMaxSpeedMetersPerSecond, - DriveConstants.kMaxAccelerationMetersPerSecondSquared) - - .setKinematics(DriveConstants.kDriveKinematics) - - .addConstraint(autoVoltageConstraint); - - Trajectory exampleTrajectory = TrajectoryGenerator.generateTrajectory( - - new Pose2d(0, 0, new Rotation2d(0)), - - List.of( - new Translation2d(1, 1), - new Translation2d(2, -1) - ), - - new Pose2d(3, 0, new Rotation2d(0)), - - config - ); - - RamseteCommand ramseteCommand = new RamseteCommand( - exampleTrajectory, - m_robotDrive::getPose, - new RamseteController(DriveConstants.kRamseteB, DriveConstants.kRamseteZeta), - new SimpleMotorFeedforward( DriveConstants.ksVolts, - DriveConstants.kvVoltSecondsPerMeter, - DriveConstants.kaVoltSecondsSquaredPerMeter), - DriveConstants.kDriveKinematics, - m_robotDrive::getWheelSpeeds, - new PIDController(DriveConstants.kPDriveVel, 0, 0), - new PIDController(DriveConstants.kPDriveVel, 0, 0), - - m_robotDrive::tankDriveVolts, - m_robotDrive - ); - - return ramseteCommand.andThen(() -> m_robotDrive.tankDriveVolts(0, 0)); + return new InstantCommand(); } /** diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 3d4cd7b..a583e33 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -508,10 +508,4 @@ public class Drive extends SubsystemBase { public double ticksToInches(double ticks) { return ticks * DriveConstants.INCHES_PER_TICK; } - - public void tankDriveVolts(double leftVolts, double rightVolts) { - m_leftFrontMotor.setVoltage(leftVolts); - m_rightFrontMotor.setVoltage(-rightVolts); - m_driveTrain.feedWatchdog(); - } } \ No newline at end of file From a5bdb28d377e564f6b0aba48170de017c5dc1f96 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 13 Feb 2020 17:34:59 -0700 Subject: [PATCH 14/44] Reconfigure motor sensor between auto and teleop --- src/main/java/frc4388/robot/Robot.java | 4 ++++ src/main/java/frc4388/robot/RobotContainer.java | 5 +++++ src/main/java/frc4388/robot/subsystems/Drive.java | 12 ++++++++++-- 3 files changed, 19 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/Robot.java b/src/main/java/frc4388/robot/Robot.java index b23b040..ca009f0 100644 --- a/src/main/java/frc4388/robot/Robot.java +++ b/src/main/java/frc4388/robot/Robot.java @@ -7,6 +7,7 @@ package frc4388.robot; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; import com.ctre.phoenix.motorcontrol.NeutralMode; import edu.wpi.first.wpilibj.TimedRobot; @@ -76,6 +77,7 @@ public class Robot extends TimedRobot { m_robotContainer.setDriveNeutralMode(NeutralMode.Brake); m_robotContainer.resetOdometry(); + m_robotContainer.configDriveTrainSensors(FeedbackDevice.IntegratedSensor); /* * String autoSelected = SmartDashboard.getString("Auto Selector", @@ -100,6 +102,8 @@ public class Robot extends TimedRobot { @Override public void teleopInit() { m_robotContainer.setDriveNeutralMode(NeutralMode.Coast); + m_robotContainer.configDriveTrainSensors(FeedbackDevice.SensorDifference); + // This makes sure that the autonomous stops running when // teleop starts running. If you want the autonomous to // continue until interrupted by another command, remove diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index fbdc8bb..e074bfb 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -9,6 +9,7 @@ package frc4388.robot; import java.util.List; +import com.ctre.phoenix.motorcontrol.FeedbackDevice; import com.ctre.phoenix.motorcontrol.NeutralMode; import edu.wpi.first.wpilibj.Joystick; @@ -156,6 +157,10 @@ public class RobotContainer { m_robotDrive.setDriveTrainNeutralMode(mode); } + public void configDriveTrainSensors(FeedbackDevice type) { + m_robotDrive.configMotorSensor(type); + } + public void resetOdometry() { m_robotDrive.resetGyroAngles(); m_robotDrive.setOdometry(new Pose2d()); diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 73a358d..161b7f1 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -162,8 +162,7 @@ public class Drive extends SubsystemBase { 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, DriveConstants.PID_PRIMARY, - DriveConstants.DRIVE_TIMEOUT_MS); + configMotorSensor(FeedbackDevice.SensorDifference); /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ m_rightFrontMotor.configSelectedFeedbackCoefficient( 1, // Coefficient @@ -389,6 +388,15 @@ public class Drive extends SubsystemBase { runDriveStraightVelocityPID(moveVel, targetGyro); } + /** + * Selects the feedback device for the motors. + * @param feedbackDevice The feedback device to set it to, usually SensorDifference or + */ + public void configMotorSensor(FeedbackDevice type) { + m_rightFrontMotor.configSelectedFeedbackSensor( type, DriveConstants.PID_PRIMARY, + DriveConstants.DRIVE_TIMEOUT_MS); + } + /** * Returns the current yaw of the pigeon */ From 0cf6f8f37070a6f6a005d0853d07e650729dfb45 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 13 Feb 2020 17:46:15 -0700 Subject: [PATCH 15/44] Changed Tank Drive Velocity Method --- src/main/java/frc4388/robot/Constants.java | 2 +- src/main/java/frc4388/robot/subsystems/Drive.java | 12 ++++++++---- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 35672cc..c241591 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -39,7 +39,7 @@ public final class Constants { /* Trajectory Constants */ public static final double kMaxSpeedMetersPerSecond = 3; public static final double kMaxAccelerationMetersPerSecondSquared = 3; - public static final double kTrackwidthMeters = 0.69; ///TODO: SET THIS SOON! + public static final double kTrackwidthMeters = 0.648; ///TODO: SET THIS SOON! public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(kTrackwidthMeters); /* Remote Sensors */ diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 161b7f1..3cbf888 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -372,7 +372,7 @@ public class Drive extends SubsystemBase { * @param rightSpeed the commanded right output */ public void tankDriveVelocity(double leftSpeed, double rightSpeed) { - DifferentialDriveWheelSpeeds wheelSpeeds = new DifferentialDriveWheelSpeeds(leftSpeed, rightSpeed); + /*DifferentialDriveWheelSpeeds wheelSpeeds = new DifferentialDriveWheelSpeeds(leftSpeed, rightSpeed); ChassisSpeeds chassisSpeeds = DriveConstants.kDriveKinematics.toChassisSpeeds(wheelSpeeds); double moveVelMPS = chassisSpeeds.vxMetersPerSecond; double angleVelRad = chassisSpeeds.omegaRadiansPerSecond; @@ -382,10 +382,14 @@ public class Drive extends SubsystemBase { m_kinematicsTargetAngle = MathUtil.clamp( m_kinematicsTargetAngle, m_currentAngleYaw-(360), m_currentAngleYaw+(360)); - double targetGyro = (m_kinematicsTargetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV; - double moveVel = inchesToMeters(metersToInches(moveVelMPS))/DriveConstants.SECONDS_TO_TICK_TIME; + double targetGyro = (m_kinematicsTargetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV;*/ + double moveVelLeft = inchesToMeters(metersToInches(leftSpeed))/DriveConstants.SECONDS_TO_TICK_TIME; + double moveVelRight = inchesToMeters(metersToInches(rightSpeed))/DriveConstants.SECONDS_TO_TICK_TIME; - runDriveStraightVelocityPID(moveVel, targetGyro); + //runDriveStraightVelocityPID(moveVel, targetGyro); + + m_rightFrontMotor.set(TalonFXControlMode.Velocity, moveVelRight); + m_leftFrontMotor.set(TalonFXControlMode.Velocity, moveVelLeft); } /** From 110f18f569bb12e8afeabc910a26427d6c0dc002 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 13 Feb 2020 17:48:49 -0700 Subject: [PATCH 16/44] Refactored constants --- src/main/java/frc4388/robot/Constants.java | 10 +++++----- src/main/java/frc4388/robot/RobotContainer.java | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index c241591..0d55be6 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -37,11 +37,11 @@ public final class Constants { public static final int DRIVE_ACCELERATION = 7000; /* Trajectory Constants */ - public static final double kMaxSpeedMetersPerSecond = 3; - public static final double kMaxAccelerationMetersPerSecondSquared = 3; - public static final double kTrackwidthMeters = 0.648; ///TODO: SET THIS SOON! - public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(kTrackwidthMeters); - + public static final double MAX_SPEED_METERS_PER_SECOND = 3; + public static final double MAX_ACCELERATION_METERS_PER_SECOND_SQUARED = 3; + public static final double TRACK_WIDTH_METERS = 0.648; ///TODO: SET THIS SOON! + public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(TRACK_WIDTH_METERS); + /* Remote Sensors */ public final static int REMOTE_0 = 0; public final static int REMOTE_1 = 1; diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index e074bfb..08c3ec4 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -174,8 +174,8 @@ public class RobotContainer { public Command getAutonomousCommand() { // Create config for trajectory - TrajectoryConfig config = new TrajectoryConfig( DriveConstants.kMaxSpeedMetersPerSecond, - DriveConstants.kMaxAccelerationMetersPerSecondSquared) + TrajectoryConfig config = new TrajectoryConfig( DriveConstants.MAX_SPEED_METERS_PER_SECOND, + DriveConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED) // Add kinematics to ensure max speed is actually obeyed .setKinematics(DriveConstants.kDriveKinematics); From 572dd7c730f527c99a673b1070ea384ba0138ea1 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 13 Feb 2020 17:51:54 -0700 Subject: [PATCH 17/44] Took out straight from methods --- .../robot/commands/DriveStraightAtVelocityPID.java | 2 +- .../robot/commands/DriveStraightToPositionPID.java | 2 +- .../commands/DriveWithJoystickUsingDeadAssistPID.java | 2 +- src/main/java/frc4388/robot/subsystems/Drive.java | 10 +++++----- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc4388/robot/commands/DriveStraightAtVelocityPID.java b/src/main/java/frc4388/robot/commands/DriveStraightAtVelocityPID.java index 7b82ff8..14cc97e 100644 --- a/src/main/java/frc4388/robot/commands/DriveStraightAtVelocityPID.java +++ b/src/main/java/frc4388/robot/commands/DriveStraightAtVelocityPID.java @@ -37,7 +37,7 @@ public class DriveStraightAtVelocityPID extends CommandBase { @Override public void execute() { //System.err.println(m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); - m_drive.runDriveStraightVelocityPID(-m_targetVel, m_targetGyro); + m_drive.runDriveVelocityPID(-m_targetVel, m_targetGyro); } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java b/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java index 0b9b998..3b74edf 100644 --- a/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java +++ b/src/main/java/frc4388/robot/commands/DriveStraightToPositionPID.java @@ -47,7 +47,7 @@ public class DriveStraightToPositionPID extends CommandBase { //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); + m_drive.runDrivePositionPID(m_targetPosOut, m_targetGyro); } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index 0a7938e..7aaf5a9 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -96,7 +96,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { } /* If the move stick is not being used */ else { - m_drive.runDriveStraightVelocityPID(0, m_targetGyro); + m_drive.runDriveVelocityPID(0, m_targetGyro); isAuxPIDEnabled = true; } } diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 3cbf888..5db8a18 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -309,12 +309,12 @@ public class Drive extends SubsystemBase { } /** - * Runs position PID while driving straight. + * Runs position PID. * Position is absolute and displacement should be handled on the command side. * @param targetPos The position to drive to in units * @param targetGyro The angle to drive at in units */ - public void runDriveStraightPositionPID(double targetPos, double targetGyro) { + public void runDrivePositionPID(double targetPos, double targetGyro) { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); @@ -325,12 +325,12 @@ public class Drive extends SubsystemBase { } /** - * Runs velocity PID while driving straight + * Runs velocity PID * * @param targetVel The velocity to drive at in units * @param targetGyro The angle to drive at in units */ - public void runDriveStraightVelocityPID(double targetVel, double targetGyro) { + public void runDriveVelocityPID(double targetVel, double targetGyro) { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); m_rightFrontMotor.set(TalonFXControlMode.Velocity, targetVel, DemandType.AuxPID, targetGyro); @@ -362,7 +362,7 @@ public class Drive extends SubsystemBase { public void runTurningPID(double targetAngle) { double targetGyro = (targetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV; - runDriveStraightVelocityPID(0, targetGyro); + runDriveVelocityPID(0, targetGyro); } /** From a3a1e953fba3443e10059324bf83618ee8e847eb Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 13 Feb 2020 17:58:45 -0700 Subject: [PATCH 18/44] Fixed small issue in conversion method --- src/main/java/frc4388/robot/Constants.java | 3 ++- src/main/java/frc4388/robot/subsystems/Drive.java | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 0d55be6..d35a01e 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -39,7 +39,7 @@ public final class Constants { /* Trajectory Constants */ public static final double MAX_SPEED_METERS_PER_SECOND = 3; public static final double MAX_ACCELERATION_METERS_PER_SECOND_SQUARED = 3; - public static final double TRACK_WIDTH_METERS = 0.648; ///TODO: SET THIS SOON! + public static final double TRACK_WIDTH_METERS = 0.648; public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(TRACK_WIDTH_METERS); /* Remote Sensors */ @@ -71,6 +71,7 @@ public final class Constants { public static final double TICKS_PER_INCH = TICKS_PER_WHEEL_REV/INCHES_PER_WHEEL_REV; public static final double INCHES_PER_TICK = 1/TICKS_PER_INCH; public static final double INCHES_PER_METER = 39.370; + public static final double METERS_PER_INCH = 1/INCHES_PER_METER; } public static final class IntakeConstants { diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 5db8a18..7a153e4 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -544,7 +544,7 @@ public class Drive extends SubsystemBase { * @return The converted value in meters */ public double inchesToMeters(double inches) { - return inches / DriveConstants.INCHES_PER_METER; + return inches * DriveConstants.METERS_PER_INCH; } /** From 03daeed5060ed95f60114ffbfa51ba9cd2969834 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 13 Feb 2020 19:35:30 -0700 Subject: [PATCH 19/44] Fixed heading in odometry, but position needs work --- src/main/java/frc4388/robot/Robot.java | 1 + src/main/java/frc4388/robot/subsystems/Drive.java | 5 +++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/Robot.java b/src/main/java/frc4388/robot/Robot.java index ca009f0..1335ec6 100644 --- a/src/main/java/frc4388/robot/Robot.java +++ b/src/main/java/frc4388/robot/Robot.java @@ -89,6 +89,7 @@ public class Robot extends TimedRobot { // schedule the autonomous command (example) if (m_autonomousCommand != null) { m_autonomousCommand.schedule(); + System.err.println("Auto Start"); } } diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 7a153e4..b3afa0d 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -77,7 +77,7 @@ public class Drive extends SubsystemBase { m_pigeon.configFactoryDefault(); resetGyroYaw(); - m_odometry = new DifferentialDriveOdometry(Rotation2d.fromDegrees(getHeading())); + m_odometry = new DifferentialDriveOdometry(Rotation2d.fromDegrees(getHeading()), new Pose2d(0, 0, new Rotation2d())); speedShift = new DoubleSolenoid(7,0,1); @@ -263,6 +263,7 @@ public class Drive extends SubsystemBase { //SmartDashboard.putNumber("PID 1 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN)); SmartDashboard.putString("Odometry Values Meters", getPose().toString()); + SmartDashboard.putNumber("Odometry Heading", getHeading()); } catch (Exception e) { System.err.println("Error in the Drive Subsystem"); @@ -271,7 +272,7 @@ public class Drive extends SubsystemBase { m_odometry.update(Rotation2d.fromDegrees( getHeading()), inchesToMeters(getDistanceInches(m_leftFrontMotor)), - inchesToMeters(getDistanceInches(m_rightFrontMotor))); + inchesToMeters(-getDistanceInches(m_rightFrontMotor))); } /** From 0e696c73ed295e9276221255063ead475b202345 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Fri, 14 Feb 2020 08:32:32 -0700 Subject: [PATCH 20/44] Debugging ramsete controller --- src/main/java/frc4388/robot/Robot.java | 8 ++++++-- .../java/frc4388/robot/RobotContainer.java | 11 ++++++----- .../java/frc4388/robot/subsystems/Drive.java | 19 ++++++++++++------- .../frc4388/robot/subsystems/Storage.java | 4 ++-- 4 files changed, 26 insertions(+), 16 deletions(-) diff --git a/src/main/java/frc4388/robot/Robot.java b/src/main/java/frc4388/robot/Robot.java index 1335ec6..a726e56 100644 --- a/src/main/java/frc4388/robot/Robot.java +++ b/src/main/java/frc4388/robot/Robot.java @@ -11,6 +11,7 @@ import com.ctre.phoenix.motorcontrol.FeedbackDevice; import com.ctre.phoenix.motorcontrol.NeutralMode; import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; @@ -35,6 +36,7 @@ public class Robot extends TimedRobot { // Instantiate our RobotContainer. This will perform all our button bindings, and put our // autonomous chooser on the dashboard. m_robotContainer = new RobotContainer(); + SmartDashboard.putString("Auto?", "NAH"); } /** @@ -77,7 +79,7 @@ public class Robot extends TimedRobot { m_robotContainer.setDriveNeutralMode(NeutralMode.Brake); m_robotContainer.resetOdometry(); - m_robotContainer.configDriveTrainSensors(FeedbackDevice.IntegratedSensor); + //m_robotContainer.configDriveTrainSensors(FeedbackDevice.IntegratedSensor); /* * String autoSelected = SmartDashboard.getString("Auto Selector", @@ -103,7 +105,7 @@ public class Robot extends TimedRobot { @Override public void teleopInit() { m_robotContainer.setDriveNeutralMode(NeutralMode.Coast); - m_robotContainer.configDriveTrainSensors(FeedbackDevice.SensorDifference); + //m_robotContainer.configDriveTrainSensors(FeedbackDevice.IntegratedSensor); // This makes sure that the autonomous stops running when // teleop starts running. If you want the autonomous to @@ -112,6 +114,8 @@ public class Robot extends TimedRobot { if (m_autonomousCommand != null) { m_autonomousCommand.cancel(); } + + SmartDashboard.putString("Auto?", "NAH"); } /** diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 08c3ec4..ce4e549 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -31,6 +31,7 @@ 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.DriveWithJoystickUsingDeadAssistPID; import frc4388.robot.commands.RunClimberWithTriggers; import frc4388.robot.commands.RunExtenderOutIn; @@ -77,7 +78,7 @@ public class RobotContainer { /* Default Commands */ // drives the robot with a two-axis input from the driver controller - m_robotDrive.setDefaultCommand(new DriveWithJoystickUsingDeadAssistPID(m_robotDrive, getDriverController())); + m_robotDrive.setDefaultCommand(new DriveWithJoystick(m_robotDrive, getDriverController())); // drives intake with input from triggers on the opperator controller m_robotIntake.setDefaultCommand(new RunIntakeWithTriggers(m_robotIntake, getOperatorController())); // drives climber with input from triggers on the opperator controller @@ -126,7 +127,7 @@ public class RobotContainer { // resets the yaw of the pigeon new JoystickButton(getDriverJoystick(), XboxController.X_BUTTON) - .whenPressed(new DriveStraightToPositionMM(m_robotDrive, 72)); + .whileHeld(new RunCommand(() -> m_robotDrive.tankDriveVelocity(1, 1), m_robotDrive)); // turn 45 degrees new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) @@ -184,11 +185,11 @@ public class RobotContainer { new Pose2d(0, 0, new Rotation2d(0)), // Pass through these two interior waypoints, making an 's' curve path List.of( - new Translation2d(1, 1), - new Translation2d(2, -1) + new Translation2d(2, 0) + //new Translation2d(4, -2) ), // End 3 meters straight ahead of where we started, facing forward - new Pose2d(3, 0, new Rotation2d(0)), + new Pose2d(4, 0, new Rotation2d(0)), // Pass config config); diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index b3afa0d..15dd296 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -373,7 +373,7 @@ public class Drive extends SubsystemBase { * @param rightSpeed the commanded right output */ public void tankDriveVelocity(double leftSpeed, double rightSpeed) { - /*DifferentialDriveWheelSpeeds wheelSpeeds = new DifferentialDriveWheelSpeeds(leftSpeed, rightSpeed); + DifferentialDriveWheelSpeeds wheelSpeeds = new DifferentialDriveWheelSpeeds(leftSpeed, rightSpeed); ChassisSpeeds chassisSpeeds = DriveConstants.kDriveKinematics.toChassisSpeeds(wheelSpeeds); double moveVelMPS = chassisSpeeds.vxMetersPerSecond; double angleVelRad = chassisSpeeds.omegaRadiansPerSecond; @@ -383,14 +383,19 @@ public class Drive extends SubsystemBase { m_kinematicsTargetAngle = MathUtil.clamp( m_kinematicsTargetAngle, m_currentAngleYaw-(360), m_currentAngleYaw+(360)); - double targetGyro = (m_kinematicsTargetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV;*/ - double moveVelLeft = inchesToMeters(metersToInches(leftSpeed))/DriveConstants.SECONDS_TO_TICK_TIME; - double moveVelRight = inchesToMeters(metersToInches(rightSpeed))/DriveConstants.SECONDS_TO_TICK_TIME; + double targetGyro = (m_kinematicsTargetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV; + double moveVel = inchesToTicks(metersToInches(moveVelMPS))/DriveConstants.SECONDS_TO_TICK_TIME; + //double moveVelRight = inchesToTicks(metersToInches(rightSpeed))/DriveConstants.SECONDS_TO_TICK_TIME; - //runDriveStraightVelocityPID(moveVel, targetGyro); + //SmartDashboard.putNumber("Move Vel Left", moveVelLeft); + //SmartDashboard.putNumber("Move Vel Right", moveVelRight); - m_rightFrontMotor.set(TalonFXControlMode.Velocity, moveVelRight); - m_leftFrontMotor.set(TalonFXControlMode.Velocity, moveVelLeft); + runDriveVelocityPID(moveVel*2, targetGyro); + + //m_rightFrontMotor.set(TalonFXControlMode.Velocity, moveVelRight); + //m_leftFrontMotor.set(TalonFXControlMode.Velocity, moveVelLeft); + + //m_driveTrain.feedWatchdog(); } /** diff --git a/src/main/java/frc4388/robot/subsystems/Storage.java b/src/main/java/frc4388/robot/subsystems/Storage.java index 84f01ec..e61cbef 100644 --- a/src/main/java/frc4388/robot/subsystems/Storage.java +++ b/src/main/java/frc4388/robot/subsystems/Storage.java @@ -59,9 +59,9 @@ public class Storage extends SubsystemBase { final boolean beam_on = m_beamSensors[0].get(); if (beam_on) { - System.err.println("Beam on"); + //System.err.println("Beam on"); } else { - System.err.println("Beam off"); + //System.err.println("Beam off"); } } From c39ec549a90e6480cf8a9974a7745e3c3b516930 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Mon, 17 Feb 2020 13:06:51 -0700 Subject: [PATCH 21/44] Set up back motor master and tune PIDs --- src/main/java/frc4388/robot/Constants.java | 4 +- src/main/java/frc4388/robot/Robot.java | 3 + .../java/frc4388/robot/RobotContainer.java | 19 +- .../java/frc4388/robot/subsystems/Drive.java | 164 +++++++++++------- 4 files changed, 124 insertions(+), 66 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index d35a01e..92d6a05 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -30,8 +30,8 @@ public final class Constants { /* PID Constants Drive*/ public static final int DRIVE_TIMEOUT_MS = 30; public static final Gains DRIVE_DISTANCE_GAINS = new Gains(0.2, 0.0, 0.0, 0.0, 0, 0.3); - public static final Gains DRIVE_VELOCITY_GAINS = new Gains(0.1, 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.5); + public static final Gains DRIVE_VELOCITY_GAINS = new Gains(0.05, 0.0, 0.0, 0.025, 0, 1.0); + public static final Gains DRIVE_TURNING_GAINS = new Gains(0.5, 0.0, 0.0, 0.0, 0, 0.5); 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 = 20000; public static final int DRIVE_ACCELERATION = 7000; diff --git a/src/main/java/frc4388/robot/Robot.java b/src/main/java/frc4388/robot/Robot.java index a726e56..5ada949 100644 --- a/src/main/java/frc4388/robot/Robot.java +++ b/src/main/java/frc4388/robot/Robot.java @@ -64,6 +64,7 @@ public class Robot extends TimedRobot { @Override public void disabledInit() { m_robotContainer.setDriveNeutralMode(NeutralMode.Coast); + //m_robotContainer.setDriveGearState(true); } @Override @@ -78,6 +79,7 @@ public class Robot extends TimedRobot { m_autonomousCommand = m_robotContainer.getAutonomousCommand(); m_robotContainer.setDriveNeutralMode(NeutralMode.Brake); + m_robotContainer.setDriveGearState(true); m_robotContainer.resetOdometry(); //m_robotContainer.configDriveTrainSensors(FeedbackDevice.IntegratedSensor); @@ -105,6 +107,7 @@ public class Robot extends TimedRobot { @Override public void teleopInit() { m_robotContainer.setDriveNeutralMode(NeutralMode.Coast); + m_robotContainer.setDriveGearState(true); //m_robotContainer.configDriveTrainSensors(FeedbackDevice.IntegratedSensor); // This makes sure that the autonomous stops running when diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index ce4e549..528a9e2 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -102,7 +102,7 @@ public class RobotContainer { private void configureButtonBindings() { /* Driver Buttons */ new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON) - .whenPressed(new DriveStraightToPositionPID(m_robotDrive, 144)); + .whenPressed(new RunCommand(() -> m_robotDrive.runTurningPID(0), m_robotDrive)); /* Operator Buttons */ // activates "Lit Mode" @@ -131,7 +131,7 @@ public class RobotContainer { // turn 45 degrees new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) - .whenPressed(new RunCommand(() -> m_robotDrive.runTurningPID(45), m_robotDrive)); + .whenPressed(new RunCommand(() -> m_robotDrive.driveWithInputAux(0.2, 0), m_robotDrive)); // sets solenoids into high gear new JoystickButton(getDriverJoystick(), XboxController.START_BUTTON) @@ -153,11 +153,20 @@ public class RobotContainer { /** * Sets Motors to a NeutralMode. * @param mode NeutralMode to set motors to + * @param state the gearing of the gearbox (true is high, false is low) */ public void setDriveNeutralMode(NeutralMode mode) { m_robotDrive.setDriveTrainNeutralMode(mode); } + /** + * Sets the gear of the drivetrain + * @param state the gearing of the gearbox (true is high, false is low) + */ + public void setDriveGearState(boolean state) { + m_robotDrive.setShiftState(state); + } + public void configDriveTrainSensors(FeedbackDevice type) { m_robotDrive.configMotorSensor(type); } @@ -185,11 +194,11 @@ public class RobotContainer { new Pose2d(0, 0, new Rotation2d(0)), // Pass through these two interior waypoints, making an 's' curve path List.of( - new Translation2d(2, 0) - //new Translation2d(4, -2) + new Translation2d(1, 1), + new Translation2d(2, -1) ), // End 3 meters straight ahead of where we started, facing forward - new Pose2d(4, 0, new Rotation2d(0)), + new Pose2d(3, 0, new Rotation2d(0)), // Pass config config); diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 15dd296..ed48967 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -85,13 +85,6 @@ public class Drive extends SubsystemBase { m_leftBackMotor.follow(m_leftFrontMotor); m_rightBackMotor.follow(m_rightFrontMotor); - setDriveTrainNeutralMode(NeutralMode.Coast); - - /* deadbands */ - m_leftBackMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // DO NOT CHANGE - m_rightBackMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // Ensures motors run at the same - // speed - /* flip input so forward becomes back, etc */ m_leftFrontMotor.setInverted(false); m_rightFrontMotor.setInverted(true); @@ -99,6 +92,15 @@ public class Drive extends SubsystemBase { m_leftBackMotor.setInverted(InvertType.FollowMaster); m_rightBackMotor.setInverted(InvertType.FollowMaster); + setDriveTrainNeutralMode(NeutralMode.Coast); + + /* deadbands */ + m_leftBackMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // DO NOT CHANGE + m_rightBackMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // Ensures motors run at the same speed + //m_leftFrontMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // DO NOT CHANGE + //m_rightFrontMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // Ensures motors run at the same speed + + /* PID for Front Motor Control in Teleop */ m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); m_rightFrontMotor.config_kF(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.config_kP(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); @@ -130,6 +132,21 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.configMotionAcceleration(DriveConstants.DRIVE_ACCELERATION, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.configMotionSCurveStrength(0, DriveConstants.DRIVE_TIMEOUT_MS); + /* PID for Back Motor control in Auto */ + m_rightBackMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); + m_rightBackMotor.config_kF(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightBackMotor.config_kP(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightBackMotor.config_kI(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightBackMotor.config_kD(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightBackMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); + + m_leftBackMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); + m_leftBackMotor.config_kF(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); + m_leftBackMotor.config_kP(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); + m_leftBackMotor.config_kI(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); + m_leftBackMotor.config_kD(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); + m_leftBackMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); + /* Setup Sensors for WPI_TalonFXs */ resetEncoders(); @@ -138,18 +155,22 @@ public class Drive extends SubsystemBase { DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout - /* - * Configure the Remote Talon's selected sensor as a remote sensor for the right - * Talon - */ + /* Configure the left back Talon's selected sensor as local QuadEncoder */ + m_leftBackMotor.configSelectedFeedbackSensor( FeedbackDevice.IntegratedSensor, // Local Feedback Source + DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] + DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout + + /* Configure the right back Talon's selected sensor as local QuadEncoder */ + m_rightBackMotor.configSelectedFeedbackSensor( FeedbackDevice.IntegratedSensor, // Local Feedback Source + DriveConstants.PID_PRIMARY, // PID Index for Source [0, 1] + DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout + + /* Configure the Remote Talon's selected sensor as a remote sensor for the right Talon */ m_rightFrontMotor.configRemoteFeedbackFilter( m_leftFrontMotor.getDeviceID(), // Device ID of Source RemoteSensorSource.TalonSRX_SelectedSensor, DriveConstants.REMOTE_0, // Source number [0, 1] DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout - /* - * Configure the Pigeon IMU to the other Remote Slot available on the right - * Talon - */ + /* Configure the Pigeon IMU to the other Remote Slot available on the right Talon */ m_rightFrontMotor.configRemoteFeedbackFilter( m_pigeon.getDeviceID(), RemoteSensorSource.Pigeon_Yaw, DriveConstants.REMOTE_1, DriveConstants.DRIVE_TIMEOUT_MS); @@ -164,19 +185,22 @@ public class Drive extends SubsystemBase { /* Configure Sum [Sum of both QuadEncoders] to be used for Primary PID Index */ configMotorSensor(FeedbackDevice.SensorDifference); - /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ + /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) DOESN'T WORK */ + /* m_rightFrontMotor.configSelectedFeedbackCoefficient( 1, // Coefficient DriveConstants.PID_PRIMARY, // PID Slot of Source DriveConstants.DRIVE_TIMEOUT_MS); // Configuration Timeout + */ - m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.RemoteSensor1, DriveConstants.PID_TURN, + m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.RemoteSensor1, + DriveConstants.PID_TURN, DriveConstants.DRIVE_TIMEOUT_MS); - /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ - m_rightFrontMotor.configSelectedFeedbackCoefficient(1, DriveConstants.PID_TURN, DriveConstants.DRIVE_TIMEOUT_MS); + /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) DOESN'T WORK */ + //m_rightFrontMotor.configSelectedFeedbackCoefficient(1, DriveConstants.PID_TURN, DriveConstants.DRIVE_TIMEOUT_MS); - /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) */ - m_leftFrontMotor.configSelectedFeedbackCoefficient(1, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS); + /* Don't scale the Feedback Sensor (use 1 for 1:1 ratio) DOESN'T WORK */ + //m_leftFrontMotor.configSelectedFeedbackCoefficient(1, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS); /* Set status frame periods to ensure we don't have stale data */ m_rightFrontMotor.setStatusFramePeriod(StatusFrame.Status_12_Feedback1, 20, DriveConstants.DRIVE_TIMEOUT_MS); @@ -185,18 +209,8 @@ public class Drive extends SubsystemBase { m_leftFrontMotor.setStatusFramePeriod(StatusFrame.Status_2_Feedback0, 5, DriveConstants.DRIVE_TIMEOUT_MS); m_pigeon.setStatusFramePeriod(PigeonIMU_StatusFrame.CondStatus_9_SixDeg_YPR, 5, DriveConstants.DRIVE_TIMEOUT_MS); - /* Smart Dashboard Initial Values */ - - /* Gyro */ - SmartDashboard.putNumber("Pigeon Yaw", getGyroYaw()); - //SmartDashboard.putNumber("Pigeon Pitch", getGyroPitch()); - //SmartDashboard.putNumber("Pigeon Roll", getGyroRoll()); - - /* Sensor Values */ - //SmartDashboard.putNumber("Left Motor Velocity Raw", m_leftFrontMotor.getSelectedSensorVelocity(0)); - //SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); - //SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition(0)); - //SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition()); + m_leftBackMotor.setStatusFramePeriod(StatusFrame.Status_13_Base_PIDF0, 20, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightBackMotor.setStatusFramePeriod(StatusFrame.Status_13_Base_PIDF0, 20, DriveConstants.DRIVE_TIMEOUT_MS); /** * Max out the peak output (for all modes). However you can limit the output of @@ -207,6 +221,11 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.configPeakOutputForward(+1, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.configPeakOutputReverse(-1, DriveConstants.DRIVE_TIMEOUT_MS); + m_leftBackMotor.configPeakOutputForward(+1, DriveConstants.DRIVE_TIMEOUT_MS); + m_leftBackMotor.configPeakOutputReverse(-1, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightBackMotor.configPeakOutputForward(+1, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightBackMotor.configPeakOutputReverse(-1, DriveConstants.DRIVE_TIMEOUT_MS); + /** * 1ms per loop. PID loop can be slowed down if need be. For example, - if * sensor updates are too slow - sensor deltas are very small per update, so @@ -221,6 +240,15 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.configClosedLoopPeriod( DriveConstants.PID_TURN, closedLoopTimeMs, DriveConstants.DRIVE_TIMEOUT_MS); + + m_leftBackMotor.configClosedLoopPeriod( DriveConstants.PID_PRIMARY, + closedLoopTimeMs, + DriveConstants.DRIVE_TIMEOUT_MS); + + m_leftBackMotor.configClosedLoopPeriod( DriveConstants.PID_PRIMARY, + closedLoopTimeMs, + DriveConstants.DRIVE_TIMEOUT_MS); + /** * configAuxPIDPolarity(boolean invert, int timeoutMs) false means talon's local * output is PID0 + PID1, and other side Talon is PID0 - PID1 true means talon's @@ -247,16 +275,16 @@ public class Drive extends SubsystemBase { //SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); //SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition()); //SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition(0)); - //SmartDashboard.putNumber("Right Motor Velocity Int Sensor", m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); - //SmartDashboard.putNumber("Left Motor Velocity Int Sensor", m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + SmartDashboard.putNumber("Right Motor Velocity Int Sensor", m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + SmartDashboard.putNumber("Left Motor Velocity Int Sensor", m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); //SmartDashboard.putNumber("Right Front Motor Current", m_rightFrontMotor.getSupplyCurrent()); //SmartDashboard.putNumber("Left Front Motor Current", m_leftFrontMotor.getSupplyCurrent()); //SmartDashboard.putNumber("Right Back Motor Current", m_rightFrontMotor.getSupplyCurrent()); //SmartDashboard.putNumber("Left Back Motor Current", m_leftFrontMotor.getSupplyCurrent()); - //SmartDashboard.putNumber("PID 0 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); - //SmartDashboard.putNumber("PID 1 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); + SmartDashboard.putNumber("PID 0 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); + SmartDashboard.putNumber("PID 1 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); //SmartDashboard.putNumber("PID 0 Target", m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_PRIMARY)); //SmartDashboard.putNumber("PID 1 Target", m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN)); //SmartDashboard.putNumber("PID 0 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY)); @@ -271,8 +299,8 @@ public class Drive extends SubsystemBase { } m_odometry.update(Rotation2d.fromDegrees( getHeading()), - inchesToMeters(getDistanceInches(m_leftFrontMotor)), - inchesToMeters(-getDistanceInches(m_rightFrontMotor))); + inchesToMeters(getDistanceInches(m_leftBackMotor)), + -inchesToMeters(getDistanceInches(m_rightBackMotor))); } /** @@ -293,6 +321,8 @@ public class Drive extends SubsystemBase { */ public void driveWithInput(double move, double steer) { m_driveTrain.arcadeDrive(move, steer); + m_leftBackMotor.follow(m_leftFrontMotor); + m_rightBackMotor.follow(m_rightFrontMotor); } /** @@ -305,6 +335,8 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.set(TalonFXControlMode.PercentOutput, move, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); + m_leftBackMotor.follow(m_leftFrontMotor); + m_rightBackMotor.follow(m_rightFrontMotor); m_driveTrain.feedWatchdog(); } @@ -321,6 +353,8 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.set(TalonFXControlMode.Position, targetPos, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); + m_leftBackMotor.follow(m_leftFrontMotor); + m_rightBackMotor.follow(m_rightFrontMotor); m_driveTrain.feedWatchdog(); } @@ -334,8 +368,11 @@ public class Drive extends SubsystemBase { public void runDriveVelocityPID(double targetVel, double targetGyro) { m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); + m_rightFrontMotor.set(TalonFXControlMode.Velocity, targetVel, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); + m_leftBackMotor.follow(m_leftFrontMotor); + m_rightBackMotor.follow(m_rightFrontMotor); m_driveTrain.feedWatchdog(); } @@ -351,6 +388,8 @@ public class Drive extends SubsystemBase { m_rightFrontMotor.set(ControlMode.MotionMagic, targetPos, DemandType.AuxPID, targetGyro); m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1); + m_leftBackMotor.follow(m_leftFrontMotor); + m_rightBackMotor.follow(m_rightFrontMotor); m_driveTrain.feedWatchdog(); } @@ -369,33 +408,38 @@ public class Drive extends SubsystemBase { /** * Controls the left and right sides of the drive with velocity targets. * - * @param leftSpeed the commanded left output - * @param rightSpeed the commanded right output + * @param leftSpeed the commanded left speed + * @param rightSpeed the commanded right speed */ public void tankDriveVelocity(double leftSpeed, double rightSpeed) { - DifferentialDriveWheelSpeeds wheelSpeeds = new DifferentialDriveWheelSpeeds(leftSpeed, rightSpeed); - ChassisSpeeds chassisSpeeds = DriveConstants.kDriveKinematics.toChassisSpeeds(wheelSpeeds); - double moveVelMPS = chassisSpeeds.vxMetersPerSecond; - double angleVelRad = chassisSpeeds.omegaRadiansPerSecond; - double angleVelDeg = Math.toDegrees(angleVelRad); + //DifferentialDriveWheelSpeeds wheelSpeeds = new DifferentialDriveWheelSpeeds(leftSpeed, rightSpeed); + //ChassisSpeeds chassisSpeeds = DriveConstants.kDriveKinematics.toChassisSpeeds(wheelSpeeds); + //double moveVelMPS = chassisSpeeds.vxMetersPerSecond; + //double angleVelRad = chassisSpeeds.omegaRadiansPerSecond; + //double angleVelDeg = Math.toDegrees(angleVelRad); - m_kinematicsTargetAngle += angleVelDeg * (m_deltaTime/1000); - m_kinematicsTargetAngle = MathUtil.clamp( m_kinematicsTargetAngle, - m_currentAngleYaw-(360), - m_currentAngleYaw+(360)); - double targetGyro = (m_kinematicsTargetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV; - double moveVel = inchesToTicks(metersToInches(moveVelMPS))/DriveConstants.SECONDS_TO_TICK_TIME; - //double moveVelRight = inchesToTicks(metersToInches(rightSpeed))/DriveConstants.SECONDS_TO_TICK_TIME; + //m_kinematicsTargetAngle += angleVelDeg * (m_deltaTime/1000); + //m_kinematicsTargetAngle = MathUtil.clamp( m_kinematicsTargetAngle, + // m_currentAngleYaw-(360), + // m_currentAngleYaw+(360)); + //double targetGyro = (m_kinematicsTargetAngle / 360) * DriveConstants.TICKS_PER_GYRO_REV; + double moveVelLeft = inchesToTicks(metersToInches(leftSpeed))/DriveConstants.SECONDS_TO_TICK_TIME; + double moveVelRight = inchesToTicks(metersToInches(rightSpeed))/DriveConstants.SECONDS_TO_TICK_TIME; //SmartDashboard.putNumber("Move Vel Left", moveVelLeft); //SmartDashboard.putNumber("Move Vel Right", moveVelRight); - runDriveVelocityPID(moveVel*2, targetGyro); + //runDriveVelocityPID(moveVel*2, targetGyro); - //m_rightFrontMotor.set(TalonFXControlMode.Velocity, moveVelRight); - //m_leftFrontMotor.set(TalonFXControlMode.Velocity, moveVelLeft); + m_rightBackMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); + m_leftBackMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); - //m_driveTrain.feedWatchdog(); + m_rightBackMotor.set(TalonFXControlMode.Velocity, moveVelRight); + m_leftBackMotor.set(TalonFXControlMode.Velocity, moveVelLeft); + m_leftFrontMotor.follow(m_leftFrontMotor); + m_rightFrontMotor.follow(m_rightFrontMotor); + + m_driveTrain.feedWatchdog(); } /** @@ -486,8 +530,8 @@ public class Drive extends SubsystemBase { * @return The current wheel speeds. */ public DifferentialDriveWheelSpeeds getWheelSpeeds() { - return new DifferentialDriveWheelSpeeds( inchesToMeters(getVelocityInchesPerSecond(m_leftFrontMotor)), - inchesToMeters(getVelocityInchesPerSecond(m_rightFrontMotor))); + return new DifferentialDriveWheelSpeeds( inchesToMeters(getVelocityInchesPerSecond(m_leftBackMotor)), + -inchesToMeters(getVelocityInchesPerSecond(m_rightBackMotor))); } /** @@ -496,6 +540,8 @@ public class Drive extends SubsystemBase { public void resetEncoders() { m_leftFrontMotor.getSensorCollection().setIntegratedSensorPosition(0, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.getSensorCollection().setIntegratedSensorPosition(0, DriveConstants.DRIVE_TIMEOUT_MS); + m_leftBackMotor.getSensorCollection().setIntegratedSensorPosition(0, DriveConstants.DRIVE_TIMEOUT_MS); + m_rightBackMotor.getSensorCollection().setIntegratedSensorPosition(0, DriveConstants.DRIVE_TIMEOUT_MS); } /** From 1aa9037285a8f60a8eeddedfd76fa4bbc5c54c52 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Mon, 17 Feb 2020 13:10:10 -0700 Subject: [PATCH 22/44] Cleanup DeadAssist --- .../DriveWithJoystickUsingDeadAssistPID.java | 48 +++++++++---------- 1 file changed, 22 insertions(+), 26 deletions(-) diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index 5cfb24d..be92dc7 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -15,10 +15,9 @@ import frc4388.utility.controller.IHandController; public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { Drive m_drive; - double m_targetGyro; - long lastTime; + double m_targetGyro, m_currentGyro; + long m_lastTime, m_deltaTime; IHandController m_controller; - boolean isAuxPIDEnabled = false; /** * Creates a new DriveWithJoystickUsingDeadAssistPID to control the drivetrain with an Xbox controller. @@ -39,32 +38,19 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { // Called when the command is initially scheduled. @Override public void initialize() { - lastTime = System.currentTimeMillis(); + m_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); + m_currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); double moveInput = -m_controller.getLeftYAxis(); double steerInput = m_controller.getRightXAxis(); double moveOutput = 0; double steerOutput = 0; - long deltaTime = System.currentTimeMillis() - lastTime; - lastTime = System.currentTimeMillis(); - - /* If AuxPID is enabled, then update using the steer input */ - if (isAuxPIDEnabled) { - 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)); - } - /* Otherwise set target angle to current angle (prevents buildup of gyro error) */ - else { - m_targetGyro = currentGyro; - } + m_deltaTime = System.currentTimeMillis() - m_lastTime; + m_lastTime = System.currentTimeMillis(); /* If move stick is being used */ if (moveInput != 0) { @@ -85,31 +71,41 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { } else { steerOutput = cosMultiplier*Math.cos(1.571*steerInput)-(cosMultiplier+deadzone); } + resetGyroTarget(); m_drive.driveWithInput(moveOutput, steerOutput); System.out.println("Driving With Input"); - isAuxPIDEnabled = false; } /* If only the move stick is being used */ else { + updateGyroTarget(steerInput); m_drive.driveWithInputAux(moveOutput, m_targetGyro); System.out.println("Driving with Input Aux with Target: " + m_targetGyro); - isAuxPIDEnabled = true; } } /* If the move stick is not being used */ else { + updateGyroTarget(steerInput); m_drive.runDriveStraightVelocityPID(0, m_targetGyro); System.out.println("Driving with Velocity PID with Target: " + m_targetGyro); - isAuxPIDEnabled = true; } } - private void updateGyroTarget() { - + /** + * If AuxPID is enabled, then update using the steer input + */ + private void updateGyroTarget(double steerInput) { + m_targetGyro += 2 * steerInput * m_deltaTime; + + m_targetGyro = MathUtil.clamp( m_targetGyro, + m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/4), + m_currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/4)); } + /** + * set target angle to current angle (prevents buildup of gyro error). + */ private void resetGyroTarget() { - + m_targetGyro = m_currentGyro; } // Called once the command ends or is interrupted. From b729d04db44367de4ddf6e6b13a15513a0fd8764 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Mon, 17 Feb 2020 18:25:48 -0700 Subject: [PATCH 23/44] rework Deadassist to enable after a timeout This keeps it out of the hair of the drivers while also possibly being useful --- .../java/frc4388/robot/RobotContainer.java | 2 +- .../DriveWithJoystickUsingDeadAssistPID.java | 75 ++++++++++++------- .../java/frc4388/robot/subsystems/Drive.java | 8 +- 3 files changed, 54 insertions(+), 31 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 528a9e2..2a244bb 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -78,7 +78,7 @@ public class RobotContainer { /* Default Commands */ // drives the robot with a two-axis input from the driver controller - m_robotDrive.setDefaultCommand(new DriveWithJoystick(m_robotDrive, getDriverController())); + m_robotDrive.setDefaultCommand(new DriveWithJoystickUsingDeadAssistPID(m_robotDrive, getDriverController())); // drives intake with input from triggers on the opperator controller m_robotIntake.setDefaultCommand(new RunIntakeWithTriggers(m_robotIntake, getOperatorController())); // drives climber with input from triggers on the opperator controller diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index 53ec7ee..d0e95a6 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -16,7 +16,9 @@ import frc4388.utility.controller.IHandController; public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { Drive m_drive; double m_targetGyro, m_currentGyro; - long m_lastTime, m_deltaTime; + long m_currTime, m_deltaTime; + long m_deadTimeSteer, m_deadTimeMove; + long m_deadTimeout = 500; IHandController m_controller; /** @@ -38,7 +40,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { // Called when the command is initially scheduled. @Override public void initialize() { - m_lastTime = System.currentTimeMillis(); + m_currTime = System.currentTimeMillis(); } // Called every time the scheduler runs while the command is scheduled. @@ -48,12 +50,20 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { double moveInput = -m_controller.getLeftYAxis(); double steerInput = m_controller.getRightXAxis(); double moveOutput = 0; - double steerOutput = 0; - m_deltaTime = System.currentTimeMillis() - m_lastTime; - m_lastTime = System.currentTimeMillis(); + m_deltaTime = System.currentTimeMillis() - m_currTime; + m_currTime = System.currentTimeMillis(); /* If move stick is being used */ if (moveInput != 0) { + m_deadTimeMove = m_currTime; + } + /* If steer stick is being used */ + if (steerInput != 0) { + m_deadTimeSteer = m_currTime; + } + + /* If move stick has not been pressed for 1 sec */ + if (m_currTime - m_deadTimeMove < m_deadTimeout) { /* Curves the moveInput to be slightly more gradual at first */ if (moveInput >= 0) { moveOutput = -Math.cos(1.571*moveInput)+1; @@ -61,35 +71,48 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { moveOutput = Math.cos(1.571*moveInput)-1; } - /* If steer stick is being used. */ - if (steerInput != 0) { - double cosMultiplier = .45; - double deadzone = .2; - /* Curves the steer output to be similarily gradual */ - if (steerInput > 0){ - steerOutput = -cosMultiplier*Math.cos(1.571*steerInput)+(cosMultiplier+deadzone); - } else { - steerOutput = cosMultiplier*Math.cos(1.571*steerInput)-(cosMultiplier+deadzone); - } - resetGyroTarget(); - m_drive.driveWithInput(moveOutput, steerOutput); - System.out.println("Driving With Input"); + /* If steer stick has not been used for less than 1 sec */ + if (m_currTime - m_deadTimeSteer < m_deadTimeout) { + runDriveWithInput(moveOutput, steerInput); + m_deadTimeSteer = m_currTime; } - /* If only the move stick is being used */ + /* If steer stick has not been used for 1 sec */ else { - updateGyroTarget(steerInput); - m_drive.driveWithInputAux(moveOutput, m_targetGyro); - System.out.println("Driving with Input Aux with Target: " + m_targetGyro); + runDriveStraight(moveOutput); } } - /* If the move stick is not being used */ + /* If the move stick has not been used for 1 sec */ else { - updateGyroTarget(steerInput); - m_drive.runDriveStraightVelocityPID(0, m_targetGyro); - System.out.println("Driving with Velocity PID with Target: " + m_targetGyro); + runStoppedTurn(steerInput); } } + private void runDriveWithInput(double move, double steer) { + double cosMultiplier = .45; + double steerOutput = 0; + double deadzone = .2; + /* Curves the steer output to be similarily gradual */ + if (steer > 0){ + steerOutput = -cosMultiplier*Math.cos(1.571*steer)+(cosMultiplier+deadzone); + } else { + steerOutput = cosMultiplier*Math.cos(1.571*steer)-(cosMultiplier+deadzone); + } + resetGyroTarget(); + m_drive.driveWithInput(move, steerOutput); + System.out.println("Driving With Input"); + } + + private void runDriveStraight(double move) { + m_drive.driveWithInputAux(move, m_targetGyro); + System.out.println("Driving with Input Aux with Target: " + m_targetGyro); + } + + private void runStoppedTurn(double steer) { + updateGyroTarget(steer); + m_drive.runDriveVelocityPID(0, m_targetGyro); + System.out.println("Driving with Velocity PID with Target: " + m_targetGyro); + } + /** * If AuxPID is enabled, then update using the steer input */ diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index ed48967..c18a1d6 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -278,10 +278,10 @@ public class Drive extends SubsystemBase { SmartDashboard.putNumber("Right Motor Velocity Int Sensor", m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); SmartDashboard.putNumber("Left Motor Velocity Int Sensor", m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); - //SmartDashboard.putNumber("Right Front Motor Current", m_rightFrontMotor.getSupplyCurrent()); - //SmartDashboard.putNumber("Left Front Motor Current", m_leftFrontMotor.getSupplyCurrent()); - //SmartDashboard.putNumber("Right Back Motor Current", m_rightFrontMotor.getSupplyCurrent()); - //SmartDashboard.putNumber("Left Back Motor Current", m_leftFrontMotor.getSupplyCurrent()); + SmartDashboard.putNumber("Right Front Motor Current Supply", m_rightFrontMotor.getSupplyCurrent()); + SmartDashboard.putNumber("Left Front Motor Current Supply", m_leftFrontMotor.getSupplyCurrent()); + SmartDashboard.putNumber("Right Front Motor Current Stator ", m_rightFrontMotor.getStatorCurrent()); + SmartDashboard.putNumber("Left Front Motor Current Stator", m_leftFrontMotor.getSupplyCurrent()); SmartDashboard.putNumber("PID 0 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); SmartDashboard.putNumber("PID 1 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); From 6f8e8f8b8f95e8b97ff4f48278457f2fd4c487f1 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Tue, 18 Feb 2020 16:56:56 -0700 Subject: [PATCH 24/44] Added Variable to get Right Motor Pos and Vel --- src/main/java/frc4388/robot/RobotContainer.java | 2 +- src/main/java/frc4388/robot/subsystems/Drive.java | 11 ++++++++++- 2 files changed, 11 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 2a244bb..941afe0 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -169,7 +169,7 @@ public class RobotContainer { public void configDriveTrainSensors(FeedbackDevice type) { m_robotDrive.configMotorSensor(type); - } + } public void resetOdometry() { m_robotDrive.resetGyroAngles(); diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index c18a1d6..0d23a08 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -49,6 +49,10 @@ public class Drive extends SubsystemBase { public WPI_TalonFX m_rightBackMotor = new WPI_TalonFX(DriveConstants.DRIVE_RIGHT_BACK_CAN_ID); public static PigeonIMU m_pigeon = new PigeonIMU(DriveConstants.PIGEON_ID); + public double m_rightFrontMotorPos; + + public double m_rightFrontMotorVel; + public DifferentialDrive m_driveTrain = new DifferentialDrive(m_leftFrontMotor, m_rightFrontMotor); SendableChooser m_chooser = new SendableChooser(); @@ -265,6 +269,11 @@ public class Drive extends SubsystemBase { m_lastTime = System.currentTimeMillis(); m_lastAngleYaw = m_currentAngleYaw; m_currentAngleYaw = getGyroYaw(); + + m_rightFrontMotorPos = m_rightFrontMotor.getSelectedSensorPosition(); + + m_rightFrontMotorVel = m_rightFrontMotor.getSelectedSensorVelocity(); + try { SmartDashboard.putNumber("Pigeon Yaw", getGyroYaw()); @@ -459,7 +468,7 @@ public class Drive extends SubsystemBase { m_pigeon.getYawPitchRoll(ypr); return ypr[0]; - } + } /** * Returns the current pitch of the pigeon From c5011b72d70771f473f2176ee176e7e70c00948b Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Tue, 18 Feb 2020 17:29:26 -0700 Subject: [PATCH 25/44] Tune the teleop controller --- src/main/java/frc4388/robot/Constants.java | 12 +++---- .../DriveWithJoystickUsingDeadAssistPID.java | 31 ++++++++++++------ .../java/frc4388/robot/subsystems/Drive.java | 32 +++++++++---------- 3 files changed, 44 insertions(+), 31 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 92d6a05..4dcbaaf 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -29,12 +29,12 @@ public final class Constants { /* PID Constants Drive*/ public static final int DRIVE_TIMEOUT_MS = 30; - public static final Gains DRIVE_DISTANCE_GAINS = new Gains(0.2, 0.0, 0.0, 0.0, 0, 0.3); - public static final Gains DRIVE_VELOCITY_GAINS = new Gains(0.05, 0.0, 0.0, 0.025, 0, 1.0); - public static final Gains DRIVE_TURNING_GAINS = new Gains(0.5, 0.0, 0.0, 0.0, 0, 0.5); - 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 = 20000; - public static final int DRIVE_ACCELERATION = 7000; + public static final Gains DRIVE_DISTANCE_GAINS = new Gains(0.1, 0.0, 1.0, 0.0, 0, 0.3); + public static final Gains DRIVE_VELOCITY_GAINS = new Gains(0.1, 0.0, 0.2, 0.025, 0, 0.05); + public static final Gains DRIVE_TURNING_GAINS = new Gains(0.5, 0.0, 0.0, 0.05, 0, 0.5); + //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 = 20000; + //public static final int DRIVE_ACCELERATION = 7000; /* Trajectory Constants */ public static final double MAX_SPEED_METERS_PER_SECOND = 3; diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index d0e95a6..74b662e 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -16,9 +16,10 @@ import frc4388.utility.controller.IHandController; public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { Drive m_drive; double m_targetGyro, m_currentGyro; + double m_stopPos; long m_currTime, m_deltaTime; long m_deadTimeSteer, m_deadTimeMove; - long m_deadTimeout = 500; + long m_deadTimeout = 100; IHandController m_controller; /** @@ -56,13 +57,15 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { /* If move stick is being used */ if (moveInput != 0) { m_deadTimeMove = m_currTime; + m_stopPos = m_drive.m_rightFrontMotor.getSelectedSensorPosition() + + (m_drive.m_rightFrontMotor.getSelectedSensorVelocity()); } /* If steer stick is being used */ if (steerInput != 0) { m_deadTimeSteer = m_currTime; } - /* If move stick has not been pressed for 1 sec */ + /* If move stick has been pressed within 1 sec */ if (m_currTime - m_deadTimeMove < m_deadTimeout) { /* Curves the moveInput to be slightly more gradual at first */ if (moveInput >= 0) { @@ -74,7 +77,6 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { /* If steer stick has not been used for less than 1 sec */ if (m_currTime - m_deadTimeSteer < m_deadTimeout) { runDriveWithInput(moveOutput, steerInput); - m_deadTimeSteer = m_currTime; } /* If steer stick has not been used for 1 sec */ else { @@ -103,21 +105,30 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { } private void runDriveStraight(double move) { - m_drive.driveWithInputAux(move, m_targetGyro); - System.out.println("Driving with Input Aux with Target: " + m_targetGyro); + m_drive.driveWithInputAux(move * 3/4, m_targetGyro); + System.out.println("Driving Straight with Target: " + m_targetGyro); } private void runStoppedTurn(double steer) { updateGyroTarget(steer); - m_drive.runDriveVelocityPID(0, m_targetGyro); - System.out.println("Driving with Velocity PID with Target: " + m_targetGyro); + m_drive.runDrivePositionPID(m_stopPos, m_targetGyro); + + System.out.println("Turning with Target: " + m_targetGyro); + + /* if (m_drive.m_rightFrontMotor.getSelectedSensorVelocity() > 3000) { + m_drive.driveWithInputAux(0, m_targetGyro); + System.out.println("!Turning with Target: " + m_targetGyro); + } else { + m_drive.runDriveVelocityPID(0, m_targetGyro); + System.out.println("Turning with Target: " + m_targetGyro); + }*/ } /** * If AuxPID is enabled, then update using the steer input */ private void updateGyroTarget(double steerInput) { - m_targetGyro += 2 * steerInput * m_deltaTime; + m_targetGyro -= 5 * steerInput * m_deltaTime; m_targetGyro = MathUtil.clamp( m_targetGyro, m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/4), @@ -128,7 +139,9 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { * set target angle to current angle (prevents buildup of gyro error). */ private void resetGyroTarget() { - m_targetGyro = m_currentGyro; + //m_targetGyro = m_currentGyro; + m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(1) + + (3 * m_drive.m_rightFrontMotor.getSelectedSensorVelocity(1)); } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index c18a1d6..7d96e13 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -55,7 +55,7 @@ public class Drive extends SubsystemBase { public static Gains m_gainsDistance = DriveConstants.DRIVE_DISTANCE_GAINS; public static Gains m_gainsVelocity = DriveConstants.DRIVE_VELOCITY_GAINS; public static Gains m_gainsTurning = DriveConstants.DRIVE_TURNING_GAINS; - public static Gains m_gainsMotionMagic = DriveConstants.DRIVE_MOTION_MAGIC_GAINS; + //public static Gains m_gainsMotionMagic = DriveConstants.DRIVE_MOTION_MAGIC_GAINS; public final DifferentialDriveOdometry m_odometry; @@ -101,12 +101,12 @@ public class Drive extends SubsystemBase { //m_rightFrontMotor.configNeutralDeadband(0.0, DriveConstants.DRIVE_TIMEOUT_MS); // Ensures motors run at the same speed /* PID for Front Motor Control in Teleop */ - m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); - m_rightFrontMotor.config_kF(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kP(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kI(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.config_kD(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); - m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); + //m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); + //m_rightFrontMotor.config_kF(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); + //m_rightFrontMotor.config_kP(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kP, DriveConstants.DRIVE_TIMEOUT_MS); + //m_rightFrontMotor.config_kI(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kI, DriveConstants.DRIVE_TIMEOUT_MS); + //m_rightFrontMotor.config_kD(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kD, DriveConstants.DRIVE_TIMEOUT_MS); + //m_rightFrontMotor.configClosedLoopPeakOutput(DriveConstants.SLOT_VELOCITY, m_gainsVelocity.m_kPeakOutput, DriveConstants.DRIVE_TIMEOUT_MS); m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN); m_rightFrontMotor.config_kF(DriveConstants.SLOT_TURNING, m_gainsTurning.m_kF, DriveConstants.DRIVE_TIMEOUT_MS); @@ -122,15 +122,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.configClosedLoopPeakOutput( DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kPeakOutput, 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); + //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.configClosedLoopPeakOutput( DriveConstants.SLOT_MOTION_MAGIC, m_gainsMotionMagic.m_kPeakOutput, 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); /* PID for Back Motor control in Auto */ m_rightBackMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); From 2c47b71534c774e1e46a320e926d9cb9e181ae0a Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Tue, 18 Feb 2020 17:36:57 -0700 Subject: [PATCH 26/44] Update Drive.java Added Back Motor Velocities and Outputs. --- .../java/frc4388/robot/subsystems/Drive.java | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 0d23a08..8043229 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -279,21 +279,23 @@ public class Drive extends SubsystemBase { SmartDashboard.putNumber("Pigeon Yaw", getGyroYaw()); //SmartDashboard.putNumber("Pigeon Pitch", getGyroPitch()); //SmartDashboard.putNumber("Pigeon Roll", getGyroRoll()); + SmartDashboard.putNumber("Left Back Output", m_leftBackMotor.get()); + SmartDashboard.putNumber("Right Back Output", m_rightBackMotor.get()); - //SmartDashboard.putNumber("Left Motor Velocity Raw", m_leftFrontMotor.getSelectedSensorVelocity(0)); - //SmartDashboard.putNumber("Right Motor Velocity Raw", m_rightFrontMotor.getSelectedSensorVelocity()); + SmartDashboard.putNumber("Left Back Motor Velocity Raw", m_leftBackMotor.getSelectedSensorVelocity()); + SmartDashboard.putNumber("Right Back Motor Velocity Raw", m_rightBackMotor.getSelectedSensorVelocity()); //SmartDashboard.putNumber("Left Motor Position Raw", m_leftFrontMotor.getSelectedSensorPosition()); //SmartDashboard.putNumber("Right Motor Position Raw", m_rightFrontMotor.getSelectedSensorPosition(0)); SmartDashboard.putNumber("Right Motor Velocity Int Sensor", m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); SmartDashboard.putNumber("Left Motor Velocity Int Sensor", m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); - SmartDashboard.putNumber("Right Front Motor Current Supply", m_rightFrontMotor.getSupplyCurrent()); - SmartDashboard.putNumber("Left Front Motor Current Supply", m_leftFrontMotor.getSupplyCurrent()); - SmartDashboard.putNumber("Right Front Motor Current Stator ", m_rightFrontMotor.getStatorCurrent()); - SmartDashboard.putNumber("Left Front Motor Current Stator", m_leftFrontMotor.getSupplyCurrent()); + //SmartDashboard.putNumber("Right Front Motor Current Supply", m_rightFrontMotor.getSupplyCurrent()); + //SmartDashboard.putNumber("Left Front Motor Current Supply", m_leftFrontMotor.getSupplyCurrent()); + //SmartDashboard.putNumber("Right Front Motor Current Stator ", m_rightFrontMotor.getStatorCurrent()); + //SmartDashboard.putNumber("Left Front Motor Current Stator", m_leftFrontMotor.getSupplyCurrent()); - SmartDashboard.putNumber("PID 0 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); - SmartDashboard.putNumber("PID 1 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); + //SmartDashboard.putNumber("PID 0 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY)); + //SmartDashboard.putNumber("PID 1 Error", m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN)); //SmartDashboard.putNumber("PID 0 Target", m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_PRIMARY)); //SmartDashboard.putNumber("PID 1 Target", m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN)); //SmartDashboard.putNumber("PID 0 Pos", m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY)); From d1af80a114fdb33e7f7c90f1069b65cb8698e3c9 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Tue, 18 Feb 2020 17:52:47 -0700 Subject: [PATCH 27/44] Changed Gearing Buttons to Bumpers --- src/main/java/frc4388/robot/RobotContainer.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 941afe0..80484b4 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -134,11 +134,11 @@ public class RobotContainer { .whenPressed(new RunCommand(() -> m_robotDrive.driveWithInputAux(0.2, 0), m_robotDrive)); // sets solenoids into high gear - new JoystickButton(getDriverJoystick(), XboxController.START_BUTTON) + new JoystickButton(getDriverJoystick(), XboxController.RIGHT_BUMPER_BUTTON) .whenPressed(new InstantCommand(() -> m_robotDrive.setShiftState(true), m_robotDrive)); // sets solenoids into low gear - new JoystickButton(getDriverJoystick(), XboxController.BACK_BUTTON) + new JoystickButton(getDriverJoystick(), XboxController.LEFT_BUMPER_BUTTON) .whenPressed(new InstantCommand(() -> m_robotDrive.setShiftState(false), m_robotDrive)); // interrupts any running command From cce4f67726ad1016ae0a1ec5693f1b3e4d3d5e71 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Tue, 18 Feb 2020 19:07:42 -0700 Subject: [PATCH 28/44] Add temp sensing --- src/main/java/frc4388/robot/subsystems/Drive.java | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 32d540f..9571f66 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -271,9 +271,7 @@ public class Drive extends SubsystemBase { m_currentAngleYaw = getGyroYaw(); m_rightFrontMotorPos = m_rightFrontMotor.getSelectedSensorPosition(); - m_rightFrontMotorVel = m_rightFrontMotor.getSelectedSensorVelocity(); - try { SmartDashboard.putNumber("Pigeon Yaw", getGyroYaw()); @@ -289,6 +287,9 @@ public class Drive extends SubsystemBase { SmartDashboard.putNumber("Right Motor Velocity Int Sensor", m_rightFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); SmartDashboard.putNumber("Left Motor Velocity Int Sensor", m_leftFrontMotor.getSensorCollection().getIntegratedSensorVelocity()); + SmartDashboard.putNumber("Right Motor Temp", m_rightFrontMotor.getTemperature()); + SmartDashboard.putNumber("Left Motor Temp", m_leftFrontMotor.getTemperature()); + //SmartDashboard.putNumber("Right Front Motor Current Supply", m_rightFrontMotor.getSupplyCurrent()); //SmartDashboard.putNumber("Left Front Motor Current Supply", m_leftFrontMotor.getSupplyCurrent()); //SmartDashboard.putNumber("Right Front Motor Current Stator ", m_rightFrontMotor.getStatorCurrent()); From cdf2d64157315905ecd8666832e9895693dd414f Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Tue, 18 Feb 2020 19:22:18 -0700 Subject: [PATCH 29/44] Renamed speedShift, declared coolFalcon --- src/main/java/frc4388/robot/subsystems/Drive.java | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 9571f66..aef4006 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -63,7 +63,8 @@ public class Drive extends SubsystemBase { public final DifferentialDriveOdometry m_odometry; - public DoubleSolenoid speedShift; + public DoubleSolenoid m_speedShift; + public DoubleSolenoid m_coolFalcon; public long m_lastTime, m_deltaTime; //in milliseconds @@ -83,8 +84,9 @@ public class Drive extends SubsystemBase { m_odometry = new DifferentialDriveOdometry(Rotation2d.fromDegrees(getHeading()), new Pose2d(0, 0, new Rotation2d())); - speedShift = new DoubleSolenoid(7,0,1); - + m_speedShift = new DoubleSolenoid(7,0,1); + m_coolFalcon = new DoubleSolenoid(7,3,2); + /* set back motors as followers */ m_leftBackMotor.follow(m_leftFrontMotor); m_rightBackMotor.follow(m_rightFrontMotor); @@ -626,10 +628,10 @@ public class Drive extends SubsystemBase { */ public void setShiftState(boolean state) { if (state == true) { - speedShift.set(DoubleSolenoid.Value.kForward); + m_speedShift.set(DoubleSolenoid.Value.kForward); } if (state == false) { - speedShift.set(DoubleSolenoid.Value.kReverse); + m_speedShift.set(DoubleSolenoid.Value.kReverse); } } } From 14793f3cef10ed843e63426693d5132c5629ca3a Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Tue, 18 Feb 2020 19:25:32 -0700 Subject: [PATCH 30/44] Added method to open and close solenoid, started solenoid closed --- .../java/frc4388/robot/subsystems/Drive.java | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index aef4006..9fa438a 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -86,6 +86,8 @@ public class Drive extends SubsystemBase { m_speedShift = new DoubleSolenoid(7,0,1); m_coolFalcon = new DoubleSolenoid(7,3,2); + + coolFalcon(false); /* set back motors as followers */ m_leftBackMotor.follow(m_leftFrontMotor); @@ -634,4 +636,18 @@ public class Drive extends SubsystemBase { m_speedShift.set(DoubleSolenoid.Value.kReverse); } } + + /** + * Set to open or close solenoid that cools the falcon, true = open, false = close + * @param state Chooses between open and close + */ + public void coolFalcon(boolean state) { + if (state == true) { + m_coolFalcon.set(DoubleSolenoid.Value.kForward); + } + if (state == false) { + m_coolFalcon.set(DoubleSolenoid.Value.kReverse); + } + } + } From 24e0d07f3a3b1755ea6586c60c8cf824b451abe6 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Tue, 18 Feb 2020 19:28:05 -0700 Subject: [PATCH 31/44] Added opening every 10 seconds --- src/main/java/frc4388/robot/subsystems/Drive.java | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 9fa438a..58c14fb 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -66,6 +66,8 @@ public class Drive extends SubsystemBase { public DoubleSolenoid m_speedShift; public DoubleSolenoid m_coolFalcon; + public int m_currentTimeSec = (int)(System.currentTimeMillis() * 1000); + public long m_lastTime, m_deltaTime; //in milliseconds public double m_lastAngleYaw, m_currentAngleYaw, m_kinematicsTargetAngle; @@ -269,6 +271,13 @@ public class Drive extends SubsystemBase { @Override public void periodic() { + + if (m_currentTimeSec % 10 == 0) { + coolFalcon(true); + } else if ((m_currentTimeSec - 2) % 10 == 0) { + coolFalcon(false); + } + m_deltaTime = System.currentTimeMillis() - m_lastTime; m_lastTime = System.currentTimeMillis(); m_lastAngleYaw = m_currentAngleYaw; From 6cc1f7fb50a79df2096d4c61cef7f0c5d7f82f0d Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Tue, 18 Feb 2020 19:44:11 -0700 Subject: [PATCH 32/44] Messing with Dead Assist --- .../DriveWithJoystickUsingDeadAssistPID.java | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index 74b662e..7eff284 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -77,6 +77,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { /* If steer stick has not been used for less than 1 sec */ if (m_currTime - m_deadTimeSteer < m_deadTimeout) { runDriveWithInput(moveOutput, steerInput); + resetGyroTarget(); } /* If steer stick has not been used for 1 sec */ else { @@ -99,7 +100,6 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { } else { steerOutput = cosMultiplier*Math.cos(1.571*steer)-(cosMultiplier+deadzone); } - resetGyroTarget(); m_drive.driveWithInput(move, steerOutput); System.out.println("Driving With Input"); } @@ -131,17 +131,17 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { m_targetGyro -= 5 * steerInput * m_deltaTime; m_targetGyro = MathUtil.clamp( m_targetGyro, - m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/4), - m_currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/4)); + m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/8), + m_currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/8)); } /** * set target angle to current angle (prevents buildup of gyro error). */ private void resetGyroTarget() { - //m_targetGyro = m_currentGyro; - m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(1) - + (3 * m_drive.m_rightFrontMotor.getSelectedSensorVelocity(1)); + m_targetGyro = m_currentGyro; + m_targetGyro = m_currentGyro + + (3 * m_drive.m_rightFrontMotor.getSelectedSensorVelocity(1)); } // Called once the command ends or is interrupted. From 8f039ce40af5581fef5ae48e797aace4c185ece2 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Wed, 19 Feb 2020 08:46:55 -0700 Subject: [PATCH 33/44] Create DriveWithJoystickStraight to have an assist that doesn't use stopped turns --- .../DriveWithJoystickDriveStraight.java | 118 ++++++++++++++++++ 1 file changed, 118 insertions(+) create mode 100644 src/main/java/frc4388/robot/commands/DriveWithJoystickDriveStraight.java diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickDriveStraight.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickDriveStraight.java new file mode 100644 index 0000000..2a30287 --- /dev/null +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickDriveStraight.java @@ -0,0 +1,118 @@ +/*----------------------------------------------------------------------------*/ +/* 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 edu.wpi.first.wpiutil.math.MathUtil; +import frc4388.robot.Constants.DriveConstants; +import frc4388.robot.subsystems.Drive; +import frc4388.utility.controller.IHandController; + +public class DriveWithJoystickDriveStraight extends CommandBase { + Drive m_drive; + double m_targetGyro, m_currentGyro; + double m_stopPos; + long m_currTime, m_deltaTime; + long m_deadTimeSteer, m_deadTimeMove; + long m_deadTimeout = 100; + IHandController m_controller; + + /** + * Creates a new DriveWithJoystickDriveStraight to control the drivetrain with an Xbox controller. + * Applies a curved ramp to the input from the controllers to make the robot less "touchy". + * Also uses PIDs to keep the robot on course when given a "dead" or 0 input. + * @param subsystem pass the Drive subsystem from {@link frc4388.robot.RobotContainer#RobotContainer() RobotContainer} + * @param controller pass the Driver {@link frc4388.utility.controller.IHandController#getClass() IHandController} using the + * {@link frc4388.robot.RobotContainer#getDriverJoystick() getDriverJoystick()} method in + * {@link frc4388.robot.RobotContainer#RobotContainer() RobotContainer} + */ + public DriveWithJoystickDriveStraight(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_currTime = System.currentTimeMillis(); + } + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + m_currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + double moveInput = -m_controller.getLeftYAxis(); + double steerInput = m_controller.getRightXAxis(); + double moveOutput = 0; + m_deltaTime = System.currentTimeMillis() - m_currTime; + m_currTime = System.currentTimeMillis(); + + /* If steer stick is being used */ + if (steerInput != 0) { + m_deadTimeSteer = m_currTime; + } + + /* Curves the moveInput to be slightly more gradual at first */ + if (moveInput >= 0) { + moveOutput = -Math.cos(1.571*moveInput)+1; + } else { + moveOutput = Math.cos(1.571*moveInput)-1; + } + + /* If steer stick has not been used for less than 1 sec */ + if (m_currTime - m_deadTimeSteer < m_deadTimeout) { + runDriveWithInput(moveOutput, steerInput); + resetGyroTarget(); + } + /* If steer stick has not been used for 1 sec */ + else { + runDriveStraight(moveOutput); + } + } + + private void runDriveWithInput(double move, double steer) { + double cosMultiplier = .45; + double steerOutput = 0; + double deadzone = .2; + /* Curves the steer output to be similarily gradual */ + if (steer > 0){ + steerOutput = -cosMultiplier*Math.cos(1.571*steer)+(cosMultiplier+deadzone); + } else { + steerOutput = cosMultiplier*Math.cos(1.571*steer)-(cosMultiplier+deadzone); + } + m_drive.driveWithInput(move, steerOutput); + System.out.println("Driving With Input"); + } + + private void runDriveStraight(double move) { + m_drive.driveWithInputAux(move * 3/4, m_targetGyro); + System.out.println("Driving Straight with Target: " + m_targetGyro); + } + + /** + * set target angle to current angle (prevents buildup of gyro error). + */ + private void resetGyroTarget() { + //m_targetGyro = m_currentGyro; + m_targetGyro = m_currentGyro + + (3 * m_drive.m_rightFrontMotor.getSelectedSensorVelocity(1)); + } + + // 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; + } +} From 9c2a897236c75603ca5ff43ea16e589b9a05b727 Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Wed, 19 Feb 2020 09:14:03 -0700 Subject: [PATCH 34/44] Cleanup DeadAssist --- .../DriveWithJoystickUsingDeadAssistPID.java | 14 ++++---------- 1 file changed, 4 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index 7eff284..3ce828f 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -112,16 +112,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { private void runStoppedTurn(double steer) { updateGyroTarget(steer); m_drive.runDrivePositionPID(m_stopPos, m_targetGyro); - System.out.println("Turning with Target: " + m_targetGyro); - - /* if (m_drive.m_rightFrontMotor.getSelectedSensorVelocity() > 3000) { - m_drive.driveWithInputAux(0, m_targetGyro); - System.out.println("!Turning with Target: " + m_targetGyro); - } else { - m_drive.runDriveVelocityPID(0, m_targetGyro); - System.out.println("Turning with Target: " + m_targetGyro); - }*/ } /** @@ -129,7 +120,6 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { */ private void updateGyroTarget(double steerInput) { m_targetGyro -= 5 * steerInput * m_deltaTime; - m_targetGyro = MathUtil.clamp( m_targetGyro, m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/8), m_currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/8)); @@ -142,6 +132,10 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { m_targetGyro = m_currentGyro; m_targetGyro = m_currentGyro + (3 * m_drive.m_rightFrontMotor.getSelectedSensorVelocity(1)); + + m_targetGyro = MathUtil.clamp( m_targetGyro, + m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/8), + m_currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/8)); } // Called once the command ends or is interrupted. From faf777234db7b42155ebeb39b12e37d976f5f68b Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Wed, 19 Feb 2020 16:25:38 -0700 Subject: [PATCH 35/44] Fixed Solenoid to Cool Falcon --- src/main/java/frc4388/robot/RobotContainer.java | 2 +- src/main/java/frc4388/robot/subsystems/Drive.java | 6 +++++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 80484b4..65199c5 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -78,7 +78,7 @@ public class RobotContainer { /* Default Commands */ // drives the robot with a two-axis input from the driver controller - m_robotDrive.setDefaultCommand(new DriveWithJoystickUsingDeadAssistPID(m_robotDrive, getDriverController())); + m_robotDrive.setDefaultCommand(new DriveWithJoystick(m_robotDrive, getDriverController())); // drives intake with input from triggers on the opperator controller m_robotIntake.setDefaultCommand(new RunIntakeWithTriggers(m_robotIntake, getOperatorController())); // drives climber with input from triggers on the opperator controller diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 58c14fb..9afa4c9 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -66,7 +66,7 @@ public class Drive extends SubsystemBase { public DoubleSolenoid m_speedShift; public DoubleSolenoid m_coolFalcon; - public int m_currentTimeSec = (int)(System.currentTimeMillis() * 1000); + public int m_currentTimeSec = (int)(System.currentTimeMillis() / 1000); public long m_lastTime, m_deltaTime; //in milliseconds @@ -271,11 +271,15 @@ public class Drive extends SubsystemBase { @Override public void periodic() { + m_currentTimeSec = (int)(System.currentTimeMillis() / 1000); + SmartDashboard.putNumber("Time Seconds", m_currentTimeSec); if (m_currentTimeSec % 10 == 0) { coolFalcon(true); + SmartDashboard.putBoolean("Solenoid", true); } else if ((m_currentTimeSec - 2) % 10 == 0) { coolFalcon(false); + SmartDashboard.putBoolean("Solenoid", false); } m_deltaTime = System.currentTimeMillis() - m_lastTime; From 0f0b3e7208110bd5c3627c8e6084be8922d5c161 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Wed, 19 Feb 2020 17:38:15 -0700 Subject: [PATCH 36/44] Changed formatting --- src/main/java/frc4388/robot/subsystems/Drive.java | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 9afa4c9..32ea707 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -84,7 +84,8 @@ public class Drive extends SubsystemBase { m_pigeon.configFactoryDefault(); resetGyroYaw(); - m_odometry = new DifferentialDriveOdometry(Rotation2d.fromDegrees(getHeading()), new Pose2d(0, 0, new Rotation2d())); + m_odometry = new DifferentialDriveOdometry( Rotation2d.fromDegrees(getHeading()), + new Pose2d(0, 0, new Rotation2d()) ); m_speedShift = new DoubleSolenoid(7,0,1); m_coolFalcon = new DoubleSolenoid(7,3,2); @@ -606,7 +607,7 @@ public class Drive extends SubsystemBase { * @param ticks The value in ticks to convert * @return The converted value in inches */ - public double ticksToInches(double ticks) { + public double ticksToInches(double ticks) { return ticks * DriveConstants.INCHES_PER_TICK; } From 11f7f2272e7cbfbe1d7db043bd7b6ca795d0160f Mon Sep 17 00:00:00 2001 From: "Keenan D. Buckley" Date: Wed, 19 Feb 2020 19:15:45 -0700 Subject: [PATCH 37/44] Fix Dead assist so it uses the right constants and TurnRate code --- src/main/java/frc4388/robot/Constants.java | 2 +- src/main/java/frc4388/robot/RobotContainer.java | 1 + .../robot/commands/DriveWithJoystickDriveStraight.java | 4 ++-- .../robot/commands/DriveWithJoystickUsingDeadAssistPID.java | 6 +----- src/main/java/frc4388/robot/subsystems/Drive.java | 6 +++++- 5 files changed, 10 insertions(+), 9 deletions(-) diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 4dcbaaf..13ce0ee 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -31,7 +31,7 @@ public final class Constants { public static final int DRIVE_TIMEOUT_MS = 30; public static final Gains DRIVE_DISTANCE_GAINS = new Gains(0.1, 0.0, 1.0, 0.0, 0, 0.3); public static final Gains DRIVE_VELOCITY_GAINS = new Gains(0.1, 0.0, 0.2, 0.025, 0, 0.05); - public static final Gains DRIVE_TURNING_GAINS = new Gains(0.5, 0.0, 0.0, 0.05, 0, 0.5); + public static final Gains DRIVE_TURNING_GAINS = new Gains(0.5, 0.0, 0.05, 0.0, 0, 0.5); //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 = 20000; //public static final int DRIVE_ACCELERATION = 7000; diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 80484b4..c0879e3 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -33,6 +33,7 @@ import frc4388.robot.commands.DriveStraightToPositionMM; import frc4388.robot.commands.DriveStraightToPositionPID; import frc4388.robot.commands.DriveWithJoystick; import frc4388.robot.commands.DriveWithJoystickUsingDeadAssistPID; +import frc4388.robot.commands.DriveWithJoystickDriveStraight; import frc4388.robot.commands.RunClimberWithTriggers; import frc4388.robot.commands.RunExtenderOutIn; import frc4388.robot.commands.RunIntakeWithTriggers; diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickDriveStraight.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickDriveStraight.java index 2a30287..a298f9c 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickDriveStraight.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickDriveStraight.java @@ -47,7 +47,7 @@ public class DriveWithJoystickDriveStraight extends CommandBase { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - m_currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN); + m_currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(1); double moveInput = -m_controller.getLeftYAxis(); double steerInput = m_controller.getRightXAxis(); double moveOutput = 0; @@ -102,7 +102,7 @@ public class DriveWithJoystickDriveStraight extends CommandBase { private void resetGyroTarget() { //m_targetGyro = m_currentGyro; m_targetGyro = m_currentGyro - + (3 * m_drive.m_rightFrontMotor.getSelectedSensorVelocity(1)); + + m_drive.getTurnRate(); } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java index 3ce828f..7756772 100644 --- a/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java +++ b/src/main/java/frc4388/robot/commands/DriveWithJoystickUsingDeadAssistPID.java @@ -131,11 +131,7 @@ public class DriveWithJoystickUsingDeadAssistPID extends CommandBase { private void resetGyroTarget() { m_targetGyro = m_currentGyro; m_targetGyro = m_currentGyro - + (3 * m_drive.m_rightFrontMotor.getSelectedSensorVelocity(1)); - - m_targetGyro = MathUtil.clamp( m_targetGyro, - m_currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/8), - m_currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/8)); + + m_drive.getTurnRate(); } // Called once the command ends or is interrupted. diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 58c14fb..64bb463 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -318,6 +318,9 @@ public class Drive extends SubsystemBase { SmartDashboard.putString("Odometry Values Meters", getPose().toString()); SmartDashboard.putNumber("Odometry Heading", getHeading()); + SmartDashboard.putNumber("Time Seconds", m_currentTimeSec); + //SmartDashboard.putNumber("Delta Time", m_deltaTime); + } catch (Exception e) { System.err.println("Error in the Drive Subsystem"); // e.printStackTrace(System.err); @@ -539,7 +542,8 @@ public class Drive extends SubsystemBase { */ public double getTurnRate() { double deltaYaw = m_currentAngleYaw - m_lastAngleYaw; - return deltaYaw / (m_deltaTime/1000); + double turnRate = 1000 * deltaYaw / m_deltaTime; + return turnRate; } /** From 0d13b05dda261589ca443611f18d5299be949ba0 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Wed, 19 Feb 2020 19:16:26 -0700 Subject: [PATCH 38/44] Testing System Time, made Simpler Trajectory --- src/main/java/frc4388/robot/RobotContainer.java | 4 ++-- src/main/java/frc4388/robot/subsystems/Drive.java | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 65199c5..608ec18 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -194,8 +194,8 @@ public class RobotContainer { new Pose2d(0, 0, new Rotation2d(0)), // Pass through these two interior waypoints, making an 's' curve path List.of( - new Translation2d(1, 1), - new Translation2d(2, -1) + new Translation2d(3, 0) + //new Translation2d(2, -1) ), // End 3 meters straight ahead of where we started, facing forward new Pose2d(3, 0, new Rotation2d(0)), diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 32ea707..970aa6c 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -273,7 +273,7 @@ public class Drive extends SubsystemBase { @Override public void periodic() { m_currentTimeSec = (int)(System.currentTimeMillis() / 1000); - SmartDashboard.putNumber("Time Seconds", m_currentTimeSec); + SmartDashboard.putNumber("Time Seconds", System.currentTimeMillis()); if (m_currentTimeSec % 10 == 0) { coolFalcon(true); From c40bba15ff2377b2fcfb845f351d668cc3591c87 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 20 Feb 2020 16:53:13 -0700 Subject: [PATCH 39/44] Fixed motor following problem --- src/main/java/frc4388/robot/subsystems/Drive.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 764cc61..696c3c8 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -469,8 +469,8 @@ public class Drive extends SubsystemBase { m_rightBackMotor.set(TalonFXControlMode.Velocity, moveVelRight); m_leftBackMotor.set(TalonFXControlMode.Velocity, moveVelLeft); - m_leftFrontMotor.follow(m_leftFrontMotor); - m_rightFrontMotor.follow(m_rightFrontMotor); + m_leftFrontMotor.follow(m_leftBackMotor); + m_rightFrontMotor.follow(m_rightBackMotor); m_driveTrain.feedWatchdog(); } From 92af17f8850a75a82a57a708e020a69dee8cfd64 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Thu, 20 Feb 2020 20:14:51 -0700 Subject: [PATCH 40/44] Changed values and cleaned up --- src/main/java/frc4388/robot/RobotContainer.java | 10 +++++----- src/main/java/frc4388/robot/subsystems/Drive.java | 13 +++++++++---- 2 files changed, 14 insertions(+), 9 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 965062a..b58ccfe 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -128,7 +128,7 @@ public class RobotContainer { // resets the yaw of the pigeon new JoystickButton(getDriverJoystick(), XboxController.X_BUTTON) - .whileHeld(new RunCommand(() -> m_robotDrive.tankDriveVelocity(1, 1), m_robotDrive)); + .whileHeld(new RunCommand(() -> m_robotDrive.tankDriveVelocity(9, 3), m_robotDrive)); // turn 45 degrees new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON) @@ -195,14 +195,14 @@ public class RobotContainer { new Pose2d(0, 0, new Rotation2d(0)), // Pass through these two interior waypoints, making an 's' curve path List.of( - new Translation2d(3, 0) - //new Translation2d(2, -1) + new Translation2d(10, 0) ), // End 3 meters straight ahead of where we started, facing forward - new Pose2d(3, 0, new Rotation2d(0)), + new Pose2d(20, 20, new Rotation2d(0)), // Pass config config); - + // 10 = 20, 20 = 35, 30 = 53.5 + // (0,10) = (8,22) RamseteCommand ramseteCommand = new RamseteCommand( exampleTrajectory, m_robotDrive::getPose, diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 696c3c8..5258a46 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -275,10 +275,10 @@ public class Drive extends SubsystemBase { m_currentTimeSec = (int)(System.currentTimeMillis() / 1000); SmartDashboard.putNumber("Time Seconds", System.currentTimeMillis()); - if (m_currentTimeSec % 10 == 0) { + if (m_currentTimeSec % 30 == 0) { coolFalcon(true); SmartDashboard.putBoolean("Solenoid", true); - } else if ((m_currentTimeSec - 2) % 10 == 0) { + } else if ((m_currentTimeSec - 1) % 30 == 0) { coolFalcon(false); SmartDashboard.putBoolean("Solenoid", false); } @@ -467,6 +467,8 @@ public class Drive extends SubsystemBase { m_rightBackMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); m_leftBackMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY); + System.err.println(moveVelLeft); + m_rightBackMotor.set(TalonFXControlMode.Velocity, moveVelRight); m_leftBackMotor.set(TalonFXControlMode.Velocity, moveVelLeft); m_leftFrontMotor.follow(m_leftBackMotor); @@ -531,9 +533,12 @@ public class Drive extends SubsystemBase { m_currentAngleYaw = 0; m_kinematicsTargetAngle = 0; } - +//lol +//sko +//ridge /** - * Returns the heading of the robot +//brayden=bad coder + * Returns the heading of the robot * @return The robot's heading in degrees, from -180 to 180 */ public double getHeading() { From fee7f99a9fd343926d970a76633fcd796a5d7592 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Fri, 21 Feb 2020 16:28:45 -0700 Subject: [PATCH 41/44] Disabled Ramsete Command --- src/main/java/frc4388/robot/RobotContainer.java | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index b58ccfe..6ba9571 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -185,7 +185,7 @@ public class RobotContainer { public Command getAutonomousCommand() { // Create config for trajectory - TrajectoryConfig config = new TrajectoryConfig( DriveConstants.MAX_SPEED_METERS_PER_SECOND, + /*TrajectoryConfig config = new TrajectoryConfig( DriveConstants.MAX_SPEED_METERS_PER_SECOND, DriveConstants.MAX_ACCELERATION_METERS_PER_SECOND_SQUARED) // Add kinematics to ensure max speed is actually obeyed .setKinematics(DriveConstants.kDriveKinematics); @@ -212,7 +212,8 @@ public class RobotContainer { m_robotDrive); // Run path following command, then stop at the end. - return ramseteCommand.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0)); + return ramseteCommand.andThen(() -> m_robotDrive.tankDriveVelocity(0, 0));*/ + return new InstantCommand(); } /** From e58cc6618e3819d30aedfa15bddd34256315d357 Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Fri, 21 Feb 2020 16:43:42 -0700 Subject: [PATCH 42/44] Fixed semicolo --- src/main/java/frc4388/robot/subsystems/Drive.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 7377b58..3c42b67 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -40,7 +40,7 @@ import edu.wpi.first.wpilibj.geometry.Pose2d; import edu.wpi.first.wpilibj.geometry.Rotation2d; import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry; -import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds +import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; From 52f126706a0c4238e9bdd5a3945f996a14bc3deb Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Fri, 21 Feb 2020 16:47:03 -0700 Subject: [PATCH 43/44] Deleted extra java doc --- src/main/java/frc4388/robot/RobotContainer.java | 3 +-- src/main/java/frc4388/robot/subsystems/Drive.java | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index c1dcc09..a254ac3 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -170,11 +170,10 @@ public class RobotContainer { new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON) .whileHeld(new TrackTarget(m_robotShooter)); } - + /** * Sets Motors to a NeutralMode. * @param mode NeutralMode to set motors to - * @param state the gearing of the gearbox (true is high, false is low) */ public void setDriveNeutralMode(NeutralMode mode) { m_robotDrive.setDriveTrainNeutralMode(mode); diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 3c42b67..250716c 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -295,7 +295,7 @@ public class Drive extends SubsystemBase { m_songChooser.addOption(songString, songsDir.getAbsolutePath() + "/" + songString); } Shuffleboard.getTab("Songs").add(m_songChooser); - } + } String currentSong = ""; @Override From 123fa0291ad84bf9ea388d2228a2fc6dcd6d495a Mon Sep 17 00:00:00 2001 From: Aarav Shah <91212@psdschools.org> Date: Fri, 21 Feb 2020 16:48:22 -0700 Subject: [PATCH 44/44] Fix --- src/main/java/frc4388/robot/subsystems/Drive.java | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/java/frc4388/robot/subsystems/Drive.java b/src/main/java/frc4388/robot/subsystems/Drive.java index 250716c..7d395cd 100644 --- a/src/main/java/frc4388/robot/subsystems/Drive.java +++ b/src/main/java/frc4388/robot/subsystems/Drive.java @@ -81,6 +81,8 @@ public class Drive extends SubsystemBase { public DoubleSolenoid m_speedShift; public DoubleSolenoid m_coolFalcon; + SendableChooser m_songChooser = new SendableChooser(); + public int m_currentTimeSec = (int)(System.currentTimeMillis() / 1000); public long m_lastTime, m_deltaTime; //in milliseconds