[snippets] Add ProfiledPIDController with feedforward snippets (#8280)

Adds snippets demonstrating ProfiledPIDController usage with
SimpleMotorFeedforward using the two-parameter calculate() method
(currentVelocity, nextVelocity).

These snippets will be used in frc-docs to document the recommended
feedforward pattern with ProfiledPIDController.

Co-authored-by: sciencewhiz <sciencewhiz@users.noreply.github.com>
This commit is contained in:
Jason Daming
2025-10-27 19:49:16 -07:00
committed by GitHub
parent 873e960e93
commit a6a4912a80
5 changed files with 151 additions and 0 deletions

View File

@@ -0,0 +1,25 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package edu.wpi.first.wpilibj.snippets.profiledpidfeedforward;
import edu.wpi.first.wpilibj.RobotBase;
/**
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
* you are doing, do not modify this file except to change the parameter class to the startRobot
* call.
*/
public final class Main {
private Main() {}
/**
* Main initialization function. Do not perform any initialization here.
*
* <p>If you change your main robot class, change the parameter type.
*/
public static void main(String... args) {
RobotBase.startRobot(Robot::new);
}
}

View File

@@ -0,0 +1,51 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package edu.wpi.first.wpilibj.snippets.profiledpidfeedforward;
import edu.wpi.first.math.controller.ProfiledPIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* ProfiledPIDController with feedforward snippets for frc-docs.
* https://docs.wpilib.org/en/stable/docs/software/advanced-controls/controllers/profiled-pidcontroller.html
*/
public class Robot extends TimedRobot {
private final ProfiledPIDController m_controller =
new ProfiledPIDController(1.0, 0.0, 0.0, new TrapezoidProfile.Constraints(5.0, 10.0));
private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(0.5, 1.5, 0.3);
private final Encoder m_encoder = new Encoder(0, 1);
private final PWMSparkMax m_motor = new PWMSparkMax(0);
double m_lastSpeed;
/** Called once at the beginning of the robot program. */
public Robot() {
m_encoder.setDistancePerPulse(1.0 / 256.0);
}
/**
* Controls a simple motor's position using a SimpleMotorFeedforward and a ProfiledPIDController.
*
* @param goalPosition the desired position
*/
public void goToPosition(double goalPosition) {
double pidVal = m_controller.calculate(m_encoder.getDistance(), goalPosition);
m_motor.setVoltage(
pidVal
+ m_feedforward.calculateWithVelocities(
m_lastSpeed, m_controller.getSetpoint().velocity));
m_lastSpeed = m_controller.getSetpoint().velocity;
}
@Override
public void teleopPeriodic() {
// Example usage: move to position 10.0
goToPosition(10.0);
}
}

View File

@@ -169,5 +169,16 @@
"foldername": "accelerometerfilter",
"gradlebase": "java",
"mainclass": "Main"
},
{
"name": "ProfiledPIDFeedforward",
"description": "Snippets of ProfiledPIDController with feedforward for frc-docs.",
"tags": [
"PID",
"Profiled PID"
],
"foldername": "profiledpidfeedforward",
"gradlebase": "java",
"mainclass": "Robot"
}
]