This repository has been archived by the owner on May 19, 2024. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
refactor(config): Rename constants to configs.
- Loading branch information
1 parent
624f68d
commit b711e42
Showing
11 changed files
with
436 additions
and
200 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file was deleted.
Oops, something went wrong.
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,76 @@ | ||
package frc.lib.config; | ||
|
||
import edu.wpi.first.math.geometry.Rotation2d; | ||
|
||
/** Absolute encoder config. */ | ||
public class AbsoluteEncoderConfig { | ||
|
||
/** Interpret counterclockwise rotation on the encoder as having positive velocity. */ | ||
private boolean ccwPositive = true; | ||
|
||
/** Ratio between the absolute encoder and the mechanism. */ | ||
private double sensorToMechanismRatio = 1.0; | ||
|
||
/** Offset between absolute encoder reading and mechanism position. */ | ||
private Rotation2d offset = new Rotation2d(); | ||
|
||
/** | ||
* Modifies this absolute encoder config's counterclockwise positive. | ||
* | ||
* @param ccwPositive the counterclockwise positive. | ||
* @return this absolute encoder config. | ||
*/ | ||
public AbsoluteEncoderConfig withCCWPositive(boolean ccwPositive) { | ||
this.ccwPositive = ccwPositive; | ||
return this; | ||
} | ||
|
||
/** | ||
* Modifies this absolute encoder config's sensor to mechanism ratio. | ||
* | ||
* @param sensorToMechanismRatio the sensor to mechanism ratio. | ||
* @return this absolute encoder config. | ||
*/ | ||
public AbsoluteEncoderConfig withSensorToMechanismRatio(double sensorToMechanismRatio) { | ||
this.sensorToMechanismRatio = sensorToMechanismRatio; | ||
return this; | ||
} | ||
|
||
/** | ||
* Modifies this absolute encoder config's offset. | ||
* | ||
* @param offset the offset. | ||
* @return this absolute encoder config. | ||
*/ | ||
public AbsoluteEncoderConfig withOffset(Rotation2d offset) { | ||
this.offset = offset; | ||
return this; | ||
} | ||
|
||
/** | ||
* Returns true if the absolute encoder is counterclockwise positive. | ||
* | ||
* @return true if the absolute encoder is counterclockwise positive. | ||
*/ | ||
public boolean ccwPositive() { | ||
return ccwPositive; | ||
} | ||
|
||
/** | ||
* Returns the absolute encoder sensor to mechanism ratio. | ||
* | ||
* @return the absolute encoder sensor to mechanism ratio. | ||
*/ | ||
public double sensorToMechanismRatio() { | ||
return sensorToMechanismRatio; | ||
} | ||
|
||
/** | ||
* Returns the absolute encoder offset. | ||
* | ||
* @return the absolute encoder offset. | ||
*/ | ||
public Rotation2d offset() { | ||
return offset; | ||
} | ||
} |
Oops, something went wrong.