Skip to content

Commit

Permalink
getting ready to test elevator!
Browse files Browse the repository at this point in the history
  • Loading branch information
sigalrmp committed Feb 1, 2025
1 parent 962e544 commit 25ef024
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 15 deletions.
14 changes: 6 additions & 8 deletions src/main/java/org/sciborgs1155/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,12 @@
import static edu.wpi.first.units.Units.Second;
import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.wpilibj2.command.button.RobotModeTriggers.*;
import static org.sciborgs1155.robot.Constants.*;
import static org.sciborgs1155.robot.Constants.DEADBAND;
import static org.sciborgs1155.robot.Constants.Field.*;
import static org.sciborgs1155.robot.Constants.PERIOD;
import static org.sciborgs1155.robot.drive.DriveConstants.*;

import com.ctre.phoenix6.SignalLogger;
import edu.wpi.first.wpilibj.DataLogManager;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
Expand All @@ -32,9 +32,7 @@
import org.sciborgs1155.lib.InputStream;
import org.sciborgs1155.lib.Test;
import org.sciborgs1155.robot.Ports.OI;
import org.sciborgs1155.robot.arm.Arm;
import org.sciborgs1155.robot.commands.Autos;
import org.sciborgs1155.robot.coroller.Coroller;
import org.sciborgs1155.robot.drive.Drive;
import org.sciborgs1155.robot.elevator.Elevator;
import org.sciborgs1155.robot.led.LEDStrip;
Expand All @@ -55,13 +53,11 @@ public class Robot extends CommandRobot implements Logged {
private final PowerDistribution pdh = new PowerDistribution();

// SUBSYSTEMS
private final Drive drive = Drive.create();
private final Vision vision = Vision.create();
private final Arm arm = Arm.create();
private final Coroller coroller = Coroller.create();
private final Drive drive = Drive.none();
private final Vision vision = new Vision();
private final LEDStrip led = new LEDStrip();
private final Elevator elevator = Elevator.create();
private final Scoral scoral = Scoral.create();
private final Scoral scoral = Scoral.none();

// COMMANDS
@Log.NT private final SendableChooser<Command> autos = Autos.configureAutos(drive);
Expand Down Expand Up @@ -159,6 +155,8 @@ private void configureBindings() {
.onTrue(Commands.runOnce(() -> speedMultiplier = Constants.SLOW_SPEED_MULTIPLIER))
.onFalse(Commands.runOnce(() -> speedMultiplier = Constants.FULL_SPEED_MULTIPLIER));

teleop().onTrue(Commands.runOnce(() -> SignalLogger.start()));
disabled().onTrue(Commands.runOnce(() -> SignalLogger.stop()));
// TODO: Add any additional bindings.

}
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/org/sciborgs1155/robot/elevator/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,11 +76,11 @@ public Elevator(ElevatorIO hardware) {
new SysIdRoutine.Mechanism(v -> hardware.setVoltage(v.in(Volts)), null, this));

SmartDashboard.putData(
"pivot quasistatic forward", sysIdRoutine.quasistatic(Direction.kForward));
"elevator quasistatic forward", sysIdRoutine.quasistatic(Direction.kForward));
SmartDashboard.putData(
"pivot quasistatic backward", sysIdRoutine.quasistatic(Direction.kReverse));
SmartDashboard.putData("pivot dynamic forward", sysIdRoutine.dynamic(Direction.kForward));
SmartDashboard.putData("pivot dynamic backward", sysIdRoutine.dynamic(Direction.kReverse));
"elevator quasistatic backward", sysIdRoutine.quasistatic(Direction.kReverse));
SmartDashboard.putData("elevator dynamic forward", sysIdRoutine.dynamic(Direction.kForward));
SmartDashboard.putData("elevator dynamic backward", sysIdRoutine.dynamic(Direction.kReverse));
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,9 @@ public class ElevatorConstants {
public static final double GEARING = 20 / 1;
public static final Distance SPROCKET_RADIUS = Inches.of(1);
public static final Distance SPROCKET_CIRCUMFRENCE = SPROCKET_RADIUS.times(2 * Math.PI);

// Input to Output; "values greater than one represent a reduction"
/** conversion factor in METERS PER ROTATION */
public static final double CONVERSION_FACTOR = GEARING / SPROCKET_CIRCUMFRENCE.in(Meters) / 2;

public static final Current CURRENT_LIMIT = Amps.of(50);
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/org/sciborgs1155/robot/scoral/Scoral.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ public class Scoral extends SubsystemBase implements Logged, AutoCloseable {
public final Trigger beambreakTrigger = new Trigger(() -> beambreak());

public static Scoral create() {
return new Scoral(Robot.isReal() ? realMotor() : Scoral.none());
return new Scoral(Robot.isReal() ? realMotor() : SimpleMotor.none());
}

private static SimpleMotor realMotor() {
Expand All @@ -37,8 +37,8 @@ private static SimpleMotor realMotor() {
return SimpleMotor.talon(new TalonFX(ROLLER), config);
}

public static SimpleMotor none() {
return SimpleMotor.none();
public static Scoral none() {
return new Scoral(SimpleMotor.none());
}

public Scoral(SimpleMotor hardware) {
Expand Down

0 comments on commit 25ef024

Please sign in to comment.