Skip to content
Merged
Show file tree
Hide file tree
Changes from 3 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
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "mako-robot-code-2025-2";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 252;
public static final String GIT_SHA = "c3a03ac85f9fc8db8fa8225419aef8e3f57fe815";
public static final String GIT_DATE = "2025-09-26 11:36:41 EDT";
public static final int GIT_REVISION = 254;
public static final String GIT_SHA = "7d66fde4bea895cd6c927ae3cd0ac07aeab8335d";
public static final String GIT_DATE = "2025-09-29 14:30:00 EDT";
public static final String GIT_BRANCH = "elevator-motor-fix";
public static final String BUILD_DATE = "2025-09-26 11:37:50 EDT";
public static final long BUILD_UNIX_TIME = 1758901070990L;
public static final int DIRTY = 0;
public static final String BUILD_DATE = "2025-10-01 17:42:01 EDT";
public static final long BUILD_UNIX_TIME = 1759354921292L;
public static final int DIRTY = 1;

private BuildConstants() {}
}
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@

/** Add your docs here. */
public class ElevatorConstants {
public static final int ELEVATOR_LEADER_MOTOR_ID = 0;
public static final int ELEVATOR_FOLLOWER_MOTOR_ID = 62;
public static final int ELEVATOR_LEADER_MOTOR_ID = 0-9; // 0, changed for testing just follower
public static final int ELEVATOR_FOLLOWER_MOTOR_ID = 34;

public static final double ELEVATOR_P = 10;
public static final double ELEVATOR_I = 0;
Expand All @@ -20,19 +20,20 @@ public class ElevatorConstants {
public static final double ELEVATOR_G = -0.35;

public static final double DRUM_RADIUS = 1;
public static final double ELEVATOR_GEAR_RATIO = 4.8; // 29
public static final double ELEVATOR_GEAR_RATIO = 4.8; // 4.8
public static final double ELEVATOR_CARRIAGE_MASS = 10;
public static final double MIN_HEIGHT = 0;
public static final double MAX_HEIGHT = 3;
public static final double INCLINE_ANGLE_RADIANS = Units.degreesToRadians(8);
public static final boolean SIMULATE_GRAVITY = true;

public static final double STATOR_CURRENT_LIMIT = 100; // 100
public static final double STATOR_CURRENT_LIMIT = 200; // 100
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why was this doubled

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When limits were enabled i forgot to turn them off and i wasnt sure how high the threshold was gonna be so i was gonna tune it and i wanted there to be a negligible existing limit

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok... but why is it doubled. Like what's the point of a threshold if you're going to make the existing limit negligible? At that point the threshold becomes the actual limit, but with a delay.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Also, you doubled acceleration
image
Why?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ill revert the limit 😔 i HALVED the acceleration cuz the elevator was too fast

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i see ur right

but how was the elevator too fast? ...Ig u slowed it down for testing which is chill

public static final double SUPPLY_CURRENT_LIMIT = 0;
public static final double STATOR_CURRENT_THRESHOLD = 10000000; // will tune later
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You should make the constant name a little more descriptive. Is this for the hard stop? Or just stator current in general?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Its for the hard stop lol ill add comments and adjust names tmr

public static final boolean STATOR_CURRENT_LIMIT_ENABLE = true;
public static final boolean SUPPLY_CURRENT_LIMIT_ENABLE = false;

public static final double MOTION_MAGIC_MAX_ACCELERATION = 80; // 160
public static final double MOTION_MAGIC_MAX_ACCELERATION = 160; // 160
public static final double MOTION_MAGIC_CRUISE_VELOCITY = 100; // 100

public static final double ELEVATOR_ERROR_TOLERANCE = 0.08;
Expand All @@ -46,10 +47,10 @@ public class ElevatorConstants {
// Elevator setpoints
public enum ElevatorSetpoints {
L1(-2.50),
L2(-2.8 + .00004829),
L2(-2.8 + .0000000000000000000004829), // Easter egg lol
L3(-4.517),
L4(-7.55), // -9.2
FEEDER(-0.3);
L4(-7.55),
FEEDER(-0.2);

private final double position;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import com.ctre.phoenix6.controls.Follower;
import com.ctre.phoenix6.controls.MotionMagicTorqueCurrentFOC;
import com.ctre.phoenix6.controls.MotionMagicVoltage;
import com.ctre.phoenix6.controls.NeutralOut;
import com.ctre.phoenix6.controls.TorqueCurrentFOC;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.GravityTypeValue;
Expand All @@ -33,7 +34,6 @@ public class PhysicalElevator implements ElevatorInterface {

private final MotionMagicTorqueCurrentFOC mmTorqueRequest = new MotionMagicTorqueCurrentFOC(0.0);
private final TorqueCurrentFOC currentOut = new TorqueCurrentFOC(0.0);

private final StatusSignal<Angle> leaderPosition;
private final StatusSignal<Angle> followerPosition;
private final StatusSignal<Voltage> leaderAppliedVoltage;
Expand Down Expand Up @@ -87,7 +87,6 @@ public PhysicalElevator() {

// Use Follower control
followerMotor.setControl(follower);
elevatorConfig.Feedback.SensorToMechanismRatio = 19.2;
followerMotor.getConfigurator().apply(elevatorConfig);

leaderPosition = leaderMotor.getPosition();
Expand Down Expand Up @@ -123,8 +122,8 @@ public PhysicalElevator() {
leaderVelocity,
followerTemp,
leaderTemp);
leaderMotor.optimizeBusUtilization();
followerMotor.optimizeBusUtilization();
leaderMotor.optimizeBusUtilization();
}

@Override
Expand All @@ -145,7 +144,7 @@ public void updateInputs(ElevatorInputs inputs) {
inputs.leaderMotorPosition = leaderPosition.getValueAsDouble();
inputs.leaderMotorVoltage = leaderAppliedVoltage.getValueAsDouble();
inputs.leaderDutyCycle = leaderDutyCycle.getValueAsDouble();
inputs.followerMotorPosition = followerPosition.getValueAsDouble() / 4.0;
inputs.followerMotorPosition = followerPosition.getValueAsDouble();
inputs.followerMotorVoltage = followerAppliedVoltage.getValueAsDouble();
inputs.followerDutyCycle = followerDutyCycle.getValueAsDouble();
inputs.desiredPosition = elevatorReference.getValueAsDouble();
Expand All @@ -167,13 +166,12 @@ public double getElevatorPosition() {
@Override
public void setElevatorPosition(double position) {
leaderMotor.setControl(mmPositionRequest.withPosition(position));
followerMotor.setControl(mmPositionRequest.withPosition(-position));
}

@Override
public void hardStop() {
if (leaderPosition.getValueAsDouble() == 0) {
leaderMotor.setControl(mmPositionRequest.withPosition(-0.1));
if (leaderStatorCurrent.getValueAsDouble() > ElevatorConstants.STATOR_CURRENT_THRESHOLD) {
leaderMotor.setControl(mmPositionRequest.withPosition(0.001));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think setting the control to move the elevator up a bit is a little dangerous. I think you may want to consider resetting the position to the bottom of the elevator when it reaches that point. So it should only work when the elevator is moving down and the stator current is continuing to be high. This is because if the elevator is all the way up or gets caught on something, the stator current will also increase.

So the safest way to do this would probably be to reset to the bottom position when the stator current has been increased and it's moving downward.

You should also have an override to this on a button.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Also comment this cuz people are gonna read ts.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

How do i say if its going downward? Like if its approaching 0? And how do i word/structure that? Also ik abt the override as far as the subsystem interfacing but r u saying u want it as a physical button as well?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes you need a physical button to override the hardstop. It's not override in the interface sense. It's like actually telling the robot, do NOT use the hardstop when this button is pressed. You can also make it toggleable, so one press turns it off, the next turns it on.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

To tell if it's going downward just check if the position is decreasing over a certain interval. Off the top of my head, I think you could create like a list or smthn of your elevator positions, store them up, kind of like how we do for vision and stuff, and keep a certain amount of positions for a specific window of time. If the trend is decreasing then it's going downward.

Lowkey that's hella complicated so like ask chat. it's also 1:30 AM..

Copy link
Member

@Ishan1522 Ishan1522 Oct 15, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here's what 6328 does https://github.com/Mechanical-Advantage/RobotCode2025Public/blob/main/src/main/java/org/littletonrobotics/frc2025/subsystems/superstructure/elevator/Elevator.java#L353 It's simpler than what I said and their code def works. Check it out. I'll look through other example later maybe perchance

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Kk

}
}

Expand Down
Loading