integrated indexer motor with manipulator

This commit is contained in:
Tylr-J42 2025-03-28 01:21:28 -04:00
parent 11512e140c
commit 9b7d2b45a4
4 changed files with 35 additions and 44 deletions

View File

@ -43,7 +43,7 @@ public class RobotContainer {
private Elevator elevator; private Elevator elevator;
//private ElevatorSysID elevator; //private ElevatorSysID elevator;
private Indexer indexer; //private Indexer indexer;
private Manipulator manipulator; private Manipulator manipulator;
@ -66,7 +66,7 @@ public class RobotContainer {
elevator = new Elevator(); elevator = new Elevator();
//elevator = new ElevatorSysID(); //elevator = new ElevatorSysID();
indexer = new Indexer(); //indexer = new Indexer();
manipulator = new Manipulator(); manipulator = new Manipulator();
@ -123,9 +123,9 @@ public class RobotContainer {
elevator.maintainPosition() elevator.maintainPosition()
); );
indexer.setDefaultCommand( //indexer.setDefaultCommand(
indexer.runIndexer(() -> 0) // indexer.runIndexer(() -> 0)
); //);
manipulatorPivot.setDefaultCommand( manipulatorPivot.setDefaultCommand(
@ -149,7 +149,7 @@ public class RobotContainer {
driver.leftTrigger().whileTrue( driver.leftTrigger().whileTrue(
manipulator.runUntilCollected(() -> 0.75) manipulator.runUntilCollected(() -> 0.75)
.alongWith(indexer.runIndexer(() -> .75)) //.alongWith(indexer.runIndexer(() -> .75))
.until(() -> manipulator.getCoralBeamBreak() == false) .until(() -> manipulator.getCoralBeamBreak() == false)
.andThen(manipulator.retractCommand(() -> .1)) .andThen(manipulator.retractCommand(() -> .1))
); );
@ -215,7 +215,9 @@ public class RobotContainer {
operator.back().onTrue(elevator.homeCommand()); operator.back().onTrue(elevator.homeCommand());
operator.start().toggleOnTrue(climberPivot.runPivot(() -> -operator.getRightY()*0.5).alongWith(climberRollers.runRoller(() -> operator.getLeftY()*0.5))); operator.start().toggleOnTrue(
climberPivot.runPivot(() -> -operator.getRightY()*0.5)
.alongWith(climberRollers.runRoller(() -> operator.getLeftY()*0.5)));
operator.a().onTrue( operator.a().onTrue(
safeMoveManipulator(ElevatorConstants.kCoralIntakePosition, ManipulatorPivotConstants.kStartingPosition) safeMoveManipulator(ElevatorConstants.kCoralIntakePosition, ManipulatorPivotConstants.kStartingPosition)
@ -223,18 +225,18 @@ public class RobotContainer {
operator.x().onTrue( operator.x().onTrue(
safeMoveManipulator(ElevatorConstants.kL2AlgaePosition, ManipulatorPivotConstants.kL2AlgaePosition) safeMoveManipulator(ElevatorConstants.kL2AlgaePosition, ManipulatorPivotConstants.kL2AlgaePosition)
.alongWith(manipulator.runManipulator(() -> 0.85, false)) .alongWith(manipulator.runManipulator(() -> 0.5, false))
.until(() -> driver.a().getAsBoolean()) .until(() -> driver.a().getAsBoolean())
); );
operator.b().onTrue( operator.b().onTrue(
safeMoveManipulator(ElevatorConstants.kL3AlgaePosition, ManipulatorPivotConstants.kL3AlgaePosition) safeMoveManipulator(ElevatorConstants.kL3AlgaePosition, ManipulatorPivotConstants.kL3AlgaePosition)
.alongWith(manipulator.runManipulator(() -> 0.85, false)) .alongWith(manipulator.runManipulator(() -> 0.5, false))
.until(() -> driver.a().getAsBoolean()) .until(() -> driver.a().getAsBoolean())
); );
operator.y().onTrue(moveWithAlgae(ElevatorConstants.kProcessorPosition, ManipulatorPivotConstants.kProcessorPosition) operator.y().onTrue(moveWithAlgae(ElevatorConstants.kProcessorPosition, ManipulatorPivotConstants.kProcessorPosition)
.alongWith(manipulator.runManipulator(() -> 0.85, false)) .alongWith(manipulator.runManipulator(() -> 0.5, false))
.until(() -> driver.a().getAsBoolean()) .until(() -> driver.a().getAsBoolean())
); );

View File

@ -9,7 +9,7 @@ public class IndexerConstants {
public static final SparkMaxConfig motorConfig = new SparkMaxConfig(); public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
static{ static{
motorConfig.smartCurrentLimit(40) motorConfig.smartCurrentLimit(30)
.idleMode(IdleMode.kCoast); .idleMode(IdleMode.kBrake);
}; };
} }

View File

@ -1,32 +0,0 @@
package frc.robot.subsystems;
import java.util.function.DoubleSupplier;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.IndexerConstants;
public class Indexer extends SubsystemBase {
private SparkMax indexerMotor;
public Indexer() {
indexerMotor = new SparkMax(IndexerConstants.kIndexerMotorID, MotorType.kBrushless);
indexerMotor.configure(
IndexerConstants.motorConfig,
ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters
);
}
public Command runIndexer(DoubleSupplier speed) {
return run(() -> {
indexerMotor.set(speed.getAsDouble());
});
}
}

View File

@ -10,11 +10,14 @@ import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.IndexerConstants;
import frc.robot.constants.ManipulatorConstants; import frc.robot.constants.ManipulatorConstants;
public class Manipulator extends SubsystemBase { public class Manipulator extends SubsystemBase {
private SparkMax manipulatorMotor; private SparkMax manipulatorMotor;
private SparkMax indexerMotor;
private DigitalInput coralBeamBreak; private DigitalInput coralBeamBreak;
public Manipulator() { public Manipulator() {
@ -29,6 +32,17 @@ public class Manipulator extends SubsystemBase {
PersistMode.kPersistParameters PersistMode.kPersistParameters
); );
indexerMotor = new SparkMax(
IndexerConstants.kIndexerMotorID,
MotorType.kBrushless
);
indexerMotor.configure(
IndexerConstants.motorConfig,
ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters
);
coralBeamBreak = new DigitalInput(ManipulatorConstants.kCoralBeamBreakID); coralBeamBreak = new DigitalInput(ManipulatorConstants.kCoralBeamBreakID);
} }
@ -56,6 +70,8 @@ public class Manipulator extends SubsystemBase {
manipulatorMotor.set( manipulatorMotor.set(
coral ? speed.getAsDouble() : speed.getAsDouble() * -1 coral ? speed.getAsDouble() : speed.getAsDouble() * -1
); );
indexerMotor.set(0);
}); });
} }
@ -71,6 +87,9 @@ public class Manipulator extends SubsystemBase {
manipulatorMotor.set( manipulatorMotor.set(
speed.getAsDouble() speed.getAsDouble()
); );
indexerMotor.set(1);
}).unless(() -> !coralBeamBreak.get()) }).unless(() -> !coralBeamBreak.get())
.until(() -> !coralBeamBreak.get()); .until(() -> !coralBeamBreak.get());
/* /*
@ -90,6 +109,8 @@ public class Manipulator extends SubsystemBase {
public Command retractCommand(DoubleSupplier retractSpeed){ public Command retractCommand(DoubleSupplier retractSpeed){
return run(() -> { return run(() -> {
manipulatorMotor.set(-retractSpeed.getAsDouble()); manipulatorMotor.set(-retractSpeed.getAsDouble());
indexerMotor.set(0);
} }
).until(() -> coralBeamBreak.get()); ).until(() -> coralBeamBreak.get());
} }