Merge branch 'master' into add-gear-shifting-with-pcm

This commit is contained in:
Keenan D. Buckley
2020-02-08 23:11:14 +00:00
committed by GitHub
10 changed files with 382 additions and 17 deletions
+19 -2
View File
@@ -68,10 +68,27 @@ public final class Constants {
public static final class IntakeConstants {
public static final int INTAKE_SPARK_ID = 1;
}
public static final class ClimberConstants {
public static final int CLIMBER_SPARK_ID = 10;
}
public static final class LevelerConstants {
public static final int LEVELER_CAN_ID = 9;
}
public static final class StorageConstants {
public static final int STORAGE_CAN_ID = -1;
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;
}
public static final class LEDConstants {
public static final int LED_SPARK_ID = 0;
public static final LEDPatterns DEFAULT_PATTERN = LEDPatterns.FOREST_WAVES;
}
@@ -17,10 +17,15 @@ 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.RunClimberWithTriggers;
import frc4388.robot.commands.RunIntakeWithTriggers;
import frc4388.robot.subsystems.Climber;
import frc4388.robot.commands.RunLevelerWithJoystick;
import frc4388.robot.subsystems.Drive;
import frc4388.robot.subsystems.Intake;
import frc4388.robot.subsystems.LED;
import frc4388.robot.subsystems.Leveler;
import frc4388.robot.subsystems.Storage;
import frc4388.utility.LEDPatterns;
import frc4388.utility.controller.IHandController;
import frc4388.utility.controller.XboxController;
@@ -37,6 +42,9 @@ 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 Climber m_robotClimber = new Climber();
private final Leveler m_robotLeveler = new Leveler();
private final Storage m_robotStorage = new Storage();
/* Controllers */
private final XboxController m_driverXbox = new XboxController(OIConstants.XBOX_DRIVER_ID);
@@ -53,8 +61,14 @@ public class RobotContainer {
m_robotDrive.setDefaultCommand(new DriveWithJoystick(m_robotDrive, getDriverController()));
// drives motor 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));
// 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
m_robotStorage.setDefaultCommand(new RunCommand(() -> m_robotStorage.runStorage(0.0), m_robotStorage));
}
/**
@@ -0,0 +1,63 @@
/*----------------------------------------------------------------------------*/
/* 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.Climber;
import frc4388.utility.controller.IHandController;
public class RunClimberWithTriggers extends CommandBase {
private Climber m_climber;
private IHandController m_controller;
/**
* Uses input from opperator triggers to control climber motor
* @param subsystem the climber subsystem
* @param controller the driver controller
*/
public RunClimberWithTriggers(Climber subsystem, IHandController controller) {
m_climber = subsystem;
m_controller = controller;
addRequirements(m_climber);
}
// 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() {
double rightTrigger = m_controller.getRightTriggerAxis();
double leftTrigger = m_controller.getLeftTriggerAxis();
double output = 0;
if (rightTrigger < .5) {
if(rightTrigger > leftTrigger) {
output = rightTrigger;
}
if (leftTrigger > rightTrigger) {
output = -leftTrigger;
}
} else {
output = rightTrigger;
}
m_climber.runClimber(output);
}
// 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,53 @@
/*----------------------------------------------------------------------------*/
/* 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.Leveler;
import frc4388.utility.controller.IHandController;
public class RunLevelerWithJoystick extends CommandBase {
private Leveler m_leveler;
private IHandController m_controller;
/**
* Creates a new RunLevelerWithJoystick to control the leveler with an Xbox controller.
* @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 RunLevelerWithJoystick(Leveler subsystem, IHandController controller) {
m_leveler = subsystem;
m_controller = controller;
addRequirements(m_leveler);
}
// 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() {
double input = m_controller.getLeftXAxis();
m_leveler.runLeveler(input);
}
// 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,46 @@
/*----------------------------------------------------------------------------*/
/* 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.revrobotics.CANDigitalInput;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANDigitalInput.LimitSwitchPolarity;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
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;
/**
* 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);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
}
/**
* Runs climber motor
* @param input the voltage to run motor at
*/
public void runClimber(double input) {
m_climberMotor.set(input);
}
}
@@ -18,6 +18,7 @@ public class Intake extends SubsystemBase {
* Creates a new Intake.
*/
public Intake() {
m_intakeMotor.setInverted(false);
}
@@ -0,0 +1,45 @@
/*----------------------------------------------------------------------------*/
/* 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.can.TalonSRX;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.IdleMode;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj.Talon;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc4388.robot.Constants.LevelerConstants;
public class Leveler extends SubsystemBase {
CANSparkMax m_levelerMotor = new CANSparkMax(LevelerConstants.LEVELER_CAN_ID, MotorType.kBrushless);
/**
* Creates a new Leveler.
*/
public Leveler() {
m_levelerMotor.restoreFactoryDefaults();
m_levelerMotor.setIdleMode(IdleMode.kCoast);
m_levelerMotor.setInverted(false);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
}
/**
* Runs intake motor
* @param input the percent output to run motor at
*/
public void runLeveler(double input) {
m_levelerMotor.set(input);
}
}
@@ -0,0 +1,56 @@
/*----------------------------------------------------------------------------*/
/* 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.can.TalonSRX;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.revrobotics.CANSparkMax;
import com.revrobotics.SparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
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];
/**
* Creates a new Storage.
*/
public Storage() {
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);
m_beamSensors[3] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_3);
m_beamSensors[4] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_4);
m_beamSensors[5] = new DigitalInput(StorageConstants.BEAM_SENSOR_DIO_5);
}
@Override
public void periodic() {
// NO
}
/**
* Runs storage motor
* @param input the voltage to run motor at
*/
public void runStorage(double input) {
m_storageMotor.set(input);
boolean beam_on = m_beamSensors[0].get();
if (beam_on) {
System.err.println("Beam on");
} else {
System.err.println("Beam off");
}
}
}
+15 -15
View File
@@ -1,7 +1,7 @@
{
"fileName": "Phoenix.json",
"name": "CTRE-Phoenix",
"version": "5.17.3",
"version": "5.17.4",
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
"http://devsite.ctr-electronics.com/maven/release/"
@@ -11,19 +11,19 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.17.3"
"version": "5.17.4"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.17.3"
"version": "5.17.4"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.17.3",
"version": "5.17.4",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -35,7 +35,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "diagnostics",
"version": "5.17.3",
"version": "5.17.4",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -47,7 +47,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "canutils",
"version": "5.17.3",
"version": "5.17.4",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -58,7 +58,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "platform-stub",
"version": "5.17.3",
"version": "5.17.4",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -69,7 +69,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "core",
"version": "5.17.3",
"version": "5.17.4",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
@@ -83,7 +83,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.17.3",
"version": "5.17.4",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": false,
@@ -97,7 +97,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.17.3",
"version": "5.17.4",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": false,
@@ -111,7 +111,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.17.3",
"version": "5.17.4",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": false,
@@ -125,7 +125,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "diagnostics",
"version": "5.17.3",
"version": "5.17.4",
"libName": "CTRE_PhoenixDiagnostics",
"headerClassifier": "headers",
"sharedLibrary": false,
@@ -139,7 +139,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "canutils",
"version": "5.17.3",
"version": "5.17.4",
"libName": "CTRE_PhoenixCanutils",
"headerClassifier": "headers",
"sharedLibrary": false,
@@ -152,7 +152,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "platform-stub",
"version": "5.17.3",
"version": "5.17.4",
"libName": "CTRE_PhoenixPlatform",
"headerClassifier": "headers",
"sharedLibrary": false,
@@ -165,7 +165,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "core",
"version": "5.17.3",
"version": "5.17.4",
"libName": "CTRE_PhoenixCore",
"headerClassifier": "headers",
"sharedLibrary": false,
+70
View File
@@ -0,0 +1,70 @@
{
"fileName": "REVRobotics.json",
"name": "REVRobotics",
"version": "1.5.1",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
"http://www.revrobotics.com/content/sw/max/sdk/maven/"
],
"jsonUrl": "http://www.revrobotics.com/content/sw/max/sdk/REVRobotics.json",
"javaDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "SparkMax-java",
"version": "1.5.1"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "SparkMax-driver",
"version": "1.5.1",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxaarch64bionic",
"linuxx86-64",
"linuxathena",
"linuxraspbian"
]
}
],
"cppDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "SparkMax-cpp",
"version": "1.5.1",
"libName": "SparkMax",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxaarch64bionic",
"linuxx86-64",
"linuxathena",
"linuxraspbian"
]
},
{
"groupId": "com.revrobotics.frc",
"artifactId": "SparkMax-driver",
"version": "1.5.1",
"libName": "SparkMaxDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxaarch64bionic",
"linuxx86-64",
"linuxathena",
"linuxraspbian"
]
}
]
}