Merge pull request #10 from Team4388/Intake

Intake
This commit is contained in:
Pushkar9236
2022-02-26 13:03:22 -07:00
committed by GitHub
11 changed files with 369 additions and 22 deletions
+1
View File
@@ -160,3 +160,4 @@ bin/
# Simulation GUI and other tools window save file
*-window.json
.vscode/launch.json
+1 -1
View File
@@ -2,7 +2,7 @@ import edu.wpi.first.gradlerio.deploy.roborio.RoboRIO
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2022.1.1"
id "edu.wpi.first.GradleRIO" version "2022.2.1"
}
sourceCompatibility = JavaVersion.VERSION_11
+101
View File
@@ -0,0 +1,101 @@
{
"keyboardJoysticks": [
{
"axisConfig": [
{
"decKey": 65,
"incKey": 68
},
{
"decKey": 87,
"incKey": 83
},
{
"decKey": 69,
"decayRate": 0.0,
"incKey": 82,
"keyRate": 0.009999999776482582
}
],
"axisCount": 3,
"buttonCount": 4,
"buttonKeys": [
90,
88,
67,
86
],
"povConfig": [
{
"key0": 328,
"key135": 323,
"key180": 322,
"key225": 321,
"key270": 324,
"key315": 327,
"key45": 329,
"key90": 326
}
],
"povCount": 1
},
{
"axisConfig": [
{
"decKey": 74,
"incKey": 76
},
{
"decKey": 73,
"incKey": 75
}
],
"axisCount": 2,
"buttonCount": 4,
"buttonKeys": [
77,
44,
46,
47
],
"povCount": 0
},
{
"axisConfig": [
{
"decKey": 263,
"incKey": 262
},
{
"decKey": 265,
"incKey": 264
}
],
"axisCount": 2,
"buttonCount": 6,
"buttonKeys": [
260,
268,
266,
261,
269,
267
],
"povCount": 0
},
{
"axisCount": 0,
"buttonCount": 0,
"povCount": 0
}
],
"robotJoysticks": [
{
"useGamepad": true
},
{
"guid": "78696e70757401000000000000000000",
"useGamepad": true
}
]
}
+26
View File
@@ -0,0 +1,26 @@
{
"HALProvider": {
"Other Devices": {
"SPARK MAX [5]": {
"header": {
"open": true
}
},
"SPARK MAX [6]": {
"header": {
"open": true
}
}
}
},
"NTProvider": {
"types": {
"/FMSInfo": "FMSInfo",
"/LiveWindow/Intake": "Subsystem",
"/LiveWindow/LED": "Subsystem",
"/LiveWindow/Serializer": "Subsystem",
"/LiveWindow/Ungrouped/DigitalInput[3]": "Digital Input",
"/LiveWindow/Ungrouped/Scheduler": "Scheduler"
}
}
}
+15 -6
View File
@@ -68,15 +68,24 @@ public final class Constants {
}
public static final class SerializerConstants {
public static final double SERIALIZER_BELT_SPEED = 1.0; // TODO (currently max power, DO NOT RUN)
public static final double SERIALIZER_SHOOTER_BELT_SPEED = 1.0; // TODO (currently max power, DO NOT RUN)
public static final double SERIALIZER_BELT_SPEED = 1.d; // TODO (currently max power, DO NOT RUN)
public static final double SERIALIZER_SHOOTER_BELT_SPEED = 1.d; // TODO (currently max power, DO NOT RUN)
// CAN IDs
public static final int SERIALIZER_BELT = -1; // TODO
public static final int SERIALIZER_SHOOTER_BELT = -1; // TODO
public static final int SERIALIZER_BELT_BEAM = -1; // TODO
public static final int SERIALIZER_BELT = 2; // TODO
public static final int SERIALIZER_SHOOTER_BELT = 5; // TODO
public static final int SERIALIZER_BELT_BEAM = 3; // TODO
}
public static final class IntakeConstants {
// CAN IDs
public static final int INTAKE_MOTOR = 3;
public static final int EXTENDER_MOTOR = 6;
}
public static final class StorageConstants {
public static final int STORAGE_CAN_ID = -1; //TODO
public static final int BEAM_SENSOR_SHOOTER = -1; //TODO
public static final int BEAM_SENSOR_INTAKE = -1; //TODO
}
public static final class LEDConstants {
public static final int LED_SPARK_ID = 0;
@@ -10,6 +10,7 @@ import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc4388.robot.Constants.*;
import frc4388.robot.subsystems.Intake;
import frc4388.robot.subsystems.LED;
import frc4388.robot.subsystems.Serializer;
import frc4388.robot.subsystems.SwerveDrive;
@@ -28,7 +29,7 @@ public class RobotContainer {
/* RobotMap */
private final RobotMap m_robotMap = new RobotMap();
/* Subsystems */
/* Subsystems
private final SwerveDrive m_robotSwerveDrive = new SwerveDrive(
m_robotMap.leftFrontSteerMotor, m_robotMap.leftFrontWheelMotor,
m_robotMap.rightFrontSteerMotor, m_robotMap.rightFrontWheelMotor,
@@ -39,7 +40,8 @@ public class RobotContainer {
m_robotMap.leftBackEncoder,
m_robotMap.rightBackEncoder
);
*/
private final Intake m_robotIntake = new Intake(m_robotMap.intakeMotor, m_robotMap.extenderMotor);
private final Serializer m_robotSerializer = new Serializer(m_robotMap.serializerBelt, m_robotMap.serializerShooterBelt);
private final LED m_robotLED = new LED(m_robotMap.LEDController);
@@ -56,12 +58,17 @@ public class RobotContainer {
/* Default Commands */
// drives the swerve drive with a two-axis input from the driver controller
m_robotSwerveDrive.setDefaultCommand(
new RunCommand(() -> m_robotSwerveDrive.driveWithInput(-getDriverController().getLeftXAxis(),
getDriverController().getLeftYAxis(), -getDriverController().getRightXAxis(), false), m_robotSwerveDrive));
// m_robotSwerveDrive.setDefaultCommand(
// new RunCommand(() -> m_robotSwerveDrive.driveWithInput(-getDriverController().getLeftXAxis(),
// getDriverController().getLeftYAxis(), -getDriverController().getRightXAxis(), false), m_robotSwerveDrive));
m_robotIntake.setDefaultCommand(
new RunCommand(() -> m_robotIntake.runWithTriggers(
getDriverController().getLeftTriggerAxis(), getDriverController().getRightTriggerAxis()),m_robotIntake));
// continually sends updates to the Blinkin LED controller to keep the lights on
m_robotLED.setDefaultCommand(new RunCommand(m_robotLED::updateLED, m_robotLED));
m_robotLED.setDefaultCommand(
new RunCommand(m_robotLED::updateLED, m_robotLED));
// dri
}
/**
@@ -72,16 +79,28 @@ public class RobotContainer {
*/
private void configureButtonBindings() {
/* Driver Buttons */
/* Operator Buttons */
// extends and retracts the extender
new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON)
.whenPressed(() -> m_robotIntake.runExtender(true))
.whenReleased(() -> m_robotIntake.runExtender(false));
// activates "Lit Mode"
new JoystickButton(getOperatorJoystick(), XboxController.A_BUTTON)
.whenPressed(() -> m_robotLED.setPattern(LEDPatterns.LAVA_RAINBOW))
.whenReleased(() -> m_robotLED.setPattern(LEDConstants.DEFAULT_PATTERN));
// revisit this later, not sure if we will still use this
new JoystickButton(getOperatorJoystick(), XboxController.B_BUTTON)
.whenPressed(() -> m_robotSerializer.setSerializerStateWithBeam(true, m_robotSerializer.getBeam()))
.whenReleased(() -> m_robotSerializer.setSerializerStateWithBeam(false, m_robotSerializer.getBeam()));
new JoystickButton(getOperatorJoystick(), XboxController.RIGHT_BUMPER_BUTTON)
.whenPressed(() -> m_robotIntake.runExtender(true));
new JoystickButton(getOperatorJoystick(), XboxController.LEFT_BUMPER_BUTTON)
.whenPressed(() -> m_robotIntake.runExtender(false));
}
/**
+11 -4
View File
@@ -6,11 +6,14 @@ package frc4388.robot;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import com.ctre.phoenix.sensors.CANCoder;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import frc4388.robot.Constants.IntakeConstants;
import frc4388.robot.Constants.LEDConstants;
import frc4388.robot.Constants.SerializerConstants;
import frc4388.robot.Constants.SwerveDriveConstants;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
/**
* Defines and holds all I/O objects on the Roborio. This is useful for unit
@@ -20,7 +23,7 @@ public class RobotMap {
public RobotMap() {
configureLEDMotorControllers();
configureSwerveMotorControllers();
//configureSwerveMotorControllers();
}
/* LED Subsystem */
@@ -30,7 +33,7 @@ public class RobotMap {
}
/* Swerve Subsystem */
/* Swerve Subsystem
public final WPI_TalonFX leftFrontSteerMotor = new WPI_TalonFX(SwerveDriveConstants.LEFT_FRONT_STEER_CAN_ID);
public final WPI_TalonFX leftFrontWheelMotor = new WPI_TalonFX(SwerveDriveConstants.LEFT_FRONT_WHEEL_CAN_ID);
public final WPI_TalonFX rightFrontSteerMotor = new WPI_TalonFX(SwerveDriveConstants.RIGHT_FRONT_STEER_CAN_ID);
@@ -95,6 +98,10 @@ public class RobotMap {
/* Serializer Subsystem */
public final Spark serializerBelt = new Spark(SerializerConstants.SERIALIZER_BELT);
public final Spark serializerShooterBelt = new Spark(SerializerConstants.SERIALIZER_SHOOTER_BELT);
public final CANSparkMax serializerBelt = new CANSparkMax(SerializerConstants.SERIALIZER_BELT, MotorType.kBrushless);
public final CANSparkMax serializerShooterBelt = new CANSparkMax(SerializerConstants.SERIALIZER_SHOOTER_BELT, MotorType.kBrushless);
/* Intake Subsytem */
public final WPI_TalonFX intakeMotor = new WPI_TalonFX(IntakeConstants.INTAKE_MOTOR);
public final CANSparkMax extenderMotor = new CANSparkMax(IntakeConstants.EXTENDER_MOTOR, MotorType.kBrushless);
}
@@ -0,0 +1,64 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc4388.robot.subsystems;
//Imported Limit switch ONLY
import com.revrobotics.SparkMaxLimitSwitch;
import com.revrobotics.SparkMaxLimitSwitch.Type;
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.IdleMode;
public class Intake extends SubsystemBase {
private WPI_TalonFX m_intakeMotor;
private CANSparkMax m_extenderMotor;
private SparkMaxLimitSwitch m_inLimit;
private SparkMaxLimitSwitch m_outLimit;
public boolean toggle;
/** Creates a new Intake. */
public Intake(WPI_TalonFX intakeMotor, CANSparkMax extenderMotor) {
m_intakeMotor = intakeMotor;
m_extenderMotor = extenderMotor;
m_extenderMotor.restoreFactoryDefaults();
m_intakeMotor.setNeutralMode(NeutralMode.Brake);
m_intakeMotor.setInverted(false);
m_extenderMotor.setInverted(true);
m_inLimit = m_extenderMotor.getForwardLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
m_outLimit = m_extenderMotor.getForwardLimitSwitch(SparkMaxLimitSwitch.Type.kNormallyOpen);
m_inLimit.enableLimitSwitch(true);
m_outLimit.enableLimitSwitch(true);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
}
public void runWithTriggers(double leftTrigger, double rightTrigger) {
m_intakeMotor.set(rightTrigger - leftTrigger);
}
public void runExtender(boolean extended) {
double extenderMotorSpeed = extended ? 0.25d : 0.d;
m_extenderMotor.set(extenderMotorSpeed);
}
public void toggleExtender() {
toggle = !toggle;
runExtender(toggle);
}
//Test
}
@@ -4,20 +4,24 @@ import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc4388.robot.Constants;
import edu.wpi.first.wpilibj.DigitalInput;
import com.revrobotics.CANSparkMax;
public class Serializer extends SubsystemBase{
private Spark m_serializerBelt;
private Spark m_serializerShooterBelt;
private CANSparkMax m_serializerBelt;
private CANSparkMax m_serializerShooterBelt;
private DigitalInput m_serializerBeam;
private boolean serializerState;
public Serializer(Spark serializerBelt, Spark serializerShooterBelt) {
public Serializer(CANSparkMax serializerBelt, CANSparkMax serializerShooterBelt) {
m_serializerBelt = serializerBelt;
m_serializerShooterBelt = serializerShooterBelt;
m_serializerBeam = new DigitalInput(Constants.SerializerConstants.SERIALIZER_BELT_BEAM);
serializerState = false;
setSerializerState(serializerState);
m_serializerBelt.set(0);
m_serializerShooterBelt.set(0);
}
public boolean getBeam() {
return m_serializerBeam.get();
@@ -0,0 +1,43 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc4388.robot.subsystems;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import edu.wpi.first.wpilibj.DigitalInput;
import frc4388.robot.Constants.StorageConstants;
public class Storage extends SubsystemBase {
public CANSparkMax m_storageMotor = new CANSparkMax(StorageConstants.STORAGE_CAN_ID, MotorType.kBrushless);
private DigitalInput m_beamShooter = new DigitalInput(StorageConstants.BEAM_SENSOR_SHOOTER);
private DigitalInput m_beamIntake = new DigitalInput(StorageConstants.BEAM_SENSOR_INTAKE);
/** Creates a new Storage. */
public Storage() {
}
public void manageStorage() {
if (m_beamShooter.get()) {
runStorage(1.d);
} else { runStorage(0.d); }
}
public void runStorage(double input) {
m_storageMotor.set(input);
}
public boolean getBeamShooter(){
return m_beamShooter.get();
}
public boolean getBeamIntake(){
return m_beamIntake.get();
}
@Override
public void periodic() {
manageStorage();
}
}
+73
View File
@@ -0,0 +1,73 @@
{
"fileName": "REVLib.json",
"name": "REVLib",
"version": "2022.1.1",
"uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb",
"mavenUrls": [
"https://maven.revrobotics.com/"
],
"jsonUrl": "https://software-metadata.revrobotics.com/REVLib.json",
"javaDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-java",
"version": "2022.1.1"
}
],
"jniDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2022.1.1",
"skipInvalidPlatforms": true,
"isJar": false,
"validPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxaarch64bionic",
"linuxx86-64",
"linuxathena",
"linuxraspbian",
"osxx86-64"
]
}
],
"cppDependencies": [
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-cpp",
"version": "2022.1.1",
"libName": "REVLib",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxaarch64bionic",
"linuxx86-64",
"linuxathena",
"linuxraspbian",
"osxx86-64"
]
},
{
"groupId": "com.revrobotics.frc",
"artifactId": "REVLib-driver",
"version": "2022.1.1",
"libName": "REVLibDriver",
"headerClassifier": "headers",
"sharedLibrary": false,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"windowsx86",
"linuxaarch64bionic",
"linuxx86-64",
"linuxathena",
"linuxraspbian",
"osxx86-64"
]
}
]
}