Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
refactor(config): Rename constants to configs.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 25, 2024
1 parent 624f68d commit b711e42
Show file tree
Hide file tree
Showing 11 changed files with 436 additions and 200 deletions.
11 changes: 7 additions & 4 deletions src/main/java/frc/lib/ControllerConstants.java
Original file line number Diff line number Diff line change
@@ -1,13 +1,16 @@
package frc.lib;

import frc.lib.config.FeedbackControllerConfig;
import frc.lib.config.FeedforwardControllerConfig;

/** Controller constants. */
public class ControllerConstants {

/** Feedforward controller constants. */
public FeedforwardControllerConstants feedforward = new FeedforwardControllerConstants();
public FeedforwardControllerConfig feedforward = new FeedforwardControllerConfig();

/** Feedback controller constants. */
public FeedbackControllerConstants feedback = new FeedbackControllerConstants();
public FeedbackControllerConfig feedback = new FeedbackControllerConfig();

/**
* Modifies these controller constants to use the feedforward controller constants.
Expand All @@ -16,7 +19,7 @@ public class ControllerConstants {
* @return these controller constants.
*/
public ControllerConstants withFeedforward(
FeedforwardControllerConstants feedforwardControllerConstants) {
FeedforwardControllerConfig feedforwardControllerConstants) {
this.feedforward = feedforwardControllerConstants;
return this;
}
Expand All @@ -27,7 +30,7 @@ public ControllerConstants withFeedforward(
* @param feedbackControllerConstants the feedback controller constants to use.
* @return these controller constants.
*/
public ControllerConstants withFeedback(FeedbackControllerConstants feedbackControllerConstants) {
public ControllerConstants withFeedback(FeedbackControllerConfig feedbackControllerConstants) {
this.feedback = feedbackControllerConstants;
return this;
}
Expand Down
91 changes: 0 additions & 91 deletions src/main/java/frc/lib/FeedbackControllerConstants.java

This file was deleted.

85 changes: 0 additions & 85 deletions src/main/java/frc/lib/FeedforwardControllerConstants.java

This file was deleted.

76 changes: 76 additions & 0 deletions src/main/java/frc/lib/config/AbsoluteEncoderConfig.java
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;
}
}
Loading

0 comments on commit b711e42

Please sign in to comment.