mirror of
https://github.com/Team4388/RiseOfRidgebotics2020.git
synced 2026-06-09 00:38:00 -06:00
Merge branch 'master' into add-elijahs-mystery-feature
This commit is contained in:
@@ -29,11 +29,11 @@ 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.0, 0.0, 0.0, 0.1, 0, 1.0);
|
||||
public static final Gains DRIVE_TURNING_GAINS = new Gains(0.4, 0.0, 0.0, 0.0, 0, 0.3);
|
||||
public static final Gains DRIVE_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_MOTION_MAGIC_GAINS = new Gains(0.2, 0.0, 0.0, 0.0, 0, 1.0);
|
||||
public static final int DRIVE_CRUISE_VELOCITY = 2000;
|
||||
public static final int DRIVE_ACCELERATION = 1000;
|
||||
public static final int DRIVE_CRUISE_VELOCITY = 20000;
|
||||
public static final int DRIVE_ACCELERATION = 7000;
|
||||
|
||||
/* Remote Sensors */
|
||||
public final static int REMOTE_0 = 0;
|
||||
@@ -66,7 +66,20 @@ public final class Constants {
|
||||
}
|
||||
|
||||
public static final class IntakeConstants {
|
||||
public static final int INTAKE_SPARK_ID = 1;
|
||||
public static final int INTAKE_SPARK_ID = 9;
|
||||
public static final int EXTENDER_SPARK_ID = 10;
|
||||
}
|
||||
|
||||
public static final class ShooterConstants {
|
||||
public static final int SHOOTER_FALCON_ID = 8;
|
||||
|
||||
/* PID Constants Shooter */
|
||||
public static final int SHOOTER_SLOT_IDX = 0;
|
||||
public static final int SHOOTER_PID_LOOP_IDX = 1;
|
||||
public static final int SHOOTER_TIMEOUT_MS = 30;
|
||||
public static final Gains SHOOTER_GAINS = new Gains(0.4, 0.0005, 13, 0.05, 0, 1.0);
|
||||
|
||||
public static final double ENCODER_TICKS_PER_REV = 2048;
|
||||
}
|
||||
|
||||
public static final class ClimberConstants {
|
||||
@@ -74,17 +87,34 @@ public final class Constants {
|
||||
}
|
||||
|
||||
public static final class LevelerConstants {
|
||||
public static final int LEVELER_CAN_ID = 9;
|
||||
public static final int LEVELER_CAN_ID = -1;
|
||||
}
|
||||
|
||||
public static final class StorageConstants {
|
||||
public static final int STORAGE_CAN_ID = -1;
|
||||
public static final int STORAGE_CAN_ID = 10;
|
||||
|
||||
/* Ball Indexes */
|
||||
public static final int BEAM_SENSOR_DIO_0 = 0;
|
||||
public static final int BEAM_SENSOR_DIO_1 = 1;
|
||||
public static final int BEAM_SENSOR_DIO_2 = 2;
|
||||
public static final int BEAM_SENSOR_DIO_3 = 3;
|
||||
public static final int BEAM_SENSOR_DIO_4 = 4;
|
||||
public static final int BEAM_SENSOR_DIO_5 = 5;
|
||||
|
||||
/* PID Values */
|
||||
public static final int SLOT_DISTANCE = 0;
|
||||
|
||||
/* PID Indexes */
|
||||
public static final int PID_PRIMARY = 0;
|
||||
|
||||
/* PID Gains */
|
||||
public static final double storP = 0.1;
|
||||
public static final double storI = 1e-4;
|
||||
public static final double storD = 1.0;
|
||||
public static final double storIz = 0.0;
|
||||
public static final double storF = 0.0;
|
||||
public static final double storkmaxOutput = 1.0;
|
||||
public static final double storkminOutput = -1.0;
|
||||
}
|
||||
|
||||
public static final class LEDConstants {
|
||||
|
||||
@@ -17,6 +17,8 @@ public class Gains {
|
||||
public double m_kF;
|
||||
public int m_kIzone;
|
||||
public double m_kPeakOutput;
|
||||
public double m_kmaxOutput;
|
||||
public double m_kminOutput;
|
||||
|
||||
/**
|
||||
* Creates Gains object for PIDs
|
||||
|
||||
@@ -17,14 +17,19 @@ import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
import frc4388.robot.Constants.*;
|
||||
import frc4388.robot.commands.DriveStraightAtVelocityPID;
|
||||
import frc4388.robot.commands.DriveWithJoystick;
|
||||
import frc4388.robot.commands.PlaySongDrive;
|
||||
import frc4388.robot.commands.DriveStraightToPositionMM;
|
||||
import frc4388.robot.commands.DriveStraightToPositionPID;
|
||||
import frc4388.robot.commands.DriveWithJoystickUsingDeadAssistPID;
|
||||
import frc4388.robot.commands.RunClimberWithTriggers;
|
||||
import frc4388.robot.commands.RunExtenderOutIn;
|
||||
import frc4388.robot.commands.RunIntakeWithTriggers;
|
||||
import frc4388.robot.subsystems.Climber;
|
||||
import frc4388.robot.commands.RunLevelerWithJoystick;
|
||||
import frc4388.robot.commands.ShooterVelocityControlPID;
|
||||
import frc4388.robot.subsystems.Drive;
|
||||
import frc4388.robot.subsystems.Intake;
|
||||
import frc4388.robot.subsystems.LED;
|
||||
import frc4388.robot.subsystems.Shooter;
|
||||
import frc4388.robot.subsystems.Climber;
|
||||
import frc4388.robot.commands.RunLevelerWithJoystick;
|
||||
import frc4388.robot.subsystems.Leveler;
|
||||
import frc4388.robot.subsystems.Storage;
|
||||
import frc4388.utility.LEDPatterns;
|
||||
@@ -43,6 +48,7 @@ public class RobotContainer {
|
||||
private final Drive m_robotDrive = new Drive();
|
||||
private final LED m_robotLED = new LED();
|
||||
private final Intake m_robotIntake = new Intake();
|
||||
private final Shooter m_robotShooter = new Shooter();
|
||||
private final Climber m_robotClimber = new Climber();
|
||||
private final Leveler m_robotLeveler = new Leveler();
|
||||
private final Storage m_robotStorage = new Storage();
|
||||
@@ -59,13 +65,15 @@ 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()));
|
||||
// drives motor with input from triggers on the opperator controller
|
||||
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
|
||||
m_robotClimber.setDefaultCommand(new RunClimberWithTriggers(m_robotClimber, getDriverController()));
|
||||
// continually sends updates to the Blinkin LED controller to keep the lights on
|
||||
m_robotLED.setDefaultCommand(new RunCommand(() -> m_robotLED.updateLED(), m_robotLED));
|
||||
// runs the drum shooter in idle mode
|
||||
m_robotShooter.setDefaultCommand(new RunCommand(() -> m_robotShooter.runDrumShooter(0.15), m_robotShooter));
|
||||
// drives the leveler with an axis input from the driver controller
|
||||
m_robotLeveler.setDefaultCommand(new RunLevelerWithJoystick(m_robotLeveler, getDriverController()));
|
||||
// runs storage motor at 50 percent
|
||||
@@ -80,32 +88,54 @@ public class RobotContainer {
|
||||
*/
|
||||
private void configureButtonBindings() {
|
||||
/* Driver Buttons */
|
||||
//new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON)
|
||||
// .whenPressed(new DriveStraightToPositionPID(m_robotDrive, 36));
|
||||
new JoystickButton(getDriverJoystick(), XboxController.A_BUTTON)
|
||||
.whenPressed(new DriveStraightToPositionPID(m_robotDrive, 144));
|
||||
|
||||
/* Operator Buttons */
|
||||
// activates "Lit Mode"
|
||||
new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON)
|
||||
.whenPressed(() -> m_robotLED.setPattern(LEDPatterns.LAVA_RAINBOW))
|
||||
.whenReleased(() -> m_robotLED.setPattern(LEDConstants.DEFAULT_PATTERN));
|
||||
|
||||
|
||||
new JoystickButton(getOperatorJoystick(), XboxController.X_BUTTON)
|
||||
.whileHeld(new ShooterVelocityControlPID(m_robotShooter, 4000));
|
||||
|
||||
new JoystickButton(getOperatorJoystick(), XboxController.LEFT_BUMPER_BUTTON)
|
||||
.whenPressed(new RunExtenderOutIn(m_robotIntake));
|
||||
|
||||
/* PID Test Command */
|
||||
// runs velocity PID while driving straight
|
||||
new JoystickButton(getDriverJoystick(), XboxController.B_BUTTON)
|
||||
.whenPressed(new DriveStraightAtVelocityPID(m_robotDrive, 500))
|
||||
.whenReleased(new InstantCommand(() -> System.out.print("Gamer"), m_robotDrive));
|
||||
|
||||
//new JoystickButton(getDriverJoystick(), XboxController.RIGHT_BUMPER_BUTTON)
|
||||
// .whileHeld(new DriveWithJoystickAuxPID(m_robotDrive, getDriverController()));
|
||||
|
||||
// resets the yaw of the pigeon
|
||||
new JoystickButton(getDriverJoystick(), XboxController.X_BUTTON)
|
||||
.whenPressed(new InstantCommand(() -> m_robotDrive.resetGyroYaw(), m_robotDrive));
|
||||
|
||||
.whenPressed(new DriveStraightToPositionMM(m_robotDrive, 72));
|
||||
|
||||
// turn 45 degrees
|
||||
new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON)
|
||||
.whenPressed(new PlaySongDrive(m_robotDrive));
|
||||
.whenPressed(new RunCommand(() -> m_robotDrive.runTurningPID(45), m_robotDrive));
|
||||
|
||||
//new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON)
|
||||
// .whenPressed(new RunCommand(() -> m_robotDrive.runMotionMagicPID(5000, 0), m_robotDrive));
|
||||
|
||||
// sets solenoids into high gear
|
||||
new JoystickButton(getDriverJoystick(), XboxController.START_BUTTON)
|
||||
.whenPressed(new InstantCommand(() -> m_robotDrive.setShiftState(true), m_robotDrive));
|
||||
|
||||
// sets solenoids into low gear
|
||||
new JoystickButton(getDriverJoystick(), XboxController.BACK_BUTTON)
|
||||
.whenPressed(new InstantCommand(() -> m_robotDrive.setShiftState(false), m_robotDrive));
|
||||
|
||||
// interrupts any running command
|
||||
new JoystickButton(getDriverJoystick(), XboxController.LEFT_JOYSTICK_BUTTON)
|
||||
.whenPressed(new InstantCommand(() -> System.out.print("Gamer"), m_robotDrive));
|
||||
|
||||
/* Storage Neo PID Test */
|
||||
new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON)
|
||||
.whileHeld(new RunCommand(() -> m_robotStorage.runStoragePositionPID(0.5, 0.2, 0.0, 0.0, 0.0, 0.0, 1, -1)));
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -0,0 +1,70 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package frc4388.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc4388.robot.Constants.DriveConstants;
|
||||
import frc4388.robot.subsystems.Drive;
|
||||
|
||||
public class DriveStraightToPositionMM extends CommandBase {
|
||||
Drive m_drive;
|
||||
double m_targetPosIn;
|
||||
double m_targetPosOut;
|
||||
double m_targetGyro;
|
||||
boolean isGoneFast;
|
||||
|
||||
/**
|
||||
* Creates a new DriveToDistancePID.
|
||||
* @param subsystem drive subsystem
|
||||
* @param targetPos distance to travel in inches
|
||||
*/
|
||||
public DriveStraightToPositionMM(Drive subsystem, double targetPos) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
m_drive = subsystem;
|
||||
m_targetPosIn = targetPos * DriveConstants.TICKS_PER_INCH;
|
||||
addRequirements(m_drive);
|
||||
//SmartDashboard.putNumber("Distance Target Inches", targetPos);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
System.err.println("PID START \n | \n |");
|
||||
m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN);
|
||||
m_targetPosOut = m_targetPosIn + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY);
|
||||
isGoneFast = false;
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
//System.err.println("| \n Sensor Pos \n" + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN));
|
||||
//System.err.println("Sensor Error \n" + m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN));
|
||||
//System.err.println("Sensor Target \n" + m_drive.m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_TURN));
|
||||
m_drive.runMotionMagicPID(m_targetPosOut, m_targetGyro);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
if (Math.abs((int)m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY)) < 5 && isGoneFast){
|
||||
return true;
|
||||
} else {
|
||||
if (m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY) > 100) {
|
||||
isGoneFast = true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -14,8 +14,10 @@ import frc4388.robot.subsystems.Drive;
|
||||
|
||||
public class DriveStraightToPositionPID extends CommandBase {
|
||||
Drive m_drive;
|
||||
double m_targetPos;
|
||||
double m_targetPosIn;
|
||||
double m_targetPosOut;
|
||||
double m_targetGyro;
|
||||
int i;
|
||||
|
||||
/**
|
||||
* Creates a new DriveToDistancePID.
|
||||
@@ -25,22 +27,27 @@ public class DriveStraightToPositionPID extends CommandBase {
|
||||
public DriveStraightToPositionPID(Drive subsystem, double targetPos) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
m_drive = subsystem;
|
||||
m_targetPos = targetPos * DriveConstants.TICKS_PER_INCH;
|
||||
m_targetPosIn = targetPos * DriveConstants.TICKS_PER_INCH;
|
||||
addRequirements(m_drive);
|
||||
SmartDashboard.putNumber("Distance Target Inches", targetPos);
|
||||
//SmartDashboard.putNumber("Distance Target Inches", targetPos);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
//System.err.println("PID START \n | \n |");
|
||||
m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN);
|
||||
m_targetPosOut = m_targetPosIn + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY);
|
||||
i = 0;
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
//System.err.println(m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_TURN));
|
||||
m_drive.runDriveStraightPositionPID(m_targetPos, m_targetGyro);
|
||||
//System.err.println("| \n Sensor Pos \n" + m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_PRIMARY));
|
||||
//System.err.println("Sensor Error \n" + m_drive.m_rightFrontMotor.getClosedLoopError(DriveConstants.PID_PRIMARY));
|
||||
//System.err.println("Sensor Target \n" + m_drive.m_rightFrontMotor.getClosedLoopTarget(DriveConstants.PID_PRIMARY));
|
||||
m_drive.runDriveStraightPositionPID(m_targetPosOut, m_targetGyro);
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@@ -51,9 +58,11 @@ public class DriveStraightToPositionPID extends CommandBase {
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
if (Math.abs(m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() - m_targetPos) < 500){
|
||||
if (Math.abs((int)m_drive.m_rightFrontMotor.getSelectedSensorVelocity(DriveConstants.PID_PRIMARY)) < 5 && i > 5){
|
||||
return true;
|
||||
} else {
|
||||
i++;
|
||||
//System.err.println(i);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,79 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package frc4388.robot.commands;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.TalonFXControlMode;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpiutil.math.MathUtil;
|
||||
import frc4388.robot.Constants.DriveConstants;
|
||||
import frc4388.robot.subsystems.Drive;
|
||||
import frc4388.utility.controller.IHandController;
|
||||
|
||||
public class DriveWithJoystickAuxPID extends CommandBase {
|
||||
Drive m_drive;
|
||||
double m_targetGyro;
|
||||
long lastTime;
|
||||
IHandController m_controller;
|
||||
|
||||
/**
|
||||
* Creates a new DriveWithJoystickAuxPID.
|
||||
*/
|
||||
public DriveWithJoystickAuxPID(Drive subsystem, IHandController controller) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
m_drive = subsystem;
|
||||
m_controller = controller;
|
||||
addRequirements(m_drive);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
m_targetGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN);
|
||||
lastTime = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN);
|
||||
double moveInput = m_controller.getLeftYAxis();
|
||||
double steerInput = m_controller.getRightXAxis();
|
||||
double moveOutput = 0;
|
||||
long deltaTime = System.currentTimeMillis() - lastTime;
|
||||
lastTime = System.currentTimeMillis();
|
||||
if (moveInput >= 0){
|
||||
moveOutput = -Math.cos(1.571*moveInput)+1;
|
||||
} else {
|
||||
moveOutput = Math.cos(1.571*moveInput)-1;
|
||||
}
|
||||
|
||||
m_targetGyro += 2 * steerInput * deltaTime;
|
||||
|
||||
m_targetGyro = MathUtil.clamp(m_targetGyro,
|
||||
currentGyro-(DriveConstants.TICKS_PER_GYRO_REV/4),
|
||||
currentGyro+(DriveConstants.TICKS_PER_GYRO_REV/4));
|
||||
|
||||
m_drive.driveWithInputAux(moveOutput, m_targetGyro);
|
||||
|
||||
System.err.println("Target: " + m_targetGyro);
|
||||
System.err.println("Current: " + currentGyro);
|
||||
System.err.println();
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,114 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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 DriveWithJoystickUsingDeadAssistPID extends CommandBase {
|
||||
Drive m_drive;
|
||||
double m_targetGyro;
|
||||
long lastTime;
|
||||
IHandController m_controller;
|
||||
boolean isAuxPIDEnabled = false;
|
||||
|
||||
/**
|
||||
* Creates a new DriveWithJoystickUsingDeadAssistPID 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 DriveWithJoystickUsingDeadAssistPID(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() {
|
||||
lastTime = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double currentGyro = m_drive.m_rightFrontMotor.getSelectedSensorPosition(DriveConstants.PID_TURN);
|
||||
double moveInput = m_controller.getLeftYAxis();
|
||||
double steerInput = m_controller.getRightXAxis();
|
||||
double moveOutput = 0;
|
||||
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;
|
||||
}
|
||||
|
||||
/* If move stick is being used */
|
||||
if (moveInput != 0) {
|
||||
/* 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 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);
|
||||
}
|
||||
m_drive.driveWithInput(moveOutput, steerOutput);
|
||||
isAuxPIDEnabled = false;
|
||||
}
|
||||
/* If only the move stick is being used */
|
||||
else {
|
||||
m_drive.driveWithInputAux(moveOutput, m_targetGyro);
|
||||
isAuxPIDEnabled = true;
|
||||
}
|
||||
}
|
||||
/* If the move stick is not being used */
|
||||
else {
|
||||
m_drive.runDriveStraightVelocityPID(0, m_targetGyro);
|
||||
isAuxPIDEnabled = true;
|
||||
}
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
+24
-22
@@ -8,53 +8,55 @@
|
||||
package frc4388.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc4388.robot.Constants.DriveConstants;
|
||||
import frc4388.robot.subsystems.Drive;
|
||||
import frc4388.robot.subsystems.Intake;
|
||||
import frc4388.utility.controller.IHandController;
|
||||
|
||||
public class RunExtenderOutIn extends CommandBase {
|
||||
private Intake m_intake;
|
||||
private boolean isOut = false;
|
||||
private long startTime;
|
||||
|
||||
public class DriveToDistanceMM extends CommandBase {
|
||||
Drive m_drive;
|
||||
double m_distance;
|
||||
double m_leftTarget;
|
||||
double m_rightTarget;
|
||||
|
||||
/**
|
||||
* Creates a new DriveToDistancePID.
|
||||
* @param subsystem drive subsystem
|
||||
* @param distance distance to travel in inches
|
||||
* Uses input from opperator to run the extender motor.
|
||||
* The left bumper will run the extender in and out.
|
||||
* @param subsystem pass the Intake subsystem from {@link frc4388.robot.RobotContainer#RobotContainer() RobotContainer}
|
||||
*/
|
||||
public DriveToDistanceMM(Drive subsystem, double distance) {
|
||||
public RunExtenderOutIn(Intake subsystem) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
m_drive = subsystem;
|
||||
m_distance = distance * DriveConstants.TICKS_PER_INCH;
|
||||
addRequirements(m_drive);
|
||||
m_intake = subsystem;
|
||||
addRequirements(m_intake);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
m_leftTarget = m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() + m_distance;
|
||||
m_rightTarget = -(m_drive.m_rightFrontMotor.getActiveTrajectoryPosition() + m_distance);
|
||||
isOut = !isOut;
|
||||
startTime = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
//m_drive.runMotionMagicPID(m_drive.m_leftFrontMotor, m_leftTarget);
|
||||
//m_drive.runMotionMagicPID(m_drive.m_rightFrontMotor, m_rightTarget);
|
||||
if (isOut){
|
||||
m_intake.runExtender(0.3);
|
||||
} else {
|
||||
m_intake.runExtender(-0.3);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
m_intake.runExtender(0.0);
|
||||
}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
public boolean isFinished() {
|
||||
if (Math.abs(m_drive.m_leftFrontMotor.getActiveTrajectoryPosition() - m_leftTarget) < 100){
|
||||
if (startTime + 3000 < System.currentTimeMillis()) {
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,48 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package frc4388.robot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import frc4388.robot.subsystems.Shooter;
|
||||
|
||||
public class ShooterVelocityControlPID extends CommandBase {
|
||||
Shooter m_shooter;
|
||||
double m_targetVel;
|
||||
/**
|
||||
* Creates a new ShooterVelocityControlPID.
|
||||
*/
|
||||
public ShooterVelocityControlPID(Shooter subsystem, double targetVel) {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
m_shooter = subsystem;
|
||||
m_targetVel = targetVel;
|
||||
addRequirements(m_shooter);
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
System.err.println(m_shooter.m_shooterFalcon.getSelectedSensorVelocity());
|
||||
m_shooter.runDrumShooterVelocityPID(m_targetVel, m_shooter.m_shooterFalcon.getSelectedSensorVelocity());
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
@@ -10,6 +10,7 @@ package frc4388.robot.subsystems;
|
||||
import com.revrobotics.CANDigitalInput;
|
||||
import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.CANDigitalInput.LimitSwitchPolarity;
|
||||
import com.revrobotics.CANSparkMax.IdleMode;
|
||||
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
@@ -17,18 +18,20 @@ import frc4388.robot.Constants.ClimberConstants;
|
||||
|
||||
public class Climber extends SubsystemBase {
|
||||
CANSparkMax m_climberMotor = new CANSparkMax(ClimberConstants.CLIMBER_SPARK_ID, MotorType.kBrushless);
|
||||
CANDigitalInput m_forwardLimit, m_reverseLimit;
|
||||
CANDigitalInput m_climberForwardLimit, m_climberReverseLimit;
|
||||
/**
|
||||
* Creates a new Climber.
|
||||
*/
|
||||
public Climber() {
|
||||
m_climberMotor.restoreFactoryDefaults();
|
||||
|
||||
m_forwardLimit = m_climberMotor.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyClosed);
|
||||
m_reverseLimit = m_climberMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyClosed);
|
||||
|
||||
m_forwardLimit.enableLimitSwitch(false);
|
||||
m_reverseLimit.enableLimitSwitch(false);
|
||||
m_climberMotor.setIdleMode(IdleMode.kBrake);
|
||||
m_climberMotor.setInverted(false);
|
||||
|
||||
m_climberForwardLimit = m_climberMotor.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyClosed);
|
||||
m_climberReverseLimit = m_climberMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyClosed);
|
||||
m_climberForwardLimit.enableLimitSwitch(false);
|
||||
m_climberReverseLimit.enableLimitSwitch(false);
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -17,7 +17,7 @@ import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.stream.Collectors;
|
||||
import java.util.stream.Stream;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.ControlMode;
|
||||
import com.ctre.phoenix.motorcontrol.DemandType;
|
||||
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
|
||||
import com.ctre.phoenix.motorcontrol.FollowerType;
|
||||
@@ -33,6 +33,8 @@ import com.ctre.phoenix.sensors.PigeonIMU;
|
||||
import com.ctre.phoenix.sensors.PigeonIMU_StatusFrame;
|
||||
|
||||
import edu.wpi.first.wpilibj.Filesystem;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
@@ -66,6 +68,8 @@ public class Drive extends SubsystemBase {
|
||||
|
||||
SendableChooser<String> m_songChooser = new SendableChooser<String>();
|
||||
|
||||
public DoubleSolenoid speedShift;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
@@ -78,6 +82,8 @@ public class Drive extends SubsystemBase {
|
||||
m_pigeon.configFactoryDefault();
|
||||
resetGyroYaw();
|
||||
|
||||
speedShift = new DoubleSolenoid(7,0,1);
|
||||
|
||||
/* set back motors as followers */
|
||||
m_leftBackMotor.follow(m_leftFrontMotor);
|
||||
m_rightBackMotor.follow(m_rightFrontMotor);
|
||||
@@ -95,7 +101,6 @@ 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);
|
||||
@@ -117,6 +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.configMotionCruiseVelocity(DriveConstants.DRIVE_CRUISE_VELOCITY, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
m_rightFrontMotor.configMotionAcceleration(DriveConstants.DRIVE_ACCELERATION, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
m_rightFrontMotor.configMotionSCurveStrength(0, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
|
||||
/* Setup Sensors for WPI_TalonFXs */
|
||||
m_leftFrontMotor.setSelectedSensorPosition(0, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
m_rightFrontMotor.setSelectedSensorPosition(0, DriveConstants.PID_PRIMARY, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
@@ -147,8 +161,8 @@ public class Drive extends SubsystemBase {
|
||||
m_rightFrontMotor.configSensorTerm(SensorTerm.Sum1, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
|
||||
/* Diff Signal */
|
||||
m_rightFrontMotor.configSensorTerm(SensorTerm.Diff0, FeedbackDevice.RemoteSensor0, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
m_rightFrontMotor.configSensorTerm(SensorTerm.Diff1, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
m_rightFrontMotor.configSensorTerm(SensorTerm.Diff1, FeedbackDevice.RemoteSensor0, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
m_rightFrontMotor.configSensorTerm(SensorTerm.Diff0, FeedbackDevice.IntegratedSensor, DriveConstants.DRIVE_TIMEOUT_MS);
|
||||
|
||||
/* Configure Sum [Sum of both QuadEncoders] to be used for Primary PID Index */
|
||||
m_rightFrontMotor.configSelectedFeedbackSensor( FeedbackDevice.SensorDifference,
|
||||
@@ -265,6 +279,7 @@ 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());
|
||||
|
||||
@@ -350,14 +365,29 @@ public class Drive extends SubsystemBase {
|
||||
}
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
* Runs percent output control on the moving and steering of the drive train,
|
||||
* using the Differential Drive class to manage the two inputs
|
||||
*/
|
||||
public void driveWithInput(double move, double steer){
|
||||
//m_driveTrain.arcadeDrive(move, steer);
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs a position PID while driving straight (has not been tested)
|
||||
* Runs percent output control on the drive train while using an AUX PID for rotation
|
||||
* @param targetPos The position to drive to in units
|
||||
* @param targetGyro The angle to drive at in units
|
||||
*/
|
||||
public void driveWithInputAux(double move, double targetGyro) {
|
||||
m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN);
|
||||
|
||||
m_rightFrontMotor.set(TalonFXControlMode.PercentOutput, move, DemandType.AuxPID, targetGyro);
|
||||
m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1);
|
||||
|
||||
m_driveTrain.feedWatchdog();
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs a position PID while driving straight
|
||||
* @param targetPos The position to drive to in units
|
||||
* @param targetGyro The angle to drive at in units
|
||||
*/
|
||||
@@ -365,7 +395,6 @@ public class Drive extends SubsystemBase {
|
||||
m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_DISTANCE, DriveConstants.PID_PRIMARY);
|
||||
m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN);
|
||||
|
||||
targetPos *= 2;
|
||||
m_rightFrontMotor.set(TalonFXControlMode.Position, targetPos, DemandType.AuxPID, targetGyro);
|
||||
m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1);
|
||||
|
||||
@@ -380,8 +409,6 @@ public class Drive extends SubsystemBase {
|
||||
public void runDriveStraightVelocityPID(double targetVel, double targetGyro) {
|
||||
m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_VELOCITY, DriveConstants.PID_PRIMARY);
|
||||
m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN);
|
||||
|
||||
targetVel *= 2;
|
||||
m_rightFrontMotor.set(TalonFXControlMode.Velocity, targetVel, DemandType.AuxPID, targetGyro);
|
||||
m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1);
|
||||
|
||||
@@ -389,18 +416,19 @@ public class Drive extends SubsystemBase {
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs motion magic PID while driving straight (has not been tested)
|
||||
* Runs motion magic PID while driving straight
|
||||
* @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){
|
||||
m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_MOTION_MAGIC, DriveConstants.PID_PRIMARY);
|
||||
m_rightFrontMotor.selectProfileSlot(DriveConstants.SLOT_TURNING, DriveConstants.PID_TURN);
|
||||
|
||||
m_rightFrontMotor.set(TalonFXControlMode.MotionMagic, targetPos, DemandType.AuxPID, targetGyro);
|
||||
|
||||
m_rightFrontMotor.set(ControlMode.MotionMagic, targetPos, DemandType.AuxPID, targetGyro);
|
||||
m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1);
|
||||
|
||||
//m_driveTrain.feedWatchdog();
|
||||
|
||||
m_driveTrain.feedWatchdog();
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -465,5 +493,17 @@ public class Drive extends SubsystemBase {
|
||||
public void selectSong(String song) {
|
||||
SmartDashboard.putString("Selected Song", song);
|
||||
m_orchestra.loadMusic(song);
|
||||
|
||||
/**
|
||||
* Set to high or low gear based on boolean state, true = high, false = low
|
||||
* @param state Chooses between high or low gear
|
||||
*/
|
||||
public void setShiftState(boolean state) {
|
||||
if (state == true) {
|
||||
speedShift.set(DoubleSolenoid.Value.kForward);
|
||||
}
|
||||
if (state == false) {
|
||||
speedShift.set(DoubleSolenoid.Value.kReverse);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,19 +7,38 @@
|
||||
|
||||
package frc4388.robot.subsystems;
|
||||
|
||||
import com.revrobotics.CANDigitalInput;
|
||||
import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.CANDigitalInput.LimitSwitchPolarity;
|
||||
import com.revrobotics.CANSparkMax.IdleMode;
|
||||
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc4388.robot.Constants.IntakeConstants;
|
||||
|
||||
public class Intake extends SubsystemBase {
|
||||
Spark m_intakeMotor = new Spark(IntakeConstants.INTAKE_SPARK_ID);
|
||||
|
||||
CANSparkMax m_intakeMotor = new CANSparkMax(IntakeConstants.INTAKE_SPARK_ID, MotorType.kBrushless);
|
||||
CANSparkMax m_extenderMotor = new CANSparkMax(IntakeConstants.EXTENDER_SPARK_ID, MotorType.kBrushless);
|
||||
CANDigitalInput m_extenderForwardLimit;
|
||||
CANDigitalInput m_extenderReverseLimit;
|
||||
|
||||
/**
|
||||
* Creates a new Intake.
|
||||
*/
|
||||
public Intake() {
|
||||
|
||||
m_intakeMotor.restoreFactoryDefaults();
|
||||
m_extenderMotor.restoreFactoryDefaults();
|
||||
|
||||
m_intakeMotor.setIdleMode(IdleMode.kCoast);
|
||||
m_extenderMotor.setIdleMode(IdleMode.kBrake);
|
||||
m_intakeMotor.setInverted(false);
|
||||
m_extenderMotor.setInverted(false);
|
||||
|
||||
m_extenderForwardLimit = m_extenderMotor.getForwardLimitSwitch(LimitSwitchPolarity.kNormallyClosed);
|
||||
m_extenderReverseLimit = m_extenderMotor.getReverseLimitSwitch(LimitSwitchPolarity.kNormallyClosed);
|
||||
m_extenderForwardLimit.enableLimitSwitch(false);
|
||||
m_extenderReverseLimit.enableLimitSwitch(false);
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -34,4 +53,12 @@ public class Intake extends SubsystemBase {
|
||||
public void runIntake(double input) {
|
||||
m_intakeMotor.set(input);
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs extender motor
|
||||
* @param input the percent output to run motor at
|
||||
*/
|
||||
public void runExtender(double input) {
|
||||
m_extenderMotor.set(input);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -26,7 +26,8 @@ public class Leveler extends SubsystemBase {
|
||||
*/
|
||||
public Leveler() {
|
||||
m_levelerMotor.restoreFactoryDefaults();
|
||||
m_levelerMotor.setIdleMode(IdleMode.kCoast);
|
||||
|
||||
m_levelerMotor.setIdleMode(IdleMode.kBrake);
|
||||
m_levelerMotor.setInverted(false);
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,89 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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.subsystems;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.NeutralMode;
|
||||
import com.ctre.phoenix.motorcontrol.TalonFXControlMode;
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
|
||||
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc4388.robot.Gains;
|
||||
import frc4388.robot.Constants.DriveConstants;
|
||||
import frc4388.robot.Constants.ShooterConstants;
|
||||
|
||||
public class Shooter extends SubsystemBase {
|
||||
|
||||
public WPI_TalonFX m_shooterFalcon = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_ID);
|
||||
|
||||
public static Gains m_shooterGains = ShooterConstants.SHOOTER_GAINS;
|
||||
|
||||
double velP;
|
||||
/**
|
||||
* Creates a new Shooter subsystem.
|
||||
*/
|
||||
public Shooter() {
|
||||
m_shooterFalcon.configFactoryDefault();
|
||||
|
||||
m_shooterFalcon.setNeutralMode(NeutralMode.Coast);
|
||||
m_shooterFalcon.setInverted(false);
|
||||
|
||||
setShooterGains();
|
||||
|
||||
m_shooterFalcon.configPeakOutputReverse(0, ShooterConstants.SHOOTER_TIMEOUT_MS);
|
||||
|
||||
m_shooterFalcon.setSelectedSensorPosition(0, ShooterConstants.SHOOTER_PID_LOOP_IDX, ShooterConstants.SHOOTER_TIMEOUT_MS);
|
||||
|
||||
int closedLoopTimeMs = 1;
|
||||
m_shooterFalcon.configClosedLoopPeriod(0, closedLoopTimeMs, ShooterConstants.SHOOTER_TIMEOUT_MS);
|
||||
m_shooterFalcon.configClosedLoopPeriod(1, closedLoopTimeMs, ShooterConstants.SHOOTER_TIMEOUT_MS);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// This method will be called once per scheduler run
|
||||
SmartDashboard.putNumber("Shooter Velocity", m_shooterFalcon.getSelectedSensorVelocity()*600/ShooterConstants.ENCODER_TICKS_PER_REV);
|
||||
}
|
||||
|
||||
/**
|
||||
* Runs drum shooter motor.
|
||||
* @param speed Speed to set the motor at
|
||||
*/
|
||||
public void runDrumShooter(double speed) {
|
||||
m_shooterFalcon.set(speed);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configures gains for shooter PID.
|
||||
*/
|
||||
public void setShooterGains() {
|
||||
m_shooterFalcon.selectProfileSlot(ShooterConstants.SHOOTER_SLOT_IDX, ShooterConstants.SHOOTER_PID_LOOP_IDX);
|
||||
m_shooterFalcon.config_kF(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterGains.m_kF, ShooterConstants.SHOOTER_TIMEOUT_MS);
|
||||
m_shooterFalcon.config_kP(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterGains.m_kP, ShooterConstants.SHOOTER_TIMEOUT_MS);
|
||||
m_shooterFalcon.config_kI(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterGains.m_kI, ShooterConstants.SHOOTER_TIMEOUT_MS);
|
||||
m_shooterFalcon.config_kD(ShooterConstants.SHOOTER_SLOT_IDX, m_shooterGains.m_kD, ShooterConstants.SHOOTER_TIMEOUT_MS);
|
||||
}
|
||||
/**
|
||||
* Runs drum shooter velocity PID.
|
||||
* @param falcon Motor to use
|
||||
* @param targetVel Target velocity to run motor at
|
||||
*/
|
||||
public void runDrumShooterVelocityPID(double targetVel, double actualVel) {
|
||||
velP = actualVel/targetVel; //Percent of target
|
||||
double runSpeed = actualVel + (12000*velP); //Ramp up equation
|
||||
//if (runSpeed > targetVel) {runSpeed = targetVel;}
|
||||
SmartDashboard.putNumber("shoot", actualVel);
|
||||
runSpeed = runSpeed/targetVel; //Convert to percent
|
||||
if (actualVel < targetVel - 1000){ //PID Based on ramp up amount
|
||||
m_shooterFalcon.set(TalonFXControlMode.PercentOutput, runSpeed);
|
||||
}
|
||||
else{ //PID Based on targetVel
|
||||
m_shooterFalcon.set(TalonFXControlMode.Velocity, targetVel); //Init PID
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -9,11 +9,15 @@ package frc4388.robot.subsystems;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
import com.revrobotics.CANEncoder;
|
||||
import com.revrobotics.CANPIDController;
|
||||
import com.revrobotics.CANSparkMax;
|
||||
import com.revrobotics.ControlType;
|
||||
import com.revrobotics.SparkMax;
|
||||
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
import frc4388.robot.Constants.StorageConstants;
|
||||
@@ -21,10 +25,17 @@ import frc4388.robot.Constants.StorageConstants;
|
||||
public class Storage extends SubsystemBase {
|
||||
private CANSparkMax m_storageMotor = new CANSparkMax(StorageConstants.STORAGE_CAN_ID, MotorType.kBrushless);
|
||||
private DigitalInput[] m_beamSensors = new DigitalInput[6];
|
||||
|
||||
CANPIDController m_storagePIDController = m_storageMotor.getPIDController();
|
||||
|
||||
CANEncoder m_encoder = m_storageMotor.getEncoder();
|
||||
|
||||
/**
|
||||
* Creates a new Storage.
|
||||
*/
|
||||
public Storage() {
|
||||
resetEncoder();
|
||||
|
||||
m_beamSensors[0] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_0);
|
||||
m_beamSensors[1] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_1);
|
||||
m_beamSensors[2] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_2);
|
||||
@@ -40,17 +51,42 @@ public class Storage extends SubsystemBase {
|
||||
|
||||
/**
|
||||
* Runs storage motor
|
||||
*
|
||||
* @param input the voltage to run motor at
|
||||
*/
|
||||
public void runStorage(double input) {
|
||||
public void runStorage(final double input) {
|
||||
m_storageMotor.set(input);
|
||||
boolean beam_on = m_beamSensors[0].get();
|
||||
final boolean beam_on = m_beamSensors[0].get();
|
||||
|
||||
if (beam_on) {
|
||||
//System.err.println("Beam on");
|
||||
} else {
|
||||
//System.err.println("Beam off");
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
public void resetEncoder()
|
||||
{
|
||||
m_encoder.setPosition(0);
|
||||
}
|
||||
|
||||
/* Storage PID Control */
|
||||
public void runStoragePositionPID(double targetPos, double kP, double kI, double kD, double kIz, double kF, double kmaxOutput, double kminOutput)
|
||||
{
|
||||
// Set PID Coefficients
|
||||
m_storagePIDController.setP(kP);
|
||||
m_storagePIDController.setI(kI);
|
||||
m_storagePIDController.setD(kD);
|
||||
m_storagePIDController.setIZone(kIz);
|
||||
m_storagePIDController.setFF(kF);
|
||||
m_storagePIDController.setOutputRange(kminOutput, kmaxOutput);
|
||||
|
||||
m_storagePIDController.setReference(targetPos, ControlType.kPosition);
|
||||
}
|
||||
|
||||
public void getEncoderPos()
|
||||
{
|
||||
m_encoder.getPosition();
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user