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

Commit

Permalink
refactor(arm): Use motion profile calculator.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Feb 10, 2024
1 parent b7a2c54 commit 4543483
Show file tree
Hide file tree
Showing 6 changed files with 31 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@

import edu.wpi.first.math.geometry.Rotation2d;

/** Helper class to assist with feedforward calculations. */
public class FeedforwardUtil {
/** Helper class to assist with arm feedforward calculations. */
public class ArmFeedforwardCalculator {

/**
* Calculates the gravity compensation constant for an arm given the voltage applied at an
Expand Down
17 changes: 17 additions & 0 deletions src/main/java/frc/lib/MotionProfileCalculator.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
package frc.lib;

/** Helper class to assist with motion profile calculations. */
public class MotionProfileCalculator {

/**
* Calculates an acceleration using a ramp duration.
*
* @param maximumSpeed the maximum speed in units per second.
* @param desiredRampDurationSeconds the desired duration to ramp from no speed to full speed.
* @return the acceleration in units per second per second.
*/
public static double calculateAcceleration(
double maximumSpeed, double desiredRampDurationSeconds) {
return maximumSpeed / desiredRampDurationSeconds;
}
}
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/arm/ArmConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.util.Units;
import frc.lib.CAN;
import frc.lib.MotionProfileCalculator;

/** Constants for the arm subsystem. */
public class ArmConstants {
Expand Down Expand Up @@ -33,7 +34,8 @@ public static class ShoulderMotorConstants {
public static final double MAXIMUM_SPEED = 1.5;

/** Maximum acceleration of the shoulder joint in rotations per second per second. */
public static final double MAXIMUM_ACCELERATION = 5.0;
public static final double MAXIMUM_ACCELERATION =
MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.3);
}

/** Constants for the elbow motor. */
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/arm/ShoulderMotorIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
import frc.lib.FeedforwardUtil;
import frc.lib.ArmFeedforwardCalculator;
import frc.robot.RobotConstants;
import frc.robot.arm.ArmConstants.ShoulderMotorConstants;

Expand Down Expand Up @@ -44,7 +44,7 @@ public ShoulderMotorIOSim() {
feedforward =
new ArmFeedforward(
0,
FeedforwardUtil.calculateArmGravityCompensation(
ArmFeedforwardCalculator.calculateArmGravityCompensation(
Rotation2d.fromDegrees(70.81), 0.101859),
0);
}
Expand Down
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/arm/ShoulderMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
import frc.lib.ArmFeedforwardCalculator;
import frc.lib.Configurator;
import frc.lib.FeedforwardUtil;
import frc.robot.arm.ArmConstants.ShoulderMotorConstants;

/** Shoulder motor using a Spark Max. */
Expand Down Expand Up @@ -38,7 +38,8 @@ public ShoulderMotorIOSparkMax() {
feedforward =
new ArmFeedforward(
0,
FeedforwardUtil.calculateArmGravityCompensation(Rotation2d.fromDegrees(18.0), 0.1222),
ArmFeedforwardCalculator.calculateArmGravityCompensation(
Rotation2d.fromDegrees(18.0), 0.1222),
0);
}

Expand Down
18 changes: 4 additions & 14 deletions src/main/java/frc/robot/swerve/SwerveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import frc.lib.MotionProfileCalculator;
import frc.lib.PIDFConstants;

/** Constants for the swerve subsystem. */
Expand Down Expand Up @@ -93,20 +94,9 @@ private static double calculateMaximumAttainableSpeed(
/** Maximum speed in meters per second. */
public static final double MAXIMUM_SPEED = MAXIMUM_ATTAINABLE_SPEED;

/**
* Calculates an acceleration using a ramp duration.
*
* @param maximumSpeed the maximum speed in units per second.
* @param desiredRampDurationSeconds the desired duration to ramp from no speed to full speed.
* @return the acceleration in units per second per second.
*/
private static double calculateAcceleration(
double maximumSpeed, double desiredRampDurationSeconds) {
return maximumSpeed / desiredRampDurationSeconds;
}

/** Maximum acceleration in meters per second per second. */
public static final double MAXIMUM_ACCELERATION = calculateAcceleration(MAXIMUM_SPEED, 0.1);
public static final double MAXIMUM_ACCELERATION =
MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.1);

/** Maximum attainable rotational speed in rotations per second. */
public static final double MAXIMUM_ATTAINABLE_ROTATION_SPEED =
Expand All @@ -117,7 +107,7 @@ private static double calculateAcceleration(

/** Maximum acceleration in rotations per second per second. */
public static final double MAXIMUM_ROTATION_ACCELERATION =
calculateAcceleration(MAXIMUM_ROTATION_SPEED, 0.1);
MotionProfileCalculator.calculateAcceleration(MAXIMUM_ROTATION_SPEED, 0.1);

public static final PIDFConstants DRIVE_PIDF_CONSTANTS = new PIDFConstants();

Expand Down

0 comments on commit 4543483

Please sign in to comment.