Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Add] poke setpoints [Fix] climber signal refresh #77

Merged
merged 3 commits into from
Feb 20, 2025
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 src/main/java/frc/robot/RobotConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -404,6 +404,7 @@ public static class ElevatorConstants {
public static final double ELEVATOR_SPOOL_DIAMETER = 0.04 + 0.003; //0.04m for spool diameter, 0.003 for rope diameter
public static final double ELEVATOR_GEAR_RATIO = 3.0;
public static final double ELEVATOR_DANGER_ZONE = 0.4180619200456253;
public static final double ELEVATOR_DEFAULT_POSITION_WHEN_DISABLED = 0.46;

public static final TunableNumber motionAcceleration = new TunableNumber("Elevator/MotionAcceleration",
200);
Expand All @@ -426,9 +427,9 @@ public static class ElevatorConstants {
public static final TunableNumber L4_EXTENSION_METERS = new TunableNumber("ELEVATOR SETPOINTS/L4",
1.57);
public static final TunableNumber P1_EXTENSION_METERS = new TunableNumber("ELEVATOR SETPOINTS/P1",
0.79);
0.50);
public static final TunableNumber P2_EXTENSION_METERS = new TunableNumber("ELEVATOR SETPOINTS/P2",
1.29);
0.80);
public static final TunableNumber FUNNEL_INTAKE_EXTENSION_METERS = new TunableNumber("ELEVATOR SETPOINTS/FunnnelIntake",
0.35);
public static final TunableNumber ELEVATOR_ZEROING_CURRENT = new TunableNumber("Elevator zeroing current",
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/subsystems/climber/ClimberIOReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,15 @@ public ClimberIOReal() {
motionMagicConfigs.MotionMagicJerk = ClimberConstants.CLIMBER_JERK.get();
config.withMotionMagic(motionMagicConfigs);

BaseStatusSignal.setUpdateFrequencyForAll(
50.0,
velocityRotPerSec,
tempCelsius,
appliedVolts,
supplyCurrentAmps,
statorCurrentAmps,
currentPositionRot);

motor.getConfigurator().apply(config);
motor.optimizeBusUtilization();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
import frc.robot.utils.TunableNumber;
import org.littletonrobotics.junction.Logger;

//TODO: change motion logic and reset command afterwards

public class ClimberSubsystem extends SubsystemBase {
private final ClimberIO io;
private final ClimberIOInputsAutoLogged inputs = new ClimberIOInputsAutoLogged();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ public ElevatorIOReal() {
currentLimitsConfigs.StatorCurrentLimit = 80.0;
currentLimitsConfigs.SupplyCurrentLimit = 30.0;

leader.setPosition(heightToTalonPos(0.4));
follower.setPosition(heightToTalonPos(0.4));
leader.setPosition(heightToTalonPos(ELEVATOR_DEFAULT_POSITION_WHEN_DISABLED));
follower.setPosition(heightToTalonPos(ELEVATOR_DEFAULT_POSITION_WHEN_DISABLED));

MotorOutputConfigs leaderMotorConfigs = new MotorOutputConfigs();
leaderMotorConfigs.NeutralMode = NeutralModeValue.Brake;
Expand Down
32 changes: 12 additions & 20 deletions src/main/java/frc/robot/utils/DestinationSupplier.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,27 +48,19 @@ public void updateChassisSetpoint(chassisSetpoint setpoint) {
public double getElevatorSetpoint(boolean useCoral) {
this.useCoral = useCoral;
if (useCoral) {
switch (currentElevSetpointCoral) {
case L1:
return RobotConstants.ElevatorConstants.L1_EXTENSION_METERS.get();
case L2:
return RobotConstants.ElevatorConstants.L2_EXTENSION_METERS.get();
case L3:
return RobotConstants.ElevatorConstants.L3_EXTENSION_METERS.get();
case L4:
return RobotConstants.ElevatorConstants.L4_EXTENSION_METERS.get();
default:
return RobotConstants.ElevatorConstants.L2_EXTENSION_METERS.get();
}
return switch (currentElevSetpointCoral) {
case L1 -> RobotConstants.ElevatorConstants.L1_EXTENSION_METERS.get();
case L2 -> RobotConstants.ElevatorConstants.L2_EXTENSION_METERS.get();
case L3 -> RobotConstants.ElevatorConstants.L3_EXTENSION_METERS.get();
case L4 -> RobotConstants.ElevatorConstants.L4_EXTENSION_METERS.get();
default -> RobotConstants.ElevatorConstants.L2_EXTENSION_METERS.get();
};
}else{
switch (currentElevSetpointPoke) {
case P1:
return RobotConstants.ElevatorConstants.P1_EXTENSION_METERS.get();
case P2:
return RobotConstants.ElevatorConstants.P2_EXTENSION_METERS.get();
default:
return RobotConstants.ElevatorConstants.P1_EXTENSION_METERS.get();
}
return switch (currentElevSetpointPoke) {
case P1 -> RobotConstants.ElevatorConstants.P1_EXTENSION_METERS.get();
case P2 -> RobotConstants.ElevatorConstants.P2_EXTENSION_METERS.get();
default -> RobotConstants.ElevatorConstants.P1_EXTENSION_METERS.get();
};
}
}

Expand Down