Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions notes/canIDs.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ Gyro (Pigeon2) | 0
CANivore | 0


# Comp (total devices: 25 + canivore)
# Comp (total devices: 26 + canivore)
Device | CAN ID | Code
------ | ------ | ------
Front Left Drive | 0 | X60-044
Expand All @@ -40,13 +40,14 @@ Back Right Drive | 6 | X60-042
Back Right Steer | 7 | X44-015
Intake Rollers | 8 | X44-012
Spindexer Agitator | 9 | X60-046
Kicker Roller | 10 | X60-051
1st Kicker Roller | 10 | X44-004
Shooter Hood | 11 | X44-008
Shooter Flywheel Leader (Left) | 12 | X60-048
Shooter Flywheel Follower (Right) | 13 | X60-050
intake Pivot | 14 | X44-017
Turret Pivot | 15 | X44-001
Climber | 16 | X60-049
2nd Kicker Roller | 17 | X60-051
Front Left Encoder (CANcoder) | 0
Front Right Encoder (CANcoder) | 1
Back Left Encoder (CANcoder) | 2
Expand Down
25 changes: 21 additions & 4 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,8 @@ public enum RobotEdition {

private Intake intake = null;
private Shooter shooter = null;

private Indexer indexer = null;
private final CANdleSubsystem candle =
new CANdleSubsystem(new CANdleIOReal(0, CANdleSubsystem.getCandleConfig(), canivore));

Expand Down Expand Up @@ -258,7 +260,6 @@ public Robot() {
// accounted for, it wouldn't be able to pass anything to the superstructure below and it would
// break
// granted this would never actually happen but
Indexer indexer = null;

// this looks at the ROBOT_EDITION variable and decides which version of each subsystem to
// create based on that
Expand Down Expand Up @@ -348,17 +349,30 @@ public Robot() {
MotorType.KrakenX44,
canivore),
(ROBOT_MODE == RobotMode.REAL)
? new RollerIO(10, SpindexerSubsystem.getKickerConfig(), canivore)
? new RollerIO(10, SpindexerSubsystem.getX44KickerConfig(), canivore)
: new RollerIOSim(
10,
SpindexerSubsystem.getKickerConfig(),
SpindexerSubsystem.getX44KickerConfig(),
new DCMotorSim(
LinearSystemId.createDCMotorSystem(
DCMotor.getKrakenX44Foc(1),
0.00001,
SpindexerSubsystem.KICKER_GEAR_RATIO),
SpindexerSubsystem.X44_KICKER_GEAR_RATIO),
DCMotor.getKrakenX44Foc(1)),
MotorType.KrakenX44,
canivore),
(ROBOT_MODE == RobotMode.REAL)
? new RollerIO(17, SpindexerSubsystem.getX60KickerConfig(), canivore)
: new RollerIOSim(
17,
SpindexerSubsystem.getX60KickerConfig(),
new DCMotorSim(
LinearSystemId.createDCMotorSystem(
DCMotor.getKrakenX60Foc(1),
0.00001,
SpindexerSubsystem.X60_KICKER_GEAR_RATIO),
DCMotor.getKrakenX60Foc(1)),
MotorType.KrakenX60,
canivore));
intake =
(ROBOT_MODE == RobotMode.REAL)
Expand Down Expand Up @@ -811,6 +825,9 @@ private void addAutos() {

autoChooser.addOption("Flywheel Sysid", shooter.runFlywheelSysid());
autoChooser.addOption("Hood Sysid", shooter.runHoodSysid());
autoChooser.addOption("X60 Sysid", indexer.runX60Sysid());

autoChooser.addOption("X44 Sysid", indexer.runX44Sysid());

autoChooser.addOption("Right Neutral Outpost Score", autos.getRightNeutralOutpostScore());

Expand Down
56 changes: 51 additions & 5 deletions src/main/java/frc/robot/Superstructure.java
Original file line number Diff line number Diff line change
Expand Up @@ -500,7 +500,15 @@ private void addCommands() {
bindCommands(
SuperState.FEED,
intake.agitate(),
indexer.kick(),
indexer.kick(
() ->
NewAutoAim.getParametersMechA(
swerve.getPose(),
swerve.getVelocityRobotRelative(),
FeedTargets.getFeedTarget(feedTarget).getTranslation(),
AutoAim.FEED_SHOT_TREE)
.shotData()
.flywheelVelocityRotPerSec()),
shooter.feed(
() ->
NewAutoAim.getParametersMechA(
Expand Down Expand Up @@ -530,7 +538,15 @@ private void addCommands() {
bindCommands(
SuperState.FEED_FLOW,
intake.intake(),
indexer.kick(),
indexer.kick(
() ->
NewAutoAim.getParametersMechA(
swerve.getPose(),
swerve.getVelocityRobotRelative(),
FeedTargets.getFeedTarget(feedTarget).getTranslation(),
AutoAim.FEED_SHOT_TREE)
.shotData()
.flywheelVelocityRotPerSec()),
shooter.feed(
() ->
NewAutoAim.getParametersMechA(
Expand Down Expand Up @@ -561,7 +577,17 @@ private void addCommands() {
SuperState.SCORE,
intake.agitate(),
// intake.restExtended(),
indexer.kick(),
indexer.kick(
() ->
NewAutoAim.getParametersMechA(
swerve.getPose(),
swerve.getVelocityRobotRelative(),
FieldUtils.getCurrentHubTranslation(),
Robot.ROBOT_EDITION == RobotEdition.ALPHA
? AutoAim.ALPHA_HUB_SHOT_TREE
: AutoAim.COMP_HUB_SHOT_TREE)
.shotData()
.flywheelVelocityRotPerSec()),
shooter.score(
() ->
NewAutoAim.getParametersMechA(
Expand Down Expand Up @@ -591,7 +617,17 @@ private void addCommands() {
bindCommands(
SuperState.SCORE_FLOW,
intake.intake(),
indexer.kick(),
indexer.kick(
() ->
NewAutoAim.getParametersMechA(
swerve.getPose(),
swerve.getVelocityRobotRelative(),
FieldUtils.getCurrentHubTranslation(),
Robot.ROBOT_EDITION == RobotEdition.ALPHA
? AutoAim.ALPHA_HUB_SHOT_TREE
: AutoAim.COMP_HUB_SHOT_TREE)
.shotData()
.flywheelVelocityRotPerSec()),
shooter.score(
() ->
NewAutoAim.getParametersMechA(
Expand Down Expand Up @@ -654,7 +690,17 @@ private void addCommands() {
bindCommands(
SuperState.SCORE_PRE_CLIMB,
intake.restRetracted(),
indexer.kick(),
indexer.kick(
() ->
NewAutoAim.getParametersMechA(
swerve.getPose(),
swerve.getVelocityRobotRelative(),
FieldUtils.getCurrentHubTranslation(),
Robot.ROBOT_EDITION == RobotEdition.ALPHA
? AutoAim.ALPHA_HUB_SHOT_TREE
: AutoAim.COMP_HUB_SHOT_TREE)
.shotData()
.flywheelVelocityRotPerSec()),
shooter.score(
() ->
NewAutoAim.getParametersMechA(
Expand Down
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/components/rollers/RollerIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@ public static class RollerIOInputs {
private final StatusSignal<Temperature> temperatureCelsius;
private final StatusSignal<Angle> positionRotations;

private double setpoint;

private final VoltageOut voltageOut = new VoltageOut(0.0).withEnableFOC(true);
private final VelocityVoltage velocityVoltage =
new VelocityVoltage(0.0).withEnableFOC(true).withSlot(0);
Expand Down Expand Up @@ -95,6 +97,11 @@ public void setRollerVoltage(double volts) {
}

public void setRollerVelocity(double velocityRPS) {
setpoint = velocityRPS;
motor.setControl(velocityVoltage.withVelocity(velocityRPS));
}

public double getVelocitySetpoint() {
return setpoint;
}
}
11 changes: 10 additions & 1 deletion src/main/java/frc/robot/subsystems/indexer/Indexer.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.function.DoubleSupplier;

/** Add your docs here. */
public interface Indexer extends Subsystem {
Expand All @@ -18,12 +19,20 @@ public interface Indexer extends Subsystem {
public Command spit();

/** Run both indexer and kicker towards the shooter */
public Command kick();
public Command kick(DoubleSupplier flywheelRPS);

/** Not running (set spinner to 0 but idle kicker) */
public Command rest();

public default Command stop() {
return Commands.none();
}

public default Command runX60Sysid() {
return Commands.none();
}

public default Command runX44Sysid() {
return Commands.none();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import frc.robot.components.canrange.CANrangeIOReal;
import frc.robot.components.rollers.RollerIO;
import frc.robot.components.rollers.RollerIOInputsAutoLogged;
import java.util.function.DoubleSupplier;
import org.littletonrobotics.junction.Logger;

/** Lindexer = Linear Indexer. !! ALPHA !! */
Expand Down Expand Up @@ -61,7 +62,7 @@ public Command index() {
}

@Override
public Command kick() {
public Command kick(DoubleSupplier flywheelRPS) {
return this.run(
() -> {
// if (shooterAtSetpoint.getAsBoolean()) {
Expand Down
Loading
Loading