Drive#
The drive command implements the main function of Telega-based motor controllers, which is to drive the motor in propulsive applications. It can also be used to control electric generators.
The behavior of the drive command is highly configurable via selectable run strategies, velocity control strategies, and other parameters described in this chapter.
Principles#
Internally, the purpose of the drive command is to provide setpoints to the underlying vector control system discussed in the Motor control fundamentals chapter:
The drive command supports several control modes. In the \(\tau\) (torque) and \(u_q\) (voltage) control modes, their respective setpoints are passed directly to the underlying vector control system pictured above. The operation of the underlying controller depends on the motor model parameters, particularly the DQ-frame parameters.
In the velocity control mode, an additional velocity controller is introduced that accepts the velocity setpoint and computes the torque setpoint for the underlying controller. There are several velocity control strategies available that are optimized for different applications.
Starting, stopping, stall detection, and related state transitions are managed by the selectable run strategies. Choice of the run strategy is dictated by the application where Telega is used.
The drive command makes no distinction between rotary loads and translational loads due to the similarities between linear motion and rotation around a fixed axis. The choice between the rotational and translational units depends on the mechanical ratio setting.
The drive command supports full four-quadrant operation.
The direction of the forward motion can be configured using the vsi.swap_ab
register.
Configuration registers#
Changes to the configuration registers documented in this section take effect when the command execution is (re-)started, unless expressly indicated otherwise.
Configuration parameters whose name contains a component that begins with a digit followed by an underscore
(e.g., .1_
) specify a selectable strategy.
The strategy is selected by writing the appropriate integer value into the corresponding .type
register.
“PU” indicates a per-unit value — a ratiometric value with the nominal range in \([0,+1]\) or \([-1,+1]\), depending on the context.
Register |
Type |
Unit |
Description |
---|---|---|---|
|
|
1 |
Maximum braking current as a fraction of the rated phase current amplitude. |
|
|
1 |
If greater than 1.0, enables flux weakening with the specified voltage boost. |
|
|
\(\frac\A\V,\frac\A{\V\times{}\s},\frac{\A\times{}\s}\V\) |
PID gains of the flux weakening back-EMF controller. |
|
|
Report fault if the motor has stalled this many times in a short time interval. |
|
|
|
Allow phase voltage waveform clipping to maximize voltage utilization. |
|
|
|
Always re-calibrate the VSI before commencing the drive command execution. Adds delay. |
|
|
|
Do not alter. |
|
|
|
\(\frac{\A^2}\s,\frac{\A^2}\s,\frac{\erad^2}{\s^3}\) |
EKF process noise for \(i_d,i_q,\omega_e\), respectively. |
|
|
1 |
Do not alter. |
|
|
1 |
Do not alter. |
|
|
Selects the run strategy. |
|
|
|
\([\frac\rad\s,\frac\rad\s]\) or \([\frac\m\s,\frac\m\s]\) |
Stall detection velocity threshold and the end-of-spinup-ramp velocity, respectively. |
|
|
ampere (x2) |
Alignment and ramp-end current settings as fractions of the rated phase current amplitude. |
|
|
second (x6) |
Spinup duration per stage. |
|
|
\([\frac\rad\s,\frac\rad\s]\) or \([\frac\m\s,\frac\m\s]\) |
Deactivation and activation velocity thresholds, respectively. |
|
|
second |
Deactivation and activation delay (shared). |
|
|
\([\frac\rad{\s^2},\frac{\rad}{\s^2}]\) or \([\frac\m{\s^2},\frac{\m}{\s^2}]\) |
Deceleration and acceleration limits (ramps), respectively, for the velocity control mode. |
|
|
Selects which velocity controller to use, none by default. |
|
|
|
\([\frac{\Nm\times\s}\rad,\frac\Nm\rad,\frac{\Nm\times\s^2}\rad]\) or \([\frac{\N\times\s}\m,\frac\N\m,\frac{\N\times\s^2}\m]\) |
Gains of the velocity controller. |
|
|
\([\frac{\Nm\times\s}\rad,\frac{\Nm\times\s^2}{\rad^2}]\) or \([\frac{\N\times\s}\m,\frac{\N\times\s^2}{\m^2}]\) |
Feed-forward terms of the velocity controller, linear and quadratic. |
|
|
\([\frac1\s,\frac{\rad^2}{\s^2}]\) or \([\frac1\s,\frac{\m^2}{\s^2}]\) |
Gains of the acceleration controller. |
|
|
\([\kg\times\m^2]\) or \([\kg]\) |
Maximum moment of inertia of the attached mechanical load (usually lower than the actual moment of inertia). |
Run strategies#
The run strategy, selectable via drive.runner.type
, defines how the drive handles the transition between the stationary
and running states, and vice versa, as well as the stall detection.
Each of the available strategies are reviewed in the following sections.
Ramp spinup#
The ramp spinup strategy is intended for sensorless thruster drives — propellers, fans, waterjets, pumps, etc. In this strategy, the motor is initially driven in the variable current, variable frequency (VCVF) mode bypassing the rotor state observer, until the minimum operating velocity where the normal sensorless control mode can be activated is reached. The spinup process consists of six stages:
Pickup — the controller observes the state of the motor while freewheeling. If the observed velocity exceeds the spinup threshold, regardless of the direction of rotation, stage 6 “stall inhibition” is activated immediately to avoid braking the motor.
DC alignment — the configured DC alignment current is supplied for a specified time to align the rotor along the D-axis.
VCVF ramp — the motor is driven in the VCVF mode where the velocity is ramped from zero to the ramp-end spinup velocity setting, and the current is ramped from the DC alignment current setting to the ramp-end current setting.
Backoff — the current is reduced to zero following the configured \(\frac{\delta{}i}{\delta{}t}\) limit, then an additional configurable delay is inserted for the current controllers to settle.
Synchronization — the velocity override is disabled and the controller freewheels for a configurable time while the state estimator synchronizes with the rotor.
Stall inhibition — this is the normal operating mode except that the rotor stall detection is temporarily disabled. Its purpose is to prevent incorrect stall detection caused by the post-ramp transients.
After completion of the last stage, normal operation is commenced. If motor stall is detected, the spinup proces is restarted from the first stage. The behavior is illustrated in the following state machine diagram:
The duration of each stage is set via the drive.runner.0_ramp.spinup_duration
register.
The DC alignment current and ramp-end current are set via drive.runner.0_ramp.spinup_current_pu
,
respectively.
The stall detection velocity and ramp-end velocity are set via drive.runner.0_ramp.velocity_stall_spinup
.
In the case of direct-drive propeller or fan thrusters, it is often desirable to enable faster spinup than what is provided by the default configuration. Good results can usually be achieved by adjusting the default settings as follows:
The pickup stage can be shortened to approx. 100 ms.
The DC alignment stage can be eliminated by setting the duration of its stage to zero.
The VCVF ramp can be shortened down to about 300~1000 ms, depending on the application and the spinup velocity.
The spinup current can be set to about 10-30% of the maximum.
One example of such revised configuration is given below:
drive.runner.0_ramp.spinup_current_pu: [0.3, 0.3]
drive.runner.0_ramp.spinup_duration: [0.1, 0.0, 0.4, 0.002, 0.015, 0.6]
If high torque is required during spinup, then the duration of the final stages – Backoff and Synchronization – should be shortened to avoid velocity drop during the hand-off to normal mode. One possible configuration is shown below:
drive.runner.0_ramp.spinup_current_pu: [0.5, 1.0]
drive.runner.0_ramp.spinup_duration: [0.1, 0.4, 2.0, 0.5e-3, 1.0e-3, 0.6]
Passive spinup#
The passive spinup strategy is intended for sensorless applications where the freewheeling motor is initially accelerated by an external force, such as a generator. In this strategy, the controller is kept in either the on state, where the motor is driven normally according to the externally provided command, or the off state, where the motor is freewheeling and the external commands are ignored.
The initial state is off. Once the on-threshold velocity is exceeded, the drive enters normal operating mode and remains there until the motor decelerates below the off-threshold velocity (or the command is canceled). The on/off-thresholds are usually configured with a hysteresis to avoid oscillation. Additionally, an optional on/off transition delay is available. The resulting state transitions are illustrated below.
Setting the thresholds to zero will activate the on state permanently.
Tip
The passive spinup strategy can be used for tuning the current controller bandwidth ratio as follows: enable the passive spinup mode and engage the torque control mode with zero setpoint, then rotate the motor externally while alternating the direction of rotation.
If the current control loop is tuned properly, the load torque (resistance to motion) should be virtually zero, and there should be no significant audible noise produced by the stator winding. Resistance to motion indicates that the current control loop is overdamped, so the bandwidth ratio should be increased. Loud noise produced by the stator winding indicates that the current control loop is underdamped and prone to self-induced oscillation.
Control modes#
Each mode implements control of a specific state of interest (e.g., velocity). Some control modes support optional constraints on the dependent states (e.g., torque limit).
Torque (force) control mode#
The torque (force) control mode accepts the desired torque \(\left[\text{newton}\times{}\text{meter}\right]\) or force \(\left[\text{newton}\right]\) setpoint depending on the mechanical ratio setting, and forwards it to the torque & flux controller of the underlying vector control system. Negative setpoint during forward motion or positive setpoint during reverse motion result in regenerative braking; zero setpoint results in freewheeling.
The setpoint slew rate \(\frac{\delta{}\tau}{\delta{}t}\) is implicitly defined by the current ramp setting, because motor torque is a function of current. Note, however, that the torque response is not strictly linear, which implies that the slew rate limits are not strictly proportional: \(\frac{\delta{}\tau}{\delta{}t} \not\propto \frac{\delta{}i}{\delta{}t}\). This property, however, can be ignored in practical applications. If a fine-tuned torque slew rate limit is required, it should be implemented externally.
The setpoint is clipped such that the rated phase current amplitude is not exceeded.
Note
As can be seen from \(P = \omega\,\tau = F\,v\), this control mode can accelerate an unloaded motor to the maximum velocity even at very low setpoint values.
Ratiometric torque (force) control mode#
The ratiometric torque (force) control mode accepts the desired setpoint as a ratiometric (i.e., per-unit) dimensionless value in \([-1,+1]\), multiplies it by the rated phase current amplitude, and uses the resulting value as the \(i_q\) setpoint. Out-of-range setpoint values are clipped.
As the motor torque response is non-linear, the resulting behavior is also somewhat non-linear, especially when flux weakening is active. The nonlinearity, however, is acceptably low for most applications.
Velocity control mode#
The velocity control mode accepts the desired mechanical velocity \(\omega\) in either angular \(\left[\frac{\text{radian}}{\text{second}}\right]\) or linear \(\left[\frac{\text{meter}}{\text{second}}\right]\) units depending on the mechanical ratio setting, and a set of four-quadrant constraints:
minimum acceleration \(\dot{\omega}_d < 0\) (deceleration),
maximum acceleration \(\dot{\omega}_a > 0\) \(\left[\frac{\text{radian}}{\text{second}^2}\right]\) or \(\left[\frac{\text{meter}}{\text{second}^2}\right]\);
minimum torque (force) \(\tau_b < 0\) (braking),
maximum torque (force) \(\tau_m > 0\) \(\left[\text{newton}\times{}\text{meter}\right]\) or \(\left[\text{newton}\right]\).
The velocity \(\omega\) is driven towards the target such that the deceleration/acceleration profile is followed: \(\dot{\omega}_d \le \frac{\delta{}\omega}{\delta{}t} \le \dot{\omega}_a\).
The torque (force) setpoint \(\tau\), computed by the velocity controller, is constrained such that the limits are not exceeded: \(\tau_b < \tau < \tau_a\).
In the velocity control mode, the current ramp setting should be high to avoid interference with the velocity controller.
Null strategy#
This is the default strategy. It always commands zero torque (force), hence an attempt to use this strategy will always engage freewheeling. It is provided as a safe placeholder for unconfigured systems.
PID+FF strategy#
This strategy is based on a parallel PID controller with optional feed-forward terms arranged as shown on the diagram:
The parallel PID gains are set via drive.velocity_ctl.1_pid.gain
.
The feed-forward torque contribution is computed as \(\tau_\text{ff} = \omega^2 f_2 + \omega f_1\),
where \(f_1,f_2\) are the linear and quadratic terms set via drive.velocity_ctl.1_pid.feedforward
,
respectively.
This controller is a good fit for applications where the dynamic model of the load is not accurately known.
This controller is usually not the best choice for aircraft thrusters where fast speed response is required (e.g., multirotors, lift thrusters in VTOL vehicles). To understand why, consider the standard propeller torque equation: \(Q = C_q \, \rho \, D^5 \, \frac1{4 \pi^2} \, \omega^2\), with the torque coefficient \(C_q\), fluid density \(\rho\), and diameter \(D\). Optimal control requires \(f_2 = C_q \, \rho \, D^5 \, \frac1{4 \pi^2}\); however, under this definition \(f_2\) is not constant because \(\rho\) is a function of altitude and weather conditions, and \(C_q\) is non-constant for variable-pitch propellers.
INDI strategy#
The incremental nonlinear dynamics inversion (INDI) controller is designed for loads with known and nearly fixed inertia, such as propellers, fans, pumps, etc. This is a highly robust adaptive controller that is invariant to any parameters of the load aside from its inertia, which makes it a particularly good fit for use with thrusters as it provides consistent performance regardless of the fluid density or the propeller pitch.
The INDI controller includes a parallel PI acceleration pre-controller that accepts the velocity setpoint and outputs the raw acceleration setpoint; the latter is clipped to ensure that the deceleration/acceleration limits are not exceeded, and the result is passed to the INDI controller. The resulting structure is shown in the diagram:
The gains of the PI controller are set via drive.velocity_ctl.2_indi.acceleration_pi
.
The (maximum) moment of inertia of the load used in the model is set via drive.velocity_ctl.2_indi.mass
;
typically, the value of this parameter should be lower by a factor of \(\approx{}10\) than the actual moment of inertia
of the load to account for the noise in the system; otherwise, high-frequency oscillation may occur.
The parameter refers to the “maximum” moment of inertia to account for the applications where the moment of inertia
is variable (e.g., due to the variable geometry of the load).
For a known moment of inertia, the typical tuning process for this controller involves setting the mass
parameter
to a value approximately 20 times lower than the actual moment of inertia of the load,
with subsequent slow increase to the maximum value where the controller does not exhibit instability
or high-frequency self-oscillation.
The moment of inertia provided to the INDI controller needs to be consistent with the mechanical ratio setting. For example, if the load is connected to the motor through a gearbox with a gear ratio R (where R<1 if the motor makes >1 revolution per load revolution) that is not factored into the mechanical ratio setting, the inertia must be multiplied by R.
Voltage control mode#
Warning
The voltage control mode is provided for compatibility with applications that expect the drive to exhibit control input response similar to the conventional low-cost trapezoidal motor controllers (aka ESC). Normally, its use is discouraged as it is difficult to ensure efficient and stable operation of the drive in this mode. Consider using the velocity control mode instead.
The voltage control mode accepts the desired \(u_q\) voltage setpoint [volt] and forwards it to the underlying vector control system. Regeneration takes place if \(|u_q| < |u_\text{BEMF}|\) or \(\text{sgn}(u_q) \neq \text{sgn}(u_\text{BEMF})\).
This mode does not perform current regulation. As such, care should be taken to avoid exceeding the rated motor phase current.
The voltage slew rate \(\frac{\delta{}u_q}{\delta{}t}\) is defined as part of the motor model.
The dynamic range of the voltage setpoint is limited as \(u_q \in \left[-u_\text{max},+u_\text{max}\right]\), where \(u_\text{max} = f_\text{util}\frac{u_\text{dc}}{\sqrt{3}}\), and the voltage utilization factor \(f_\text{util}\) depends on the VSI configuration. Values that exceed the range are clipped.
Ratiometric voltage control mode#
The ratiometric voltage control mode accepts the desired voltage setpoint as a ratiometric (i.e., per-unit) dimensionless value in \([-1,+1]\), multiplies it by \(f_\text{util}\frac{u_\text{dc}}{\sqrt{3}}\), and uses the resulting value as the \(u_q\) setpoint for the regular voltage control mode described earlier. Out-of-range setpoint values are clipped.
State estimators#
Behavior of the state estimator depends not only on the configuration specific for this command, but also on the VSI configuration. In particular, the standard error (square root of the error variance) of the phase current measurement circuit is dependent on the design and characteristics of the power stage hardware and is a critical parameter for the state estimator. Normally, if estimator tuning is required, it should be done by adjusting the command-specific parameters while keeping the VSI-specific parameters unchanged.
EKF#
This estimator is designed for sensorless drives. It is based on the extended Kalman filter with adaptive parameter scheduling. Normally, this estimator does not require tuning by the integrator; Zubax Robotics can perform fine-tuning for a specific application upon request.
One exception applies to the process noise matrix \(\textbf{Q}\) whose diagonal elements can be adjusted
via the drive.observer.0_ekf.proc_noise
register by the integrator.
Higher values improve the tracking performance during transients at the cost of noise immunity, and vice versa.
The following parameters have been found stable across different types of applications:
For dynamic loads: ( 1.0e6, 3.0e6, 100.0e6)
For noise resilience: (10.0e3, 30.0e3, 1000.0e3)
Flux (field) weakening#
A back-EMF-feedback flux weakening controller is implemented.
By default, it is disabled.
It can be enabled by setting the voltage boost factor \(f_{u_\text{boost}}\) via drive.flux_weakening.voltage_boost
such that \(1 < f_{u_\text{boost}} \le 1.5\);
typically, \(f_{u_\text{boost}} \approx 1.2\).
When enabled, the flux weakening controller remains inactive until the motor base velocity is exceeded
(i.e., the DC link voltage is depleted).
Once activated, the controller will inject \(i_d<0\) such that the rotor flux is suppressed
according to the \(f_{u_\text{boost}}\) setting.
The magnitude of \(i_d\) is determined by the back-EMF parallel PID controller,
whose PID gains are set via drive.flux_weakening.bemf_pid
.
The default gains of the back-EMF PID controller should be adequate for many applications. Its performance can be evaluated by plotting the DQ system quantities in real time.
Invocation#
The drive command has to be issued periodically to avoid expiration of the deadman timeout. Periodic commands are used to provide new setpoint values (torque, velocity, etc.) and to allow automatic disengagement of the drive if the outer system becomes unable to issue new commands (e.g., due to an interface failure).
Via Cyphal#
Telega implements several Cyphal subscriptions that deliver commands to the drive task. The control mode is chosen by publishing on the appropriate topic as summarized in the table:
Topic name |
Type |
Control mode |
Array/single |
---|---|---|---|
|
|
Velocity or torque |
Single |
|
|
Velocity |
Array |
|
|
Ratiometric torque |
Array |
|
|
Ratiometric torque |
Array |
|
|
Ratiometric voltage |
Array |
|
|
Ratiometric voltage |
Array |
|
|
Ratiometric velocity |
Array |
Some subscriptions are array-typed,
which allows one to control an arbitrary number of drives subscribed to the same topic synchronously.
In this case, each drive is configured with a specific value of the
mns.setpoint_index
register,
which specifies the index of the array element that contains the setpoint for the given controller.
Integer-typed setpoint array values are mapped to ratiometric values as follows:
\(n\)-bit unsigned integer arrays: \(f(0)=0, \quad{} f(2^{n}-1)=1\)
\(n\)-bit signed integer arrays: \(f(0)=0, \quad{} f(2^{n}-1)=1, \quad{} f(-(2^{n}))=f(-(2^{n})+1)=-1\)
Definition of uavcan.primitive.scalar.Real16.1.0
;
extent 2 bytes:
1float16 value # Exactly representable integers: [-2048, +2048]
2@sealed
The readiness subscription is an optional safety feature that can be enabled
to prevent accidental arming of the drive.
If the readiness subscription is configured,
no drive command will be acted upon unless the ENGAGED
readiness command is published.
If the readiness subscription is not configured, published drive commands are accepted immediately.
setpoint_dynamics
#
Definition of zubax.physics.dynamics.DoF3rd.1.0
;
extent 16 bytes:
1# Movement along an axis [meter],[newton] or rotation about an axis [radian],[newton*meter].
2zubax.physics.kinematics.DoF3rd.1.0 kinematics
3float32 force # [newton] or [newton*meter]
4@sealed
Definition of zubax.physics.kinematics.DoF3rd.1.0
;
extent 12 bytes:
1# Movement along an axis [meter] or rotation about an axis [radian].
2DoF2nd.1.0 base
3float32 acceleration
4@sealed
Definition of zubax.physics.kinematics.DoF2nd.1.0
;
extent 8 bytes:
1# Movement along an axis [meter] or rotation about an axis [radian].
2float32 position
3float32 velocity
4@sealed
The control mode selected by this subscription depends on the contents of the message as described below. A finite value refers to an IEEE754 floating point value that is neither an infinity nor a not-a-number.
If the position value is finite, the message is ignored.
Otherwise, if the velocity value is finite, the velocity control mode is selected.
If the force value is finite, the torque/force limits are set as \(\tau_b = -\text{force}, \tau_m = \text{force}\). Otherwise, no torque/force limit is applied.
If the acceleration value is finite, the acceleration limits are set as \(\dot{\omega}_d = -\text{acceleration}, \dot{\omega}_a = \text{acceleration}\). Otherwise, the acceleration limits are defined by
drive.velocity_ctl.acceleration
.
Otherwise, if the force value is finite, the torque control mode is selected.
Otherwise, the message is ignored.
Here is a trivial example using Yakut, assuming that the device is otherwise configured, the readiness subscription is disabled, the configured velocity control strategy is INDI, and the controller’s node-ID is 125. The following command will run the drive in the velocity control mode with the target velocity of -200 \(\left[\frac{\text{radian}}{\text{second}}\right]\), acceleration profile ±10 \(\left[\frac{\text{radian}}{\text{second}^2}\right]\), and torque limit of ±0.05 \(\left[\text{newton}\times\text{meter}\right]\):
1y r 125 uavcan.sub.setpoint_dynamics.id 21 # Configure the setpoint topic arbitrarily.
2y cmd 125 restart # Restart the device for the changes to take effect.
3y pub -T 0.1 21:zubax.physics.dynamics.DoF3rd "{kinematics: {base: {position: .nan, velocity: -200}, acceleration: 10}, force: 0.05}"
Due to the low torque limit used in this example, the motor can be decelerated by hand. Once the motor is released again, it will accelerate towards the setpoint velocity slowly, following the acceleration profile setting.
The following command will activate the torque control mode with a negative torque setting. In the absence of an external force, the motor will run backward. If the motor is forced to spin forward, it will act as a generator with the specified load torque at the shaft:
1y pub -T 0.1 21:zubax.physics.dynamics.DoF3rd "{kinematics: {base: {position: .nan, velocity: .nan}}, force: -0.07}"
The following command can be used to control the drive while adjusting the velocity setpoint and the torque limit interactively using a joystick (the joystick axis numbers used in this example will require adjustment):
1y pub -T 0.1 21:zubax.physics.dynamics.DoF3rd \
2'{kinematics: {base: {position: .nan, velocity: !$ "A(1,3)*1000"}, acceleration: .nan}, force: !$ "A(1,4)*0.5"}'
setpoint_velocity
#
Definition of zubax.primitive.real16.Vector31.1.0
;
extent 62 bytes:
1float16[31] value
2@sealed
The velocity array subscription accepts the desired velocity,
in \(\left[\frac{\text{radian}}{\text{second}}\right]\) or \(\left[\frac{\text{meter}}{\text{second}}\right]\),
by fetching the array element whose index is
configured via mns.setpoint_index
.
The fetched array element shall be a finite value.
The torque limit is not used and the acceleration profile is taken from drive.velocity_ctl.acceleration
.
Here is a trivial example using Yakut, assuming that the device is otherwise configured, the readiness subscription is disabled, and the controller’s node-ID is 125:
1y r 125 uavcan.sub.setpoint_velocity.id 22 # Configure the setpoint topic arbitrarily.
2y r 125 mns.setpoint_index 3 # Configure the setpoint index.
3y cmd 125 restart # Restart the device for the changes to take effect.
4y pub -T 0.1 22:zubax.primitive.real16.Vector4 "[0, 0, 0, 200]" # Only the value at index 3 is used.
The following example publishes the setpoint as a simple uavcan.primitive.scalar.Real16
scalar:
1y r 125 mns.setpoint_index 0 # Restore the default value of the setpoint index.
2y cmd 125 restart # Restart the device for the changes to take effect.
3y pub -T 0.1 22:uavcan.primitive.scalar.real16 200 # Use a plain scalar type.
setpoint_rat_torque
#
Definition of zubax.primitive.real16.Vector31.1.0
;
extent 62 bytes:
1float16[31] value
2@sealed
The ratiometric torque array subscription accepts the desired ratiometric torque value by fetching
the array element whose index is configured via mns.setpoint_index
.
The fetched array element shall be a finite value.
Here is a trivial example using Yakut, assuming that the device is otherwise configured, the readiness subscription is disabled, and the controller’s node-ID is 125:
1y r 125 uavcan.sub.setpoint_rat_torque.id 24 # Configure the setpoint topic arbitrarily.
2y r 125 mns.setpoint_index 0 # Configure the setpoint index.
3y cmd 125 restart # Restart the device for the changes to take effect.
4y pub -T 0.1 24:uavcan.primitive.scalar.real16 0.05 # Ratiometric setpoint is 5%
setpoint_rat_torque_u9
#
Definition of zubax.primitive.natural9.Vector56.1.0
;
extent 63 bytes:
1uint9[56] value
2@sealed
Definition of zubax.primitive.natural9.Vector6.1.0
;
extent 7 bytes:
1uint9[6] value
2@sealed
The integer-typed ratiometric torque array subscription accepts the desired ratiometric torque value by fetching
the array element whose index is configured via mns.setpoint_index
.
This subscription is provided as an alternative to setpoint_rat_torque
for the benefit of bandwidth-limited
applications where large groups of motor controllers need to be controlled synchronously.
Here is a trivial example using Yakut, assuming that the device is otherwise configured, the readiness subscription is disabled, and the controller’s node-ID is 125:
1y r 125 uavcan.sub.setpoint_rat_torque_u9.id 26 # Configure the setpoint topic arbitrarily.
2y r 125 mns.setpoint_index 0 # Configure the setpoint index.
3y cmd 125 restart # Restart the device for the changes to take effect.
4y pub -T 0.1 26:uavcan.primitive.scalar.Natural16 30 # Ratiometric setpoint is: 30/511=0.0587
setpoint_rat_voltage
#
This is equivalent to setpoint_rat_torque
except that the control mode is different.
setpoint_rat_voltage_u9
#
This is equivalent to setpoint_rat_torque_u9
except that the control mode is different.
setpoint_rat_velocity_u9
#
This subject implements the ratiometric velocity control by multiplying the ratiometric value by a configurable constant and then forwarding the result to the velocity controller. For details, refer to Cyphal interface.
Via auxiliary I/O port#
The auxiliary I/O port can be configured to issue drive commands in a specific control mode. Refer to the auxiliary I/O chapter for details.
Errors#
The following runtime error codes may be reported by this command:
Error |
Reason |
---|---|
1 |
The motor has stalled more than |
An invalid parameters error may be reported if the parameters are not set correctly.
A hardware error is reported if raised by the VSI interface.
System status register#
This command is indicated via the system status register using the following schema.
{ "drive": UNSPECIFIED }
UNSPECIFIED
may be replaced with an arbitrary value.