PID Control in INDI Drivers
INDI Library provides a PID (Proportional-Integral-Derivative) controller implementation that drivers can use for smooth, accurate tracking and positioning. PID controllers are particularly useful for telescope mounts, focusers, and any device requiring precise closed-loop control.
What is PID Control?
A PID controller continuously calculates an error value as the difference between a desired setpoint and a measured process variable, then applies a correction based on proportional, integral, and derivative terms:
- Proportional (P): Produces output proportional to current error. Higher values = faster response but may cause overshoot.
- Integral (I): Accounts for past errors by integrating over time. Eliminates steady-state error but can cause windup.
- Derivative (D): Predicts future error based on rate of change. Provides damping to reduce overshoot.
The output is calculated as:
output = Kp * error + Ki * ∫error·dt + Kd * d(error)/dt
PID Class API
The INDI PID class is located in libs/indibase/pid/pid.h and provides the following interface:
#include "pid.h"
// Constructor parameters:
// dt - sampling/loop interval time (seconds)
// max - maximum output value
// min - minimum output value
// Kp - proportional gain
// Kd - derivative gain
// Ki - integral gain
PID(double dt, double max, double min, double Kp, double Kd, double Ki);
// Calculate control output
double calculate(double setpoint, double measurement);
// Reset controller state (clears integral, previous values)
void reset();
// Adjust gains dynamically
void setKp(double Kp);
void setKi(double Ki);
void setKd(double Kd);
void getGains(double &Kp, double &Ki, double &Kd) const;
// Set integrator limits (anti-windup)
void setIntegratorLimits(double min, double max);
// Set derivative filter time constant
void setTau(double value);
// Access individual terms for debugging
double proportionalTerm() const;
double integralTerm() const;
double derivativeTerm() const;
Key Features
- Anti-Windup Protection: Prevents integrator accumulation when output saturates
- Derivative on Measurement: Calculates derivative on process variable (not error) to prevent “derivative kick” during setpoint changes
- Low-Pass Filtered Derivative: Reduces noise sensitivity using configurable time constant (tau)
- Trapezoidal Integration: More accurate than simple rectangular integration
Implementation Details
Understanding why the INDI PID implementation uses specific algorithms:
Why Derivative on Measurement Instead of Error?
The implementation calculates derivative on the measurement (process variable) rather than on the error:
// From pid.cpp line 152
m_DerivativeTerm = -(2.0 * m_Kd * (measurement - m_PreviousMeasurement) + (2.0 * m_Tau - m_T) * m_DerivativeTerm)
/ (2.0 * m_Tau + m_T);
Reason: Prevents “derivative kick” during setpoint changes.
When using derivative on error: d(error)/dt = d(setpoint - measurement)/dt
If the setpoint changes suddenly (e.g., slewing to a new target):
- Error jumps instantly from small value to large value
d(error)/dtbecomes extremely large- Derivative term produces a huge spike in output
- This causes jerky motion and potential overshoot
When using derivative on measurement: d(measurement)/dt
- Measurement changes gradually (limited by physical system dynamics)
- Derivative remains smooth even during setpoint changes
- Only responds to actual process variable changes, not command changes
Mathematical equivalence during tracking:
When setpoint is constant: d(setpoint)/dt = 0
Therefore: d(error)/dt = -d(measurement)/dt
The negative sign in the implementation accounts for this, making it mathematically equivalent to error-based derivative during steady tracking, but smooth during setpoint changes.
Why Trapezoidal Integration (Using Both Current and Previous Error)?
The implementation uses trapezoidal rule for integration:
// From pid.cpp line 146
m_IntegralTerm = m_IntegralTerm + 0.5 * m_Ki * m_T * (error + m_PreviousError);
Reason: More accurate approximation of the integral.
Rectangular integration (simpler but less accurate):
integral += Ki * T * error_current
This assumes error is constant over the time interval T, using the current value.
Trapezoidal integration (INDI’s approach):
integral += Ki * T * (error_current + error_previous) / 2
This approximates the area under the error curve as a trapezoid, averaging the start and end values.
Why it’s better:
- More accurate when error changes during the sampling interval
- Second-order accurate (error ~ T²) vs first-order (error ~ T) for rectangular
- Better handles rapidly changing errors
- Accumulated integral more accurately represents true error history
Visual comparison:
Error vs Time:
| * current
| /|
| / | <- Trapezoid (INDI)
| / |
| * | <- Rectangle (simple method)
|_____|___
T
The trapezoid captures the actual error change better than rectangle.
Why Low-Pass Filter on Derivative?
The derivative term includes a low-pass filter with time constant tau:
m_DerivativeTerm = -(2.0 * m_Kd * (measurement - m_PreviousMeasurement) + (2.0 * m_Tau - m_T) * m_DerivativeTerm)
/ (2.0 * m_Tau + m_T);
Reason: Derivative amplifies high-frequency noise.
Raw derivative: d(measurement)/dt is extremely sensitive to measurement noise
- Small random fluctuations in measurement create large derivative values
- Output becomes noisy and can excite system resonances
The filter equation implements a first-order low-pass filter that:
- Smooths out high-frequency noise in the derivative
- Preserves low-frequency (actual) changes
tauparameter controls filter strength: higher tau = more filtering- Default tau=2 provides good noise rejection without excessive lag
This is why you can increase Kd for better damping without making the system noisy.
Why Accumulate Capped Integral Instead of Raw Error?
The integrator is limited before accumulation:
// Integral term (with trapezoidal integration)
m_IntegralTerm = m_IntegralTerm + 0.5 * m_Ki * m_T * (error + m_PreviousError);
// Clamp Integral (anti-windup for integrator limits)
if (m_IntegratorMin != m_IntegratorMax)
m_IntegralTerm = std::min(m_IntegratorMax, std::max(m_IntegratorMin, m_IntegralTerm));
Then later, additional anti-windup when output saturates:
// Anti-windup: Back-calculate integral if output is saturated
if (output != outputBeforeSaturation && m_Ki != 0.0)
{
m_IntegralTerm = output - m_ProportionalTerm - m_DerivativeTerm;
}
Reason: Prevents integrator windup during saturation.
The problem with unlimited integration:
- Error persists because system can’t move faster (output saturated)
- Integral keeps growing to huge values (windup)
- When error finally reverses, integral takes long time to unwind
- System overshoots significantly and oscillates
INDI’s two-stage anti-windup:
- Integrator limits: Prevents integral from growing beyond reasonable bounds
- Back-calculation: When output saturates, recalculates integral to match what actually contributed to output
This keeps the integral term meaningful and prevents overshoot recovery delays.
Practical Example: Telescope Mount Tracking
The Skywatcher Alt-Az mount driver uses PID controllers for tracking celestial objects. Here’s a simplified example:
1. Initialize PID Controllers
#include "pid.h"
class MyMount : public INDI::Telescope
{
private:
std::unique_ptr<PID> m_AxisAzController;
std::unique_ptr<PID> m_AxisAltController;
};
// In initProperties() or connection handler:
void MyMount::setupPIDControllers()
{
// Sampling time: polling period in seconds
double dt = getPollingPeriod() / 1000.0; // Convert ms to seconds
// Output limits: ±1000 (example units)
double max = 1000.0;
double min = -1000.0;
// Gains (tune these for your application)
double Kp_az = 0.1; // Azimuth proportional gain
double Ki_az = 0.05; // Azimuth integral gain
double Kd_az = 0.05; // Azimuth derivative gain
// Create controller
m_AxisAzController.reset(new PID(dt, max, min, Kp_az, Kd_az, Ki_az));
// Set integrator limits to prevent windup
m_AxisAzController->setIntegratorLimits(-1000, 1000);
// Similar for altitude axis
double Kp_alt = 0.2;
double Ki_alt = 0.1;
double Kd_alt = 0.1;
m_AxisAltController.reset(new PID(dt, max, min, Kp_alt, Kd_alt, Ki_alt));
m_AxisAltController->setIntegratorLimits(-1000, 1000);
}
2. Use PID in Tracking Loop
// Called periodically (e.g., every 100ms) during tracking
void MyMount::trackingLoop()
{
// Get target position (setpoint) in encoder steps
long targetAzSteps = calculateTargetAzimuth();
long targetAltSteps = calculateTargetAltitude();
// Get current position (measurement) from encoders
long currentAzSteps = getCurrentAzimuthEncoder();
long currentAltSteps = getCurrentAltitudeEncoder();
// Calculate control output (tracking rate)
double azTrackRate = m_AxisAzController->calculate(targetAzSteps, currentAzSteps);
double altTrackRate = m_AxisAltController->calculate(targetAltSteps, currentAltSteps);
// Apply tracking rates to motors
setMotorRate(AXIS_AZ, azTrackRate);
setMotorRate(AXIS_ALT, altTrackRate);
// Optional: Log PID terms for tuning
LOGF_DEBUG("AZ - P: %.2f I: %.2f D: %.2f Output: %.2f",
m_AxisAzController->proportionalTerm(),
m_AxisAzController->integralTerm(),
m_AxisAzController->derivativeTerm(),
azTrackRate);
}
3. Reset When Needed
// Reset controller state when starting tracking or after large changes
void MyMount::startTracking()
{
m_AxisAzController->reset();
m_AxisAltController->reset();
TrackState = SCOPE_TRACKING;
}
// Also reset after sync or manual slew
void MyMount::Sync(double ra, double dec)
{
// Update alignment model...
// Reset PID to prevent integral windup from position jump
m_AxisAzController->reset();
m_AxisAltController->reset();
}
Tuning Guidelines
PID tuning is an iterative process. Start with these steps:
- Start with P-only control (Ki=0, Kd=0)
- Increase Kp until system oscillates
- Reduce Kp to 50-60% of oscillation point
- Add Integral term if steady-state error exists
- Start with Ki = Kp / 10
- Increase slowly until steady-state error eliminated
- Watch for integrator windup
- Add Derivative term to reduce overshoot
- Start with Kd = Kp / 10
- Increase if overshoot is problematic
- Don’t overdo it - high Kd amplifies noise
- Fine-tune using Ziegler-Nichols or trial-and-error
Common Patterns
Exposing PID Gains as Properties
Allow users to tune PID gains through the client:
// In header:
INDI::PropertyNumber AxisPIDNP{3};
enum { Proportional, Integral, Derivative };
// In initProperties():
AxisPIDNP[Proportional].fill("Proportional", "Proportional", "%.2f", 0.1, 100, 1, 0.1);
AxisPIDNP[Integral].fill("Integral", "Integral", "%.2f", 0, 100, 1, 0.05);
AxisPIDNP[Derivative].fill("Derivative", "Derivative", "%.2f", 0, 100, 1, 0.05);
AxisPIDNP.fill(getDeviceName(), "AXIS_PID", "PID Gains", TRACKING_TAB, IP_RW, 60, IPS_IDLE);
// In ISNewNumber():
if (AxisPIDNP.isNameMatch(name))
{
AxisPIDNP.update(values, names, n);
AxisPIDNP.setState(IPS_OK);
AxisPIDNP.apply();
// Update PID controller with new gains
m_Controller->setKp(AxisPIDNP[Proportional].getValue());
m_Controller->setKi(AxisPIDNP[Integral].getValue());
m_Controller->setKd(AxisPIDNP[Derivative].getValue());
saveConfig(AxisPIDNP);
return true;
}
Debugging PID Performance
Log individual terms to understand controller behavior:
#ifdef DEBUG_PID
LOGF_DEBUG("PID Terms - P: %8.1f I: %8.1f D: %8.1f Output: %8.1f",
controller->proportionalTerm(),
controller->integralTerm(),
controller->derivativeTerm(),
output);
#endif
Best Practices
- Match Sampling Time to Loop Period: Set
dtparameter to actual loop execution time - Set Appropriate Output Limits: Match hardware capabilities to prevent saturation
- Use Integrator Limits: Always set integrator limits to prevent windup
- Reset After Large Changes: Call
reset()after syncs, park/unpark, or manual slews - Log for Tuning: Use
proportionalTerm(),integralTerm(),derivativeTerm()to understand behavior - Start Conservative: Begin with low gains and increase gradually
- Save Working Gains: Allow users to save tuned gains to config file
Common Issues and Solutions
| Problem | Likely Cause | Solution |
|---|---|---|
| Oscillation around target | Kp too high | Reduce proportional gain |
| Slow to reach target | Kp too low | Increase proportional gain |
| Never quite reaches target | No integral term | Add/increase Ki |
| Overshoots and slow to settle | Kd too low | Increase derivative gain |
| Very noisy output | Kd too high or noisy measurement | Reduce Kd, increase tau, filter measurements |
| Sudden output jump on setpoint change | Derivative on error | PID class already handles this correctly (derivative on measurement) |
| Integrator keeps growing when stuck | No anti-windup | PID class includes anti-windup, ensure output limits are set |
Advanced Topics
Gain Scheduling
Adjust gains based on operating conditions:
// Use different gains at different speeds or positions
if (slewSpeed > HIGH_SPEED_THRESHOLD)
{
controller->setKp(HIGH_SPEED_KP);
controller->setKd(HIGH_SPEED_KD);
}
else
{
controller->setKp(NORMAL_KP);
controller->setKd(NORMAL_KD);
}
Predictive Tracking
Combine PID with feed-forward for better tracking:
// Calculate expected rate (feed-forward)
double predictedRate = calculatePredictedTrackingRate();
// Add PID correction for errors
double pidCorrection = controller->calculate(target, current);
// Combined output
double output = predictedRate + pidCorrection;