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

Commit

Permalink
refactor: Add single jointed arm feedforward.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Feb 23, 2024
1 parent c8795ef commit 17b17f7
Show file tree
Hide file tree
Showing 3 changed files with 39 additions and 7 deletions.
30 changes: 30 additions & 0 deletions src/main/java/frc/lib/SingleJointedArmFeedforward.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
package frc.lib;

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

public class SingleJointedArmFeedforward {

private final ArmFeedforward feedforward;

public SingleJointedArmFeedforward(double ks, double kg, double kv) {
feedforward = new ArmFeedforward(ks, kg, kv);
}

public SingleJointedArmFeedforward(double ks, double kg, double kv, double ka) {
feedforward = new ArmFeedforward(ks, kg, kv, ka);
}

public double calculate(Rotation2d position) {
return feedforward.calculate(position.getRadians(), 0);
}

public double calculate(Rotation2d position, double velocity) {
return feedforward.calculate(position.getRadians(), velocity);
}

public double calculate(Rotation2d position, double velocity, double acceleration) {
return feedforward.calculate(position.getRadians(), velocity, acceleration);
}

}
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/arm/ShoulderMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,12 @@
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import frc.lib.AccelerationCalculator;
import frc.lib.ArmFeedforwardCalculator;
import frc.lib.Configurator;
import frc.lib.SingleJointedArmFeedforward;
import frc.robot.arm.ArmConstants.ShoulderMotorConstants;

/** Shoulder motor using a Spark Max. */
Expand All @@ -21,7 +21,7 @@ public class ShoulderMotorIOSparkMax implements ShoulderMotorIO {
private final PIDController feedback;

/** Feedforward controller for shoulder position. */
private final ArmFeedforward feedforward;
private final SingleJointedArmFeedforward feedforward;

private final AccelerationCalculator accelerationCalculator;

Expand All @@ -32,7 +32,7 @@ public ShoulderMotorIOSparkMax() {
feedback = new PIDController(ShoulderMotorConstants.KP, 0, 0);

feedforward =
new ArmFeedforward(
new SingleJointedArmFeedforward(
0,
ArmFeedforwardCalculator.calculateArmGravityCompensation(
Rotation2d.fromDegrees(18.0), 0.1222),
Expand Down Expand Up @@ -74,7 +74,7 @@ public void setSetpoint(double positionRotations, double velocityRotationsPerSec
double feedbackVolts = feedback.calculate(measuredPositionRotations, positionRotations);

double feedforwardVolts =
feedforward.calculate(measuredPositionRotations, velocityRotationsPerSecond);
feedforward.calculate(Rotation2d.fromRotations(measuredPositionRotations), velocityRotationsPerSecond);

sparkMax.setVoltage(feedbackVolts + feedforwardVolts);
}
Expand Down
8 changes: 5 additions & 3 deletions src/main/java/frc/robot/intake/PivotMotorIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,11 @@

import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
import frc.lib.SingleJointedArmFeedforward;
import frc.robot.RobotConstants;
import frc.robot.intake.IntakeConstants.PivotMotorConstants;

Expand All @@ -17,7 +19,7 @@ public class PivotMotorIOSim implements PivotMotorIO {

private final PIDController feedback;

private final ArmFeedforward feedforward;
private final SingleJointedArmFeedforward feedforward;

public PivotMotorIOSim() {
motor = DCMotor.getVex775Pro(1);
Expand All @@ -35,7 +37,7 @@ public PivotMotorIOSim() {

feedback = new PIDController(PivotMotorConstants.KP, 0, 0);

feedforward = new ArmFeedforward(0, 0, 0);
feedforward = new SingleJointedArmFeedforward(0, 0, 0);
}

@Override
Expand All @@ -61,7 +63,7 @@ public void setSetpoint(double positionRotations, double velocityRotationsPerSec

double feedforwardVolts =
feedforward.calculate(
Units.rotationsToRadians(measuredPositionRotations), velocityRotationsPerSecond);
Rotation2d.fromRotations(measuredPositionRotations), velocityRotationsPerSecond);

singleJointedArmSim.setInputVoltage(feedbackVolts + feedforwardVolts);
}
Expand Down

0 comments on commit 17b17f7

Please sign in to comment.