Package yams.math
Class ExponentialProfilePIDController
java.lang.Object
yams.math.ExponentialProfilePIDController
Exponential profile PID controller. Similar to
PIDController or
ProfiledPIDController, but uses an ExponentialProfile-
Constructor Summary
ConstructorsConstructorDescriptionExponentialProfilePIDController(double kP, double kI, double kD, ExponentialProfile.Constraints constraints) Constructor.ExponentialProfilePIDController(PIDController controller, ExponentialProfile.Constraints constraints) Constructor. -
Method Summary
Modifier and TypeMethodDescriptionbooleanReturns true if the error is within the tolerance of the setpoint.doublecalculate(double measurementPosition, double setpointPosition) Calculate the feedback, assuming no setpoint velocity.doublecalculate(double measurementPosition, double setpointVelocity, double setpointPosition) Calculate the feedback, assuming previous state velocity.createArmConstraints(Voltage maxVolts, DCMotor motor, Mass mass, Distance length, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor an arm.createArmConstraints(Voltage maxVolts, DCMotor motor, MomentOfInertia moi, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor an arm.createConstraints(Voltage maxVolts, AngularVelocity maxVelocity, AngularAcceleration maxAcceleration) Create a generic constraints object.createElevatorConstraints(Voltage maxVolts, DCMotor motor, Mass mass, Distance drumRadius, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor an elevator.createFlywheelConstraints(Voltage maxVolts, DCMotor motor, Mass mass, Distance radius, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor a flywheel.createFlywheelConstraints(Voltage maxVolts, DCMotor motor, MomentOfInertia moi, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor a flywheel.voidenableContinuousInput(double minimumInput, double maximumInput) Enables continuous input.Get the constraints.Get the current angle.Get the current state of theExponentialProfile.Get the current velocity fromExponentialProfile.doublegetD()Get the Differential coefficient.doublegetI()Get the Integral coefficient.getKa()Get the acceleration gain kAgetKv()Get the velocity gain as constant.Get the next angle from theExponentialProfileGet the next state of theExponentialProfile.Get the next velocity fromExponentialProfiledoublegetP()Get the Proportional coefficient.doubleReturns the error tolerance of this controller.doubleGet the setpoint.voidreset(double position, double velocity) Reset the PID and profile with the given postion and velocity as the measured position and velocity.voidreset(ExponentialProfile.State measurement) Reset the controller, set the next setpoint to empty.voidsetConstraints(ExponentialProfile.Constraints constraints) Sets the constraints for theExponentialProfile.voidsetD(double kD) Sets the Differential coefficient of the PID controller gain.voidsetI(double kI) Sets the Integral coefficient of the PID controller gain.voidsetP(double kP) Sets the Proportional coefficient of the PID controller gain.voidsetTolerance(double tolerance) Sets the error which is considered tolerable for use with atSetpoint().
-
Constructor Details
-
ExponentialProfilePIDController
public ExponentialProfilePIDController(PIDController controller, ExponentialProfile.Constraints constraints) Constructor.- Parameters:
controller- The wrapped PID controller.constraints- The wrapped profile constraints.
-
ExponentialProfilePIDController
public ExponentialProfilePIDController(double kP, double kI, double kD, ExponentialProfile.Constraints constraints) Constructor.- Parameters:
kP- kP value for thePIDControllerkI- kI value for thePIDControllerkD- kD value for thePIDControllerconstraints-ExponentialProfile.Constraintsfor theExponentialProfile
-
-
Method Details
-
createElevatorConstraints
public static ExponentialProfile.Constraints createElevatorConstraints(Voltage maxVolts, DCMotor motor, Mass mass, Distance drumRadius, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor an elevator.- Parameters:
maxVolts- Maximum input voltage for profile generation.motor-DCMotorof the elevator.mass-Massof the elevator carriage.drumRadius-Distanceof the elevator drum radius.gearing-MechanismGearingof the elevator from the drum to the rotor.- Returns:
ExponentialProfile.Constraints
-
createArmConstraints
public static ExponentialProfile.Constraints createArmConstraints(Voltage maxVolts, DCMotor motor, MomentOfInertia moi, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor an arm.- Parameters:
maxVolts- Maximum input voltage for profile generation.motor-DCMotorof the arm.moi-MomentOfInertiaof the arm.gearing-MechanismGearingof the arm from the rotor to the drum.gearing.getMechanismToRotorRatio()- Returns:
ExponentialProfile.Constraints
-
createArmConstraints
public static ExponentialProfile.Constraints createArmConstraints(Voltage maxVolts, DCMotor motor, Mass mass, Distance length, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor an arm.- Parameters:
maxVolts- Maximum input voltage for profile generation.motor-DCMotorof the arm.mass-Massof the arm.length-Distanceof the arm length.gearing-MechanismGearingof the arm from the rotor to the drum.gearing.getMechanismToRotorRatio()- Returns:
ExponentialProfile.Constraints
-
createFlywheelConstraints
public static ExponentialProfile.Constraints createFlywheelConstraints(Voltage maxVolts, DCMotor motor, MomentOfInertia moi, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor a flywheel.- Parameters:
maxVolts- Maximum input voltage for profile generation.motor-DCMotorof the flywheel.moi-MomentOfInertiaof the flywheel.gearing-MechanismGearingof the flywheel from the rotor to the drum.- Returns:
ExponentialProfile.Constraints
-
createFlywheelConstraints
public static ExponentialProfile.Constraints createFlywheelConstraints(Voltage maxVolts, DCMotor motor, Mass mass, Distance radius, MechanismGearing gearing) Get theExponentialProfile.Constraintsfor a flywheel.- Parameters:
maxVolts- Maximum input voltage for profile generation.motor-DCMotorof the flywheel.mass-Massof the flywheel.radius-Distanceof the flywheel radius.gearing-MechanismGearingof the flywheel from the rotor to the drum.- Returns:
ExponentialProfile.Constraints
-
createConstraints
public static ExponentialProfile.Constraints createConstraints(Voltage maxVolts, AngularVelocity maxVelocity, AngularAcceleration maxAcceleration) Create a generic constraints object.- Parameters:
maxVolts- Maximum input voltage for profile generation.maxVelocity- Maximum velocity.maxAcceleration- Maximum acceleration.- Returns:
ExponentialProfile.Constraints
-
getKv
Get the velocity gain as constant.- Returns:
- kV with (-A/B)
-
getKa
Get the acceleration gain kA- Returns:
- kA interpreted as (1.0/B)
-
reset
Reset the controller, set the next setpoint to empty.- Parameters:
measurement- Measurement in Rotations, and Rotations per Second.
-
reset
public void reset(double position, double velocity) Reset the PID and profile with the given postion and velocity as the measured position and velocity.- Parameters:
position- Measured positionvelocity- Measured velocity.
-
getConstraints
Get the constraints.- Returns:
ExponentialProfile.Constraints
-
setConstraints
Sets the constraints for theExponentialProfile.- Parameters:
constraints- The constraints for theExponentialProfile.
-
setTolerance
public void setTolerance(double tolerance) Sets the error which is considered tolerable for use with atSetpoint().- Parameters:
tolerance- – Error which is tolerable.
-
atSetpoint
public boolean atSetpoint()Returns true if the error is within the tolerance of the setpoint. The error tolerance defaults to 0.05, and the error derivative tolerance defaults to ∞. This will return false until at least one input value has been computed.- Returns:
- Whether the error is within the acceptable bounds
-
getSetpoint
public double getSetpoint()Get the setpoint.- Returns:
- setpoint.
-
getCurrentState
Get the current state of theExponentialProfile.- Returns:
ExponentialProfile.Stategiven by theExponentialProfile.
-
getCurrentAngle
Get the current angle.- Returns:
AnglefromExponentialProfile
-
getNextAngle
Get the next angle from theExponentialProfile- Returns:
AnglefromExponentialProfile
-
getCurrentVelocitySetpoint
Get the current velocity fromExponentialProfile.- Returns:
AngularVelocityfromExponentialProfile
-
getNextVelocitySetpoint
Get the next velocity fromExponentialProfile- Returns:
- Next
AngularVelocityfromExponentialProfile
-
getNextState
Get the next state of theExponentialProfile.- Returns:
ExponentialProfile.Stategiven by theExponentialProfile.
-
calculate
public double calculate(double measurementPosition, double setpointVelocity, double setpointPosition) Calculate the feedback, assuming previous state velocity.- Parameters:
measurementPosition- Measurement position to set as the current state..setpointVelocity- Setpoint velocity.setpointPosition- Setpoint position.- Returns:
- Profile calculation
-
calculate
public double calculate(double measurementPosition, double setpointPosition) Calculate the feedback, assuming no setpoint velocity.- Parameters:
measurementPosition- Measurement position to set as the current state.setpointPosition- Setpoint position.- Returns:
- Profile calculation where setpoint velocity is 0.
-
getPositionTolerance
public double getPositionTolerance()Returns the error tolerance of this controller. Defaults to 0.05.- Returns:
- the error tolerance of the controlle
-
getP
public double getP()Get the Proportional coefficient.- Returns:
- proportional coefficient
-
setP
public void setP(double kP) Sets the Proportional coefficient of the PID controller gain.- Parameters:
kP- The proportional coefficient. Must be >= 0.
-
getI
public double getI()Get the Integral coefficient.- Returns:
- integral coefficient
-
setI
public void setI(double kI) Sets the Integral coefficient of the PID controller gain.- Parameters:
kI- The integral coefficient. Must be >= 0.
-
getD
public double getD()Get the Differential coefficient.- Returns:
- differential coefficient
-
setD
public void setD(double kD) Sets the Differential coefficient of the PID controller gain.- Parameters:
kD- The differential coefficient. Must be >= 0.
-
enableContinuousInput
public void enableContinuousInput(double minimumInput, double maximumInput) Enables continuous input.Rather then using the max and min input range as constraints, it considers them to be the same point and automatically calculates the shortest route to the setpoint.
- Parameters:
minimumInput- The minimum value expected from the input.maximumInput- The maximum value expected from the input.
-