Skip to content

Commit

Permalink
Merge pull request #1 from Spectrum3847/Dripping-Springs
Browse files Browse the repository at this point in the history
Dripping springs Updates, merge into main
  • Loading branch information
allengregoryiv authored Mar 15, 2022
2 parents 9158ff1 + f05f250 commit 6687ff1
Show file tree
Hide file tree
Showing 16 changed files with 141 additions and 61 deletions.
Binary file modified .gradle/file-system.probe
Binary file not shown.
4 changes: 4 additions & 0 deletions networktables.ini
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
[NetworkTables Storage 3.0]
string "/Preferences/.type"="RobotPreferences"
double "/Preferences/LL-AIM Tolerance"=1
double "/Preferences/LL-AIM kD"=0
double "/Preferences/LL-AIM kI"=0
double "/Preferences/LL-AIM kP"=0.8
double "/Preferences/Swerve: Theta kD"=0
double "/Preferences/Swerve: Theta kP"=1000
double "/Preferences/Swerve: X kD"=20
Expand Down
16 changes: 16 additions & 0 deletions networktables.ini.bak
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,15 @@ double "/Preferences/Swerve: X kD"=20
double "/Preferences/Swerve: X kP"=2300
double "/Preferences/Swerve: Y kD"=20
double "/Preferences/Swerve: Y kP"=2300
double "/Shuffleboard/Climber/Climber Config/Acceleration"=0
double "/Shuffleboard/Climber/Climber Config/Closed Loop Ramp Rate"=0
double "/Shuffleboard/Climber/Climber Config/CruiseVelocity"=0
double "/Shuffleboard/Climber/Climber Config/Open Loop Ramp Rate"=0
double "/Shuffleboard/Climber/Climber Config/kD"=0
double "/Shuffleboard/Climber/Climber Config/kF"=0.05
double "/Shuffleboard/Climber/Climber Config/kI"=0
double "/Shuffleboard/Climber/Climber Config/kIzone"=150
double "/Shuffleboard/Climber/Climber Config/kP"=0
double "/Shuffleboard/Gamepads/Driver 0/xLeftDeadband"=0.1
double "/Shuffleboard/Gamepads/Driver 0/xLeftExpVal"=1
double "/Shuffleboard/Gamepads/Driver 0/xLeftScalar"=1
Expand Down Expand Up @@ -34,4 +42,12 @@ double "/Shuffleboard/Gamepads/Operator 1/yRightScalar"=1
double "/Shuffleboard/Launcher/Launcher Config/kF"=0.0609999
double "/Shuffleboard/Launcher/Launcher Config/kI"=0.000499964
double "/Shuffleboard/Launcher/Launcher Config/kP"=0.0465
double "/Shuffleboard/Swerve/Drive Mod 0/Acceleration"=0
double "/Shuffleboard/Swerve/Drive Mod 0/Closed Loop Ramp Rate"=0
double "/Shuffleboard/Swerve/Drive Mod 0/CruiseVelocity"=0
double "/Shuffleboard/Swerve/Drive Mod 0/Open Loop Ramp Rate"=0.25575
double "/Shuffleboard/Swerve/Drive Mod 0/kD"=0
double "/Shuffleboard/Swerve/Drive Mod 0/kF"=0
double "/Shuffleboard/Swerve/Drive Mod 0/kI"=0
double "/Shuffleboard/Swerve/Drive Mod 0/kIzone"=0
double "/Shuffleboard/Swerve/Drive Mod 0/kP"=0.0999999
4 changes: 2 additions & 2 deletions simgui-window.json
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@
"Window": {
"###/SmartDashboard/Field": {
"Collapsed": "0",
"Pos": "300,46",
"Size": "560,342"
"Pos": "274,46",
"Size": "586,378"
},
"###FMS": {
"Collapsed": "0",
Expand Down
1 change: 1 addition & 0 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
"types": {
"/FMSInfo": "FMSInfo",
"/Shuffleboard/Main/SendableChooser[0]": "String Chooser",
"/Shuffleboard/Main/SendableChooser[1]": "String Chooser",
"/SmartDashboard/Field": "Field2d"
},
"windows": {
Expand Down
27 changes: 17 additions & 10 deletions src/main/java/frc/robot/AutonSetup.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,27 +5,34 @@
import edu.wpi.first.wpilibj2.command.PrintCommand;
import frc.robot.commands.auto.RightDoubleBall;
import frc.robot.commands.auto.TestPathPlanner;
import frc.robot.constants.AutonConstants;

public class AutonSetup {

// A simple auto routine that drives forward a specified distance, and then
// stops.
private static final Command simpleAuto = new PrintCommand("TEST SIMPLE AUTO");
//Positions
public static final SendableChooser<Double> posChooser = new SendableChooser<>();

// A complex auto routine that drives forward, drops a hatch, and then drives
// backward.
//AutoRoutines
private static final Command complexAuto = new PrintCommand("TEST COMPLEX AUTO");

private static final Command testPathPlanner = new RightDoubleBall();
private static final Command DoubleBall = new RightDoubleBall();

// A chooser for autonomous commands
public static final SendableChooser<Command> chooser = new SendableChooser<>();

public static void setupSelector() {
chooser.setDefaultOption("Simple Auto", simpleAuto);
public static void setupSelectors() {
posChooser.setDefaultOption("1. Left", AutonConstants.pos1angle);
posChooser.addOption("2. Middle", AutonConstants.pos2angle);
posChooser.addOption("3. Right", AutonConstants.pos3angle);

chooser.setDefaultOption("DoubleBall", DoubleBall);
chooser.addOption("Complex Auto", complexAuto);
chooser.addOption("Test Path Planner", testPathPlanner);
}

//Return the starting angle for each position
public static double getAutonAngle(){
return posChooser.getSelected();
}

/**
* Use this to pass the autonomous command to the main {@link Robot} class.
*
Expand Down
9 changes: 8 additions & 1 deletion src/main/java/frc/robot/Gamepads.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import frc.lib.gamepads.AndButton;
import frc.lib.gamepads.AndNotButton;
import frc.lib.gamepads.AxisButton;
import frc.lib.gamepads.XboxGamepad;
import frc.lib.util.Alert;
import frc.robot.Robot.RobotState;
Expand Down Expand Up @@ -90,6 +91,9 @@ public static void driverBindings() {

new AndNotButton(driver.aButton, driver.leftBumper).whileHeld(BallPathCommands.intakeBalls());
new AndNotButton(driver.yButton, driver.leftBumper).whileHeld(BallPathCommands.eject());
new AndNotButton(driver.xButton, driver.leftBumper).whileHeld(BallPathCommands.feed());
driver.startButton.whenPressed(BallPathCommands.tarmacShot());
driver.selectButton.whenPressed(BallPathCommands.stopLauncher());

// Aim with limelight
driver.rightBumper.whileHeld(new LLAim());
Expand Down Expand Up @@ -120,11 +124,14 @@ public static void operatorBindings() {
// Climber Controls
operator.Dpad.Up.whenPressed(ClimberCommands.fullUp());
operator.Dpad.Down.whenPressed(ClimberCommands.climb());
operator.Dpad.Left.whenPressed(ClimberCommands.extendNextRung());
operator.Dpad.Left.whenPressed(ClimberCommands.nextRungDown());
operator.Dpad.Right.whenPressed(ClimberCommands.nextRungUp());

//Manual climb tilt control
operator.leftBumper.whileHeld(ClimberCommands.tiltUp());

//Return to default command when pressed
operator.leftStickButton.whileHeld(Robot.climber.defaultCommand());
}

// Configure the button bindings for the driver control in Test Mode
Expand Down
6 changes: 5 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,11 @@ public void autonomousInit() {
LiveWindow.disableAllTelemetry();

// schedule the autonomous command (example)
visionLL.limeLightLEDOn();
m_autonomousCommand = AutonSetup.getAutonomousCommand();
double angle = AutonSetup.getAutonAngle();
Robot.swerve.resetGyro(angle);

if (m_autonomousCommand != null) {
m_autonomousCommand.schedule();
}
Expand Down Expand Up @@ -271,7 +275,7 @@ private static String getMACaddress() {
}
MAC = String.join(":", hexadecimal);
return MAC;
} catch (UnknownHostException | SocketException e) {
} catch (UnknownHostException | SocketException | NullPointerException e) {
e.printStackTrace();
}
return "";
Expand Down
62 changes: 36 additions & 26 deletions src/main/java/frc/robot/commands/ClimberCommands.java
Original file line number Diff line number Diff line change
@@ -1,57 +1,67 @@
package frc.robot.commands;


import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Robot;
import frc.robot.constants.ClimberConstants;

public class ClimberCommands {
/* Climber Sequence
* 1. fullUp
* 2. climb
* 3. nextRungExtend
* 4. nextRungUp
* Repeat 2-4.
*/
/*
* Climber Sequence
* 1. fullUp
* 2. climb
* 3. nextRungExtend
* 4. nextRungUp
* Repeat 2-4.
*/

//Put the climber fully up, used to grab the mid bar
public static Command fullUp(){
return tiltUp().alongWith(extendFull());
// Put the climber fully up, used to grab the mid bar
public static Command fullUp() {
return extendFull().alongWith(new WaitCommand(0.5).andThen(tiltUp()));
}

//Put the climber partially out and tilted up, used to grab the next rung
public static Command nextRungUp(){
// Put the climber partially out and tilted up, used to grab the next rung
public static Command nextRungUp() {
return tiltUp().alongWith(extendNextRung());
}

//pull the climber down, used to climb to mid bar, and from rung to rung
public static Command climb(){
return tiltDown().alongWith(pull());
public static Command nextRungDown(){
return extendNextRung().alongWith(releaseRung());
}

// pull the climber down, used to climb to mid bar, and from rung to rung
public static Command climb() {
return pull().alongWith(new WaitCommand(0.1).andThen(tiltDown()));
}

// release rung
public static Command releaseRung() {
return tiltUp().withTimeout(0.2).andThen(tiltDown());
}

public static Command extendFull(){
public static Command extendFull() {
return toPosition(ClimberConstants.fullExtend);
}

//Used to extend before tilting up to grab the next rung
public static Command extendNextRung(){
// Used to extend before tilting up to grab the next rung
public static Command extendNextRung() {
return toPosition(ClimberConstants.nextRungExtend);
}

public static Command pull(){
public static Command pull() {
return toPosition(ClimberConstants.fullRetract);
}

public static Command toPosition(double position){
return new RunCommand(()-> Robot.climber.setMMPosition(position), Robot.climber);
public static Command toPosition(double position) {
return new RunCommand(() -> Robot.climber.setMMPosition(position), Robot.climber);
}

public static Command tiltUp(){
return new RunCommand(()-> Robot.climber.tiltUp(), Robot.climber.pneumatic);
public static Command tiltUp() {
return new RunCommand(() -> Robot.climber.tiltUp(), Robot.climber.pneumatic);
}

public static Command tiltDown(){
return new RunCommand(()-> Robot.climber.tiltDown(), Robot.climber.pneumatic);
public static Command tiltDown() {
return new RunCommand(() -> Robot.climber.tiltDown(), Robot.climber.pneumatic);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,10 @@ public static Command runFeeder(double speed) {
return new StartEndCommand(() -> Robot.feeder.setManualOutput(speed), () -> Robot.feeder.stop(), Robot.feeder);
}

public static Command stopLauncher(){
return new RunCommand(() -> Robot.launcher.setManualOutput(0.0), Robot.launcher);
}

// Run launcher motor
public static Command runLauncher(double speed) {
return new RunCommand(() -> Robot.launcher.setManualOutput(speed), Robot.launcher);
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/swerve/LLAim.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ public LLAim() {

@Override
public void initialize() {
SmartDashboard.putNumber("/limelight/ledMode", 3);
Robot.visionLL.limeLightLEDOn();
kP = SpectrumPreferences.getNumber("LL-AIM kP", kP)/100;
kI = SpectrumPreferences.getNumber("LL-AIM kI", kI)/100;
kD = SpectrumPreferences.getNumber("LL-AIM kD", kD)/100;
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/constants/AutonConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,10 @@
import edu.wpi.first.math.trajectory.TrapezoidProfile;

public final class AutonConstants {
public static final double pos1angle = 160;
public static final double pos2angle = 120;
public static final double pos3angle = 270;

public static final double kMaxSpeedMetersPerSecond = 3;
public static final double kMaxAccelerationMetersPerSecondSquared = 3;
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
Expand Down
16 changes: 10 additions & 6 deletions src/main/java/frc/robot/constants/ClimberConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration;
import com.ctre.phoenix.motorcontrol.StatorCurrentLimitConfiguration;
import com.ctre.phoenix.motorcontrol.can.TalonFX;
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration;
import com.ctre.phoenix.sensors.SensorInitializationStrategy;
Expand All @@ -13,8 +14,8 @@
public final class ClimberConstants{
public static final String name = "Climber";

public static final int fullExtend = 100000;
public static final int nextRungExtend = 6000;
public static final int fullExtend = 118000;
public static final int nextRungExtend = 98000;
public static final int fullRetract = -2000;

//Physical Constants
Expand Down Expand Up @@ -42,22 +43,25 @@ public final class ClimberConstants{
public static final NeutralMode kNeutralMode = NeutralMode.Brake;

/* Control Loop Constants */
public static final double kP = 0.0;
public static final double kP = 0.01;
public static final double kI = 0;
public static final double kD = 0;
public static final double kF = 0.05;
public static final double kIz = 150;
public static final double motionCruiseVelocity = 0;
public static final double motionAcceleration = 0;
public static final double motionCruiseVelocity = 10000;
public static final double motionAcceleration = 20000;

/* Current Limiting */
public static final int currentLimit = 40;
public static final int tirggerThresholdLimit = 45;
public static final int tirggerThresholdLimit = 40;
public static final double PeakCurrentDuration = 0.5;
public static final boolean EnableCurrentLimit = true;
public static final SupplyCurrentLimitConfiguration supplyLimit = new SupplyCurrentLimitConfiguration(
EnableCurrentLimit, currentLimit, tirggerThresholdLimit, PeakCurrentDuration);

/*public static final StatorCurrentLimitConfiguration statorLimit = new StatorCurrentLimitConfiguration(
EnableCurrentLimit, currentLimit, tirggerThresholdLimit, PeakCurrentDuration);*/

/* Voltage Compensation */
public static final double voltageCompSaturation = 12;

Expand Down
38 changes: 27 additions & 11 deletions src/main/java/frc/robot/subsystems/Climber.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,37 +8,53 @@
import frc.robot.constants.Constants.CanIDs;
import frc.robot.constants.Constants.SolenoidPorts;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;

public class Climber extends PositionSubsystem{
public class Climber extends PositionSubsystem {
public final WPI_TalonFX motorFollower;
public final SolenoidSubsystem pneumatic;

public Climber(){
public Climber() {
setName(ClimberConstants.name);
motorLeader = new WPI_TalonFX(CanIDs.kClimberMotorLeft, Constants.Canivorename);
ClimberConstants.setupFalconLeader(motorLeader);

motorFollower = new WPI_TalonFX(CanIDs.kClimberMotorRight, Constants.Canivorename);
ClimberConstants.setupFalconFollower(motorFollower, motorLeader);



resetEncoder();
motorLeader.configForwardSoftLimitThreshold(ClimberConstants.fullExtend);
motorLeader.configForwardSoftLimitEnable(false);

motorLeader.configReverseSoftLimitThreshold(ClimberConstants.fullRetract);
motorLeader.configReverseSoftLimitEnable(false);

pneumatic = new SolenoidSubsystem("Climber Solenoid", SolenoidPorts.kclimberUp);
setDefaultCommand(new RunCommand(() -> setManualOutput(Gamepads.getClimberJoystick()), this));

setDefaultCommand(defaultCommand());
}

public void follow(){
public Command defaultCommand(){
return new RunCommand(() -> setManualOutput(Gamepads.getClimberJoystick()), this);
}
public void follow() {
motorFollower.setNeutralMode(NeutralMode.Brake);
motorFollower.follow(motorLeader);
}
public void tiltUp(){

public void tiltUp() {
motorLeader.setNeutralMode(NeutralMode.Brake);
motorFollower.setNeutralMode(NeutralMode.Brake);
pneumatic.on();
}

public void tiltDown(){
pneumatic.off();
}
public void tiltDown() {
motorLeader.setNeutralMode(NeutralMode.Brake);
motorFollower.setNeutralMode(NeutralMode.Brake);
pneumatic.off();
}
}
Loading

0 comments on commit 6687ff1

Please sign in to comment.