DC Motor Identification

Effective Moment of Inertia

The robot under development serves as a multi-purpose test bed replacing the need for a rotary motion apparatus. The rubber tire on the wheel may easily be pushed aside allowing the rim to serve as a pulley. It is possible to suspend a certain amount of weight on a string attached to the pulley to apply a torque against the shaft. The reason for relocating the tire on the wheel instead of taking it off can be found in System Modeling. In short, I reduce the effort in taking measurements by only measuring the collective parts that are critical to the model.

rotaryAparatus.jpg
rotaryApparatus.png

The experiment of discovering the moment of inertia of all the rotating parts is conducted by dropping a known weight from the pulley. The string may be loosely attached to the pulley so that it can completely fall off near its end. When the string falls off and when $\tau_{g}$ no longer exists, the pulley will decelerate and gradually stop due to the constant friction torque $\tau_{f}$. Velocity data is collected by the encoder, and the result is shown in Below.

mi.png

The graph consists of two constant angular accelerations. This change comes when the string falls off from the pulley. The constant deceleration is produced by a constant friction torque $\tau_{f}$. The acceleration torque, $\tau_{g}$, is produced by the tension in the string multiplied
by $r$, the moment arm. Friction force acts on both cases. The effective moment of inertia $J$ is a result of all the rotating parts, namely,
the rotor and reduction gears inside the motor, the wheel, and finally the shaft that connects them all together. The torque produced by the falling weight, $\tau_{g}$, can be found by analyzing the tension in the string while the angular velocity accelerates. According to the second diagram in the FBD above, two equations can be described as the following.

(1)
\begin{align} J\dot{\omega}_{accel}=\tau_{g}-\tau_{f} \end{align}
(2)
\begin{align} mg-\frac{\tau_{g}}{r}=mr\dot{\omega}_{accel} \end{align}

The relationship in the third diagram in the FBD above is,

(3)
\begin{align} J\dot{\omega}_{decel}=-\tau_{f} \end{align}

There are two equations in which I already know $\dot{\omega}_{accel}$, $\dot{\omega}_{decel}$, and $\tau_{g}$ can be obtained in Equation (2). Therefore the other two unknowns can be determined easily. Table below shows the result.

(4)
\begin{align} \left[\begin{array}{cc} \dot{\omega}_{accel} & 1\\ \dot{\omega}_{decel} & 1\end{array}\right]\left[\begin{array}{c} J\\ \tau_{f}\end{array}\right]=\left[\begin{array}{c} \tau_{g}\\ 0\end{array}\right] \end{align}
$\dot{\omega}_{accel}$ $\dot{\omega}_{decel}$ $\tau_{g}$ $\tau_{f}$ $J$
Motor (Right) 26.039 -3.496 0.0156 0.0019 0.00053

Torque Constant, PWM Frequency

FBD1motor.png

There are two fundamental equations describing the characteristics of a DC motor. The first one relates torque $\tau$ on the shaft proportional to the armature current $i$ and the second expresses the back emf voltage $e$ proportional to the shaft's rotational velocity $\omega_{enc}$, where $\omega_{enc}$ is the velocity measured by the encoder mounted
on the same frame as the DC motor.

(5)
\begin{align} \tau=Ki \end{align}
(6)
\begin{align} e=K_{e}\omega_{enc} \end{align}

The proportionality constant $K$is called the torque constant, and $K_{e}$is called back emf constant.

Assume an idealized energy transducer having no power loss in converting electric power into mechanical power

(7)
\begin{align} P=ei=\tau\omega_{enc} \end{align}

This velocity represents the shaft velocity with respect to the DC motor itself. Substituting Equation (\ref{eq:__2}) into Eq.(7) and dividing both sides by $i$ yields

(8)
\begin{align} e=K\omega_{enc} \end{align}

Thus, by comparing Eq.(8) and Eq.(6) concludes that if assuming idealized energy conversion $K_{e}$ is identical to $K$.

The robot is powered by two Lego 71427 DC motors. The FBD of the DC motor above illustrates an electrical circuit in the actuator assembly where Kirchhoff's voltage law is applied.

(9)
\begin{align} v-e-Ri-L\frac{di}{dt}=0 \end{align}

In deriving the mathematical expression for the motor, shaft viscous friction and inductance are considered negligible to simplify the model. The relative effect of the inductance is negligible compared with the mechanical motion and can be neglected. Neglecting $L$ and then substituting Eq.(5) and Eq.(8) into Eq.(9) yields

(10)
\begin{align} \tau=\frac{K}{R}v-\frac{K^{2}}{R}\omega_{enc} \end{align}

At this point It may seem like everything is solved but there are still few more problems. One is how PWM duty cycles compares to analog voltage. Oscilloscope signal data acquired from motor input did not, by any means, resemble a continuous DC analog voltage but I was able to assume the duty cycle to be roughly paired with corresponding average analog voltage by inspecting its mechanical behavior, and this probably depends highly on the motor and also the H-bridge in use.

The other problem is to choose the right PWM frequency. To find the answer to this, I carry out two distinctive experiments to characterize the motor in the best possible linear manner ensuring that the derived constants $K$ and $R$ should be as reliable as it can get.

KtApatus.jpg
speedtorque4KHz.png
speedtorque30KHz.png

This is called the torque-speed characteristics. The legend in the upper-right corner describes the PWM Duty Cycle. The supply voltage is 9V, so the average voltage for 33.3%, 55.6%, 77.8%, 100% is 3V, 5V, 7V, 9V respectively. Note that the motor torque increases in proportion to the applied voltage, but the net torque reduces as the angular velocity increases. The previous two graphs illustrate the torque-speed characteristics of the experimental data for different PWM Frequencies. The negative slope implies that the voltage-controlled DC motor has an inherent damping in its mechanical behavior.

According to the response from two different PWM frequencies, the deviation in slope becomes higher when the frequency is low, this means that each duty cycle exhibits different characteristics resulting in a non-linear characteristics. I cannot say that higher frequency is better but at least it has less deviation in slope. I chose 31.37KHz as my PWM Frequency and among the slopes I choose the 3V curve to be used for the calculation of the constants $K$ and $R$. The reason I chose the rather smaller slope is because I do not want unintended overshoots by misleading the system to interpret the motor's output to be lower than it actually is. The bottom line is I prefer latency that may cause slower behavior than overshoot that may cause instability.

PWM Freq $K_{t}$ $R$ reference curve
3.921 KHz 0.730 272.6 55.6%
31.37 KHz 1.0636 290.1 100%
31.37 KHz 0.4199 119.1 33.3%
Unless otherwise stated, the content of this page is licensed under Creative Commons Attribution-ShareAlike 3.0 License