VelocityControlAdvanced

An advanced velocity control implementation.

The VelocityControlAdvanced processing block can be found in the ‘Templates’ feature in the PMP installer.

velocity control advanced loop structure

The control loop structure where a feedback controller controls the velocity of a mechanical plant

The processing block is based on the feedback control structure shown above, where a velocity reference is tracked by a mechanical plant using sensor feedback. The reference signal is the demanded velocity and the output of the plant is position, which is measured using an encoder. The measured position and the control output are used to estimate the velocity via an observer.

Description

The implementation of the processing block is shown in The implementation of the processing block. The block consists of multiple components, which are further explained in the following sections:

  • State observer purple-rect

  • Tracking error calculation and loop control blue-rect

  • Feedback controller yellow-rect

  • Saturation and limits green-rect

  • Feedforward control red-rect

velocity control advanced implementation

The implementation of the processing block

The block is based on the VelocityControlSimple block, but has the following additional extensions and features which make it suitable for more advanced use cases:

  • Extra filter for the control algorithm.

  • Delay in the reference signal for feedforward timing optimization.

  • A state observer for velocity estimation.

State observer

The state observer is implemented as Luenberger observer, which is defined by the following equations:

\[\begin{split}\begin{aligned} \dot{\hat x}(t) &= A\hat x(t) + Bu(t) + L(y(t)-\hat{y}(t)) \\ \hat{y}(t) &= C\hat{x}(t) + Du(t) \end{aligned}\end{split}\]

The estimate of the state vector is defined as follows:

\[\hat{x}(t) = [EstimatedPosition(t); EstimatedVelocity(t)]\]

The state matrix \(A\) and input matrix \(B\) are of the following sizes:

\[\begin{split}dim[A(\cdot)] = 2*2 \\ dim[B(\cdot)] = 1*2\end{split}\]

The output matrix \(C\) and feedthrough matrix \(D\) are implemented as follows:

\[\begin{split}\begin{aligned} C &= [1\ \ 0] \\ D &= [0] \end{aligned}\end{split}\]

Therefore, the output is defined by:

\[\hat{y}(t) = EstimatedPosition(t)\]

The input is defined by:

\[u(t) = ControlOutput(t)\]

This results in the following equation:

\[\dot{\hat x}(t) = A\hat{x}(t) + B[ControlOutput(t)] + L[Position(t)-EstimatedPosition(t)]\]

This equation is defined by the schematic in the figure below. It is discretized using Euler discretization. Additionally, a position offset is used to set the initial condition of the observer equal to the measured position.

Observer implementation

The implementation of the Luenberger observer

Tracking error calculation and loop control

The tracking error is calculated using the following equation:
TrackingError = (DelayedDemandVelocity - MeasuredVelocity) * IsClosedLoop

The velocity controller can be in open loop or closed loop state. A request for a certain loop state is done via the CloseLoopRequest input. The IsClosedLoop signal is used to inform PMP about the active loop state. The behavior for different loop states are as follows:

Loop state

Loop state

Move commands

Feedforward

Feedback

OpenLoop

Allowed

Enabled

Disabled

ClosedLoop

Allowed

Enabled

Enabled

The DelayedDemandVelocity is the DemandVelocity delayed by a time that can be specified in seconds using the FeedbackDelay signal. The feedback delay is 0 s by default and can be increased up to 10 ms.

Hint

In a control loop with delay the effect of feedforward is not directly measurable on the sensor. This can cause the feedback controller to react to an error that the feedforward controller has already compensated for. This issue can be prevented by delaying the demand position used to calculate the tracking error. It is recommended to choose the FeedbackDelay equal to the IO delay of the control loop.

See also Demand position delay.

Feedback controller

The tracking error is forwarded to the control algorithm. The feedback controller has a PID controller and two generic filters.

The filters and PID controller are implemented in series. Each filter can be excluded from the control loop by configuring it as pass-through.

velocity-control-advanced implementation

The implementation of the feedback controller

Generic filter [1-2]

Each generic filter can be used to apply one of the following filters: 1st or 2nd order lowpass or highpass, 1st order lead/lag, 2nd order notch or 2nd order custom filters in either the continuous or discrete domain. By default, the generic filter type is set to PassThrough, which means that it’s disabled and the signal passes through the block.

PID

The PID controller combines a proportional, a derivative and an integral control term with a second order low pass filter. The second order low pass filter is applied to the results of the proportional and derivative terms, but not to the result of the integral term. The integrator output can be clipped to configurable limits. An IntegratorSaturated event is raised if the output exceeds the limits, i.e., IntegratorOutput < IntergratorLowerClip or IntegratorOutput > IntergratorUpperClip.

If the PID controller is not used, it can be configured as pass-through by using a proportional gain of one and setting the integrator and differentiator frequencies to zero. In this pass-through mode it is still required to configure the second order low pass filter.

Note

Each PMP Generic Filter block is a GenericFilter. The PID block is a PIDLowPass. Both blocks are discretized using Tustin’s method.

Saturation and limits

Limits are available to evaluate if the tracking error and control output stay within defined bounds. Event are raised if these bounds are exceeded.

Tracking error limit

The purpose of the control loop is to keep the tracking error small. If the tracking error becomes very large, then it’s likely that some part of the loop is not correctly functioning. For instance due to a failing actuator, a noisy sensor or obstructed mechanics.

Tracking error limit implementation

Implementation of the tracking error limit

The limit can be configured using the TrackingErrorLimit signal. The TrackingErrorLimitExceeded event is active if the tracking error exceeds the configured limit:

  • |TrackingError| > TrackingErrorLimit

Saturation

The control output saturation limits make sure that the velocity controller is aware of the physical limitations of the connected actuator. If the control output saturates, then the integrator of the PID controller is locked to prevent ‘integral windup’.

Attention

The control output saturation is not intended to protect the actuator against thermal overload. These protections should be configured on the actuator interface.

Saturation implementation

Implementation of the saturation

Note

The values of the saturation limits depend on the unit of the control output.

The saturation limits can be configured using the ControlOutputUpperSaturation and ControlOutputLowerSaturation signals. The CoutSaturationExceeded event is active if the control output exceeds these limits:

  • ControlOutput < ControlOutputLowerSaturation

  • ControlOutput > ControlOutputUpperSaturation

The saturation is disabled if ControlOutputUpperSaturation =< ControlOutputLowerSaturation.

Hint

If possible, design the controller such that the control output saturation limit is never exceeded during normal operation. Then use this event to disable the axis. This way, unsafe high forces due to mechanical obstruction, instability or magnetic misalignment are detected and captured early.

Feedforward control

The FeedforwardControl input can be used to connect the feedforward controller to the velocity controller. It is added after the PidOutput.

Integration

The integration of this processing block in the platform is depicted in The integration of velocity feedback control in the software platform. Most connections between the processing block and other software components are required for correct operation, but some are optional. The optional connections are depicted using dashed lines.

velocity control advanced integration

The integration of velocity feedback control in the software platform

Hint

In case a three phase actuator is used, the control output must be connected to the quadrature axis, often denoted as ‘DemandIq’.

Note

The unit of all signals is not defined by the processing block. The unit of the control output and feedforward control depends on the unit of the Demand input of the actuator. The unit of the demand velocity and position sensor depends on the unit of the Actual signal of the sensor.

Interface

Inputs

Inputs

Name

Description

CloseLoopRequest

Input to request a ClosedLoop loop status.

DemandVelocity

Demand velocity input used for tracking error calculation.

FeedforwardControl

Input to connect the feedforward controller to the velocity controller.

PositionSensor

Sensor value input used for tracking error calculation.

Read only signals

Read only signals

Name

Description

CombinedControlOutput

Combined feedback and feedforward controller output.

ControlOutput

Output of the velocity controller.

EstimatedPosition

Position estimated by the observer.

EstimatedVelocity

Velocity estimated by the observer.

EstimationError

Mismatch between measured and estimated position (corrected with ObserverPositionOffset).

GenericFilterOutput

Control output of the sequence of generic filters.

IsClosedLoop

Indicates if the velocity feedback control loop is open or closed.

ObserverPositionOffset

Position offset used to set the initial condition of the observer equal to the measured position.

PidOutput

Output of the PID controller.

TrackingError

Tracking error value.

Read-write signals

Read-write signals

Name

Description

A_0

Observer state matrix value A[0,0].

A_1

Observer state matrix value A[0,1].

A_2

Observer state matrix value A[1,0].

A_3

Observer state matrix value A[1,1].

B_0

Observer input matrix values B[0].

B_1

Observer input matrix values B[1].

ControlOutputLowerSaturation

Controller output lower saturation value.

ControlOutputUpperSaturation

Controller output upper saturation value.

FeedbackDelay [s]

Delay of DemandPosition before tracking error determination.

L_0

Observer gain matrix value L[0].

L_1

Observer gain matrix value L[1].

TrackingErrorLimit

Tracking error limit for feedback tracking limit determination.

Events

Events

Name

Description

TrackingErrorLimitExceeded

Active if a configurable feedback tracking error limit is exceeded.

IntegratorSaturated

Active if the integrator output reaches the saturation limit.

CoutSaturationExceeded

Active if a configurable control output saturation limit is reached.

Filters

Filters

Name

Type

Discretization type

Control_GenericFilter1

BiQuad

Tustin

Control_GenericFilter2

BiQuad

Tustin

Control_PID_LowPass

PidLp

Tustin