Motion Profiling: Exponential
Template Project
Start with the Command Robot template project. Motion profiling is typically implemented in subsystems, so the command-based structure works well. Create a new subsystem class in the
subsystems package.Overview
Exponential motion profiling uses smooth, continuous acceleration changes instead of constant acceleration. This creates natural-feeling movement that's ideal for elevators and arms. The profile continuously adjusts acceleration, eliminating sudden changes that cause mechanical stress.
What is Exponential Profiling?
Exponential profiles change acceleration smoothly over time, creating a velocity curve that looks like an exponential function. Unlike trapezoidal profiles with sharp corners, exponential profiles have smooth transitions, making them feel more natural and reducing wear on mechanisms.
Hardware Support
Built-in controller features:
- SPARK MAX: Use WPILib's
ExponentialProfileclass with PID control. - CTRE (Talon FX): Uses
Motion Magic® Expo(built-in exponential profile).
Step 1: Understand Exponential Profile Parameters
Exponential profiles require feedforward constants: kV (velocity feedforward) compensates for velocity-dependent forces. kA (acceleration feedforward) compensates for inertia during acceleration. kMaxV (max velocity) limits the top speed.
Step 2: Configure Exponential Profile (Talon FX)
For Talon FX, configure the exponential profile constants in the Motion Magic® configuration. These values work with the PID gains to create smooth motion.
public void configureExponentialProfile() {
// Configure Motion Magic® Exponential profile
MotionMagicConfigs mm = new MotionMagicConfigs();
mm.MotionMagicExpo_kV = 0.12; // Velocity feedforward
mm.MotionMagicExpo_kA = 0.01; // Acceleration feedforward
motor.getConfigurator().apply(mm);
}Step 3: Use Exponential Profile Control (Talon FX)
Once configured, use
MotionMagicExpoVoltage control request when setting positions. The controller automatically generates the exponential profile.public void setPosition(double target) {
// Use exponential motion profile
motor.setControl(new MotionMagicExpoVoltage(target));
}Step 4: Configure Exponential Profile (SPARK MAX with WPILib)
For SPARK MAX, use WPILib's
ExponentialProfile class. Create profile constraints from system characteristics, then calculate setpoints each loop cycle.Step 4a: Create Profile Constraints
// Define profile constraints from system characteristics
private static final double kMaxV = 10.0; // Max velocity
private static final double kV = 0.12; // Velocity feedforward
private static final double kA = 0.01; // Acceleration feedforward
private ExponentialProfile.Constraints constraints =
ExponentialProfile.Constraints.fromCharacteristics(kMaxV, kV, kA);
private ExponentialProfile profile = new ExponentialProfile(constraints);Step 4b: Calculate Profile Setpoints
In
periodic(), calculate the next setpoint from the profile each loop cycle. The profile takes the current position and goal position, returning the target position and velocity for this timestep.@Override
public void periodic() {
// Calculate next setpoint from profile
double dt = 0.02; // 20ms loop time
double current = getCurrentPosition();
double goal = getTargetPosition();
var state = profile.calculate(dt, current, goal);
// Apply position setpoint to PID controller
pid.setReference(state.position, ControlType.kPosition);
}Tuning Exponential Profiles
Tune feedforward first (kG, kV, kA), then feedback (kP, kD). Use simulation and dashboard tools like Elastic for live tuning. Log position and velocity graphs to observe behavior.
Feedforward Tuning
Physical forces:
- kG (Gravity): Set setpoint high, increase kG from 0. Find value where mechanism just starts to creep upward, then back off slightly.
- kV (Velocity): Run at fixed duty cycle, observe voltage and max velocity. kV = Voltage / Max Velocity (RPS). Use first 4-5 decimal places.
- kA (Acceleration): Trigger movement, measure time from 0 to max velocity. kA = kV / Time to Max Velocity.
Feedback Tuning
Position correction:
- kP (Proportional): Start small (0.1). Double values until mechanism moves. Too low = slow/sluggish curve. Too high = overshoot/oscillation. Ideal = straight line to setpoint.
- kD (Derivative): Start tiny (0.005-0.05). Increase to dampen oscillations. Too high = high-frequency jitter/noise causing motor heating. Goal = smooth flat line.
Tuning Goals
Position graph should look like a square wave: sharp rise, flat top, sharp drop without wobbling at corners. Ensure no oscillation causing mechanism to slam into limits. Simulation provides baseline values; physical robots may need slight adjustments for friction and gravity.
Full Code Example
Complete examples for both platforms:
package frc.robot.subsystems;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.math.trajectory.ExponentialProfile;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.ClosedLoopController.ControlType;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkBase.PersistMode;
// Create this class in the subsystems package (template provides ExampleSubsystem as reference)
public class Elevator extends SubsystemBase {
private SparkMax motor = new SparkMax(1, MotorType.kBrushless);
private SparkClosedLoopController pid = motor.getClosedLoopController();
// Define profile constraints from system characteristics
private static final double kMaxV = 10.0; // Max velocity
private static final double kV = 0.12; // Velocity feedforward
private static final double kA = 0.01; // Acceleration feedforward
private ExponentialProfile.Constraints constraints =
ExponentialProfile.Constraints.fromCharacteristics(kMaxV, kV, kA);
private ExponentialProfile profile = new ExponentialProfile(constraints);
private double targetPosition = 0.0;
public Elevator() {
// Configure motor and PID here
}
public void setTarget(double target) {
targetPosition = target;
}
// The template provides periodic() - update it with profile calculation
@Override
public void periodic() {
// Calculate next setpoint from profile
double dt = 0.02; // 20ms loop time
double current = motor.getEncoder().getPosition();
var state = profile.calculate(dt, current, targetPosition);
// Apply position setpoint to PID controller
pid.setReference(state.position, ControlType.kPosition);
}
}