Skip to content

Commit

Permalink
small comment clean up
Browse files Browse the repository at this point in the history
  • Loading branch information
axiaoy committed Feb 4, 2025
1 parent f3319a5 commit 3c32204
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 30 deletions.
18 changes: 4 additions & 14 deletions src/main/java/tagalong/subsystems/micro/PivotFused.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,11 +55,8 @@ public void followLastProfile() {

TrapezoidProfile.State nextState =
_trapProfile.calculate(TagalongConfiguration.LOOP_PERIOD_S, _curState, _goalState);
// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot, convert to motor units
_primaryMotor.setControl(
_requestedPositionVoltage
.withPosition(nextState.position)
// FeedForward must know the pivot rotation and other arguments in radians
_requestedPositionVoltage.withPosition(nextState.position)
.withFeedForward(
_pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(nextState.velocity))
)
Expand All @@ -79,7 +76,6 @@ public double getFFPositionRad() {
return 0.0;
}

// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
return Units.rotationsToRadians(_pivotCancoder.getPosition().getValueAsDouble())
+ _ffCenterOfMassOffsetRad;
}
Expand All @@ -91,14 +87,9 @@ public void setPivotVelocity(double rps, boolean withFF) {
}
setFollowProfile(false);

_primaryMotor.setControl(
_requestedVelocityVoltage
// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
.withVelocity(rps)
.withFeedForward(
withFF ? _pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(rps)) : 0.0
)
);
_primaryMotor.setControl(_requestedVelocityVoltage.withVelocity(rps).withFeedForward(
withFF ? _pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(rps)) : 0.0
));
}

@Override
Expand Down Expand Up @@ -173,7 +164,6 @@ public void simulationPeriodic() {
_pivotSim.setInputVoltage(_primaryMotor.get() * RobotController.getBatteryVoltage());
_pivotSim.update(TagalongConfiguration.LOOP_PERIOD_S);

// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
double prevSimVelo = _simVeloRPS;
_simVeloRPS = Units.radiansToRotations(_pivotSim.getVelocityRadPerSec());
_simRotations += Units.radiansToRotations(_pivotSim.getAngleRads());
Expand Down
11 changes: 2 additions & 9 deletions src/main/java/tagalong/subsystems/micro/PivotNoCancoder.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,8 @@ public void followLastProfile() {

TrapezoidProfile.State nextState =
_trapProfile.calculate(TagalongConfiguration.LOOP_PERIOD_S, _curState, _goalState);
// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot, convert to motor units
_primaryMotor.setControl(
_requestedPositionVoltage
.withPosition(pivotRotToMotor(nextState.position))
// FeedForward must know the pivot rotation and other arguments in radians
_requestedPositionVoltage.withPosition(pivotRotToMotor(nextState.position))
.withFeedForward(
_pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(nextState.velocity))
)
Expand All @@ -64,7 +61,6 @@ public double getFFPositionRad() {
return 0.0;
}

// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
return Units.rotationsToRadians(getPivotPosition()) + _ffCenterOfMassOffsetRad;
}

Expand All @@ -76,9 +72,7 @@ public void setPivotVelocity(double rps, boolean withFF) {
setFollowProfile(false);

_primaryMotor.setControl(
_requestedVelocityVoltage
// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
.withVelocity(pivotRotToMotor(rps))
_requestedVelocityVoltage.withVelocity(pivotRotToMotor(rps))
.withFeedForward(
withFF ? _pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(rps)) : 0.0
)
Expand Down Expand Up @@ -127,7 +121,6 @@ public void simulationPeriodic() {
_pivotSim.setInputVoltage(_primaryMotor.get() * RobotController.getBatteryVoltage());
_pivotSim.update(TagalongConfiguration.LOOP_PERIOD_S);

// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
double prevSimVelo = _simVeloRPS;
_simVeloRPS = Units.radiansToRotations(_pivotSim.getVelocityRadPerSec());
_simRotations += Units.radiansToRotations(_pivotSim.getAngleRads());
Expand Down
9 changes: 2 additions & 7 deletions src/main/java/tagalong/subsystems/micro/PivotUnfused.java
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,8 @@ public void followLastProfile() {

TrapezoidProfile.State nextState =
_trapProfile.calculate(TagalongConfiguration.LOOP_PERIOD_S, _curState, _goalState);
// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot, convert to motor units
_primaryMotor.setControl(
_requestedPositionVoltage
.withPosition(pivotRotToMotor(nextState.position))
// FeedForward must know the pivot rotation and other arguments in radians
_requestedPositionVoltage.withPosition(pivotRotToMotor(nextState.position))
.withFeedForward(
_pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(nextState.velocity))
)
Expand Down Expand Up @@ -97,9 +94,7 @@ public void setPivotVelocity(double rps, boolean withFF) {
setFollowProfile(false);

_primaryMotor.setControl(
_requestedVelocityVoltage
// FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
.withVelocity(pivotRotToMotor(rps))
_requestedVelocityVoltage.withVelocity(pivotRotToMotor(rps))
.withFeedForward(
withFF ? _pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(rps)) : 0.0
)
Expand Down

0 comments on commit 3c32204

Please sign in to comment.