Merge branch 'master' into Manual-Shooter

This commit is contained in:
ryan123rudder
2020-02-15 13:18:15 -08:00
committed by GitHub
31 changed files with 245 additions and 46 deletions
+11 -9
View File
@@ -66,28 +66,30 @@ public final class Constants {
}
public static final class IntakeConstants {
public static final int INTAKE_SPARK_ID = 9;
public static final int EXTENDER_SPARK_ID = 10;
public static final int INTAKE_SPARK_ID = -9;
public static final int EXTENDER_SPARK_ID = -10;
}
public static final class ShooterConstants {
/* Motor IDs */
public static final int SHOOTER_FALCON_ID = 8;
public static final int SHOOTER_ANGLE_ADJUST_ID = 9;
public static final int SHOOTER_ROTATE_ID = 10;
/* 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);
//#Janky
public static final int SHOOTERROTATION_SPARK_ID = 9;
//#Janky
public static final Gains DRUM_SHOOTER_GAINS = new Gains(0.4, 0.0005, 13, 0.05, 0, 1.0);
public static final Gains SHOOTER_TURRET_GAINS = new Gains(0.2, 0.0, 0.0, 0.0, 0, 1.0);
public static final double SHOOTER_TURRET_MIN = -1.0;
public static final double ENCODER_TICKS_PER_REV = 2048;
public static final double NEO_UNITS_PER_REV = 42;
public static final double DEGREES_PER_ROT = 360;
}
public static final class ClimberConstants {
public static final int CLIMBER_SPARK_ID = 10;
public static final int CLIMBER_SPARK_ID = -1;
}
public static final class LevelerConstants {
@@ -16,6 +16,7 @@ import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc4388.robot.Constants.*;
import frc4388.robot.commands.DriveStraightAtVelocityPID;
import frc4388.robot.commands.DriveWithJoystick;
import frc4388.robot.commands.DriveStraightToPositionMM;
import frc4388.robot.commands.DriveStraightToPositionPID;
import frc4388.robot.commands.DriveWithJoystickUsingDeadAssistPID;
@@ -73,14 +74,12 @@ public class RobotContainer {
m_robotLED.setDefaultCommand(new RunCommand(() -> m_robotLED.updateLED(), m_robotLED));
// runs the drum shooter in idle mode
//#Janky
m_robotShooter.setDefaultCommand(new RunCommand(() -> m_robotShooter.runShooterWithInput(m_operatorXbox), m_robotShooter));
//#Janky
// drives the leveler with an axis input from the driver controller
m_robotLeveler.setDefaultCommand(new RunLevelerWithJoystick(m_robotLeveler, getDriverController()));
// m_robotLeveler.setDefaultCommand(new RunLevelerWithJoystick(m_robotLeveler, getDriverController()));
// runs storage motor at 50 percent
m_robotStorage.setDefaultCommand(new RunCommand(() -> m_robotStorage.runStorage(0.0), m_robotStorage));
// m_robotStorage.setDefaultCommand(new RunCommand(() -> m_robotStorage.runStorage(0.0), m_robotStorage));
}
/**
@@ -123,6 +122,7 @@ public class RobotContainer {
new JoystickButton(getDriverJoystick(), XboxController.Y_BUTTON)
.whenPressed(new RunCommand(() -> m_robotDrive.runTurningPID(45), m_robotDrive));
// sets solenoids into high gear
new JoystickButton(getDriverJoystick(), XboxController.START_BUTTON)
.whenPressed(new InstantCommand(() -> m_robotDrive.setShiftState(true), m_robotDrive));
@@ -0,0 +1,52 @@
/*----------------------------------------------------------------------------*/
/* 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.Drive;
public class PlaySongDrive extends CommandBase {
private Drive m_drive;
/**
* Creates a new PlaySongDrive.
*/
public PlaySongDrive(Drive subsystem) {
// Use addRequirements() here to declare subsystem dependencies.
m_drive = subsystem;
addRequirements(m_drive);
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
m_drive.m_rightFrontMotor.set(0);
m_drive.m_leftFrontMotor.set(0);
m_drive.m_rightBackMotor.set(0);
m_drive.m_leftBackMotor.set(0);
}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_drive.playSong();
//System.err.println("Playing " + m_drive.m_orchestra.isPlaying());
//m_drive.m_driveTrain.feedWatchdog();
}
// 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;
}
}
@@ -7,6 +7,16 @@
package frc4388.robot.subsystems;
import java.io.File;
import java.io.FilenameFilter;
import java.io.IOException;
import java.nio.file.Files;
import java.nio.file.Path;
import java.nio.file.Paths;
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;
@@ -18,11 +28,15 @@ import com.ctre.phoenix.motorcontrol.SensorTerm;
import com.ctre.phoenix.motorcontrol.StatusFrame;
import com.ctre.phoenix.motorcontrol.TalonFXControlMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import com.ctre.phoenix.music.Orchestra;
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;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
@@ -42,6 +56,7 @@ public class Drive extends SubsystemBase {
public WPI_TalonFX m_leftBackMotor = new WPI_TalonFX(DriveConstants.DRIVE_LEFT_BACK_CAN_ID);
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 Orchestra m_orchestra = new Orchestra();
public DifferentialDrive m_driveTrain = new DifferentialDrive(m_leftFrontMotor, m_rightFrontMotor);
@@ -51,6 +66,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;
SendableChooser<String> m_songChooser = new SendableChooser<String>();
public DoubleSolenoid speedShift;
/**
@@ -80,7 +97,7 @@ public class Drive extends SubsystemBase {
/* flip input so forward becomes back, etc */
m_leftFrontMotor.setInverted(false);
m_rightFrontMotor.setInverted(true);
m_driveTrain.setRightSideInverted(false);
//m_driveTrain.setRightSideInverted(false);
m_leftBackMotor.setInverted(InvertType.FollowMaster);
m_rightBackMotor.setInverted(InvertType.FollowMaster);
@@ -235,8 +252,22 @@ public class Drive extends SubsystemBase {
* true means talon's local output is PID0 - PID1, and other side Talon is PID0 + PID1
*/
m_rightFrontMotor.configAuxPIDPolarity(false, DriveConstants.DRIVE_TIMEOUT_MS);
m_orchestra.addInstrument(m_leftBackMotor);
m_orchestra.addInstrument(m_rightFrontMotor);
m_orchestra.addInstrument(m_rightBackMotor);
m_orchestra.addInstrument(m_leftFrontMotor);
File songsDir = new File(Filesystem.getDeployDirectory().getAbsolutePath() + "/songs");
System.err.println(songsDir.getPath());
String[] songsStrings = songsDir.list();
for (String songString : songsStrings){
m_songChooser.addOption(songString, songsDir.getAbsolutePath() + "/" + songString);
}
Shuffleboard.getTab("Songs").add(m_songChooser);
}
String currentSong = "";
@Override
public void periodic() {
try {
@@ -264,6 +295,11 @@ 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));
if (currentSong != m_songChooser.getSelected()){
currentSong = m_songChooser.getSelected();
selectSong(currentSong);
System.err.println(currentSong);
}
} catch (Exception e) {
System.err.println("Error in the Drive Subsystem");
//e.printStackTrace(System.err);
@@ -333,7 +369,7 @@ public class Drive extends SubsystemBase {
* using the Differential Drive class to manage the two inputs
*/
public void driveWithInput(double move, double steer){
m_driveTrain.arcadeDrive(move, steer);
//m_driveTrain.arcadeDrive(move, steer);
}
/**
@@ -362,7 +398,7 @@ public class Drive extends SubsystemBase {
m_rightFrontMotor.set(TalonFXControlMode.Position, targetPos, DemandType.AuxPID, targetGyro);
m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1);
m_driveTrain.feedWatchdog();
//m_driveTrain.feedWatchdog();
}
/**
@@ -376,7 +412,7 @@ public class Drive extends SubsystemBase {
m_rightFrontMotor.set(TalonFXControlMode.Velocity, targetVel, DemandType.AuxPID, targetGyro);
m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1);
m_driveTrain.feedWatchdog();
//m_driveTrain.feedWatchdog();
}
/**
@@ -392,6 +428,7 @@ public class Drive extends SubsystemBase {
m_leftFrontMotor.follow(m_rightFrontMotor, FollowerType.AuxOutput1);
m_driveTrain.feedWatchdog();
}
/**
@@ -442,6 +479,21 @@ public class Drive extends SubsystemBase {
m_pigeon.setAccumZAngle(0);
}
/**
* Plays Music!
*/
public void playSong() {
m_orchestra.play();
}
/**
* Selects a song to play!
* @param song The name of the song to be played
*/
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
@@ -10,8 +10,12 @@ 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 com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.IdleMode;
import com.revrobotics.CANEncoder;
import com.revrobotics.CANPIDController;
import com.revrobotics.ControlType;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj.Joystick;
@@ -19,25 +23,40 @@ import edu.wpi.first.wpilibj.XboxController;
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;
import frc4388.utility.controller.IHandController;
public class Shooter extends SubsystemBase {
public WPI_TalonFX m_shooterFalcon = new WPI_TalonFX(ShooterConstants.SHOOTER_FALCON_ID);
public CANSparkMax m_angleAdjustMotor = new CANSparkMax(ShooterConstants.SHOOTER_ANGLE_ADJUST_ID, MotorType.kBrushless);
public CANSparkMax m_shooterRotateMotor = new CANSparkMax(ShooterConstants.SHOOTER_ROTATE_ID, MotorType.kBrushless);
public static Gains m_shooterGains = ShooterConstants.SHOOTER_GAINS;
public static Gains m_shooterGains = ShooterConstants.DRUM_SHOOTER_GAINS;
public static Shooter m_shooter;
public static IHandController m_controller;
// Configure PID Controllers
CANPIDController m_angleAdjustPIDController = m_angleAdjustMotor.getPIDController();
CANPIDController m_shooterRotatePIDController = m_shooterRotateMotor.getPIDController();
CANEncoder m_angleEncoder = m_angleAdjustMotor.getEncoder();
CANEncoder m_shooterRotateEncoder = m_shooterRotateMotor.getEncoder();
double velP;
double input;
public static CANSparkMax m_shooterRotate = new CANSparkMax(ShooterConstants.SHOOTERROTATION_SPARK_ID, MotorType.kBrushless);
/*
* Creates a new Shooter subsystem.
*/
public Shooter() {
//Testing purposes reseting gyros
resetGyroAngleAdj();
resetGyroShooterRotate();
m_shooterFalcon.configFactoryDefault();
m_shooterRotate.setIdleMode(IdleMode.kBrake);
m_shooterFalcon.setNeutralMode(NeutralMode.Coast);
@@ -96,17 +115,8 @@ public class Shooter extends SubsystemBase {
m_shooterFalcon.set(TalonFXControlMode.Velocity, targetVel); //Init PID
}
}
//PLZ Help I Have No Idea What I Am Doing
//Help PLZ
//I Am Desperate
//PLZ
//PLZ
//With A Cherry On Top
//#Janky
public void runShooterWithInput(IHandController controller) {
/* m_controller = controller;
input = controller.getLeftXAxis();
@@ -115,7 +125,52 @@ public class Shooter extends SubsystemBase {
*/
input = controller.getLeftXAxis();
System.err.println(input);
m_shooterRotate.set(input);
m_shooterRotateMotor.set(input);
}
/* Angle Adjustment PID Control */
public void runAngleAdjustPID(double targetAngle)
{
// Set PID Coefficients
m_angleAdjustPIDController.setP(m_shooterGains.m_kP);
m_angleAdjustPIDController.setI(m_shooterGains.m_kI);
m_angleAdjustPIDController.setD(m_shooterGains.m_kD);
m_angleAdjustPIDController.setIZone(m_shooterGains.m_kIzone);
m_angleAdjustPIDController.setFF(m_shooterGains.m_kF);
m_angleAdjustPIDController.setOutputRange(ShooterConstants.SHOOTER_TURRET_MIN, m_shooterGains.m_kPeakOutput);
// Convert input angle in degrees to rotations of the motor
targetAngle = targetAngle/ShooterConstants.DEGREES_PER_ROT;
m_angleAdjustPIDController.setReference(targetAngle, ControlType.kPosition);
}
/* Rotate Shooter PID Control */
public void runshooterRotatePID(double targetAngle)
{
// Set PID Coefficients
m_shooterRotatePIDController.setP(m_shooterGains.m_kP);
m_shooterRotatePIDController.setI(m_shooterGains.m_kI);
m_shooterRotatePIDController.setD(m_shooterGains.m_kD);
m_shooterRotatePIDController.setFF(m_shooterGains.m_kF);
m_shooterRotatePIDController.setIZone(m_shooterGains.m_kIzone);
m_shooterRotatePIDController.setOutputRange(ShooterConstants.SHOOTER_TURRET_MIN, m_shooterGains.m_kPeakOutput);
// Convert input angle in degrees to rotations of the motor
targetAngle = targetAngle/ShooterConstants.DEGREES_PER_ROT;
m_shooterRotatePIDController.setReference(targetAngle, ControlType.kPosition);
}
/* For Testing Purposes, reseting gyro for angle adjuster */
public void resetGyroAngleAdj()
{
m_angleEncoder.setPosition(0);
}
/* For Testing Purposes, reseting gyro for shooter rotation */
public void resetGyroShooterRotate()
{
m_shooterRotateEncoder.setPosition(0);
}
//#Janky
}
@@ -56,6 +56,7 @@ public class Storage extends SubsystemBase {
public void runStorage(final double input) {
m_storageMotor.set(input);
final boolean beam_on = m_beamSensors[0].get();
}
public void resetEncoder()