- Background
- Deriving Dynamics Model
- State Space Control
- Manufacturing
- Determining Parameter Values
- Motor Controller Design
- Resources
- Appendix A: MATLAB Code for Deriving System Dynamics
- Appendix B: MATLAB Code for Approximating Parameters
This documentation is written to provide guidelines who’re trying to create their own pendulum model and also serve as my personal notes to organize theories I learned.
Rotary Pendulum, also known as Furuta Pendulum is often used as an example in control system theory. It has a pendulum attached to rotary arm which can be controlled directly by a motor.
The structure may be simple, but its dynamics are highly nonlinear making it harder to control.
I first came across to Furuta Pendulum in Control System Lab where we worked with the Quanser Motion System pendulum module and the TMS320F2837xD Dual-Core Microcontroller from TI. The objective of the lab was Plant modeling with Pendulum Load and develop regulator position for the arm while balancing the pendulum. After finishing the lab, I wanted to learn more and build my own pendulum model from scratch.
What seemed like a straightforward task turned out to be far more challenging than I had expected and required a wide range of skills to accomplish. It involved understanding laws of physicsl, 3D printing skils, designing the control system, and implementing BLDC motor control.
The goal of this project is to build my own Furuta pendulum model only using basic components and to understand the fundamental theories behind its operation.
This section presents the system dynamics of a pendulum using Lagrange’s method. The equations were derived using MATLAB’s Symbolic Toolbox, and the corresponding MATLAB code is provided in Appendix A.
Consider a rotational pendulum consisting of a rotating arm and a pendulum, as illustrated in Figure 1. The brushless motor (BLDC) is used to apply torque
Figure 1. Schematic of the Furuta Pendulum system.
Figure 2. Side view defining parameters.
Figure 3. Top view of the Arm and Pendulum
The center of mass of the pendulum can be expressed in the Cartesian coordinate system as follows:
By differentiating, we obtain the following velocity vector:
Note that
Kinetic energy of the motor
Kinetic energy energy of the pendulum is given by:
Total kinetic energy is:
Total potential energy is:
The Lagrangian is the difference in kinetic and potential energies:
The equations of motion are determined from Lagrangian by evaluating Euler-Lagrange equation:
In this section, we will transform the nonlinear model into a linear state-space representation and analyze its controllability and observability. Subsequently, we will implement an LQR controller to stabilize the pendulum in the inverted position and simulate the system using MATLAB.
Before proceeding, I will assume that readers have a basic understanding of state-space control. If not, I recommend watching the Control Bootcamp series by Steve Brunton [2], which provides an excellent introduction to state-space control concepts.
In the previous section, we derived the dynamic model in terms of force. However, the dynamics are nonlinear, and we need to linearize the system around a stable position. In this case, there are two stable positions: the hanging down position
We’re interested in controlling the pendulum in inverted position
We introduce state variables as following:
Since we don’t have precise measruements for mass and dimensions, we will assume certain parameters based on the 3D design. Evaluating the system’s controllability and observability before manufacturing will help in determining the appropriate model size and motor specifications later.
We have following state space system:
If we choose our input
The system is controllabe if we can place eigenvalues of
In state space model, the system is controllable if the controllability matrix
In MATLAB, the controllability can be determined using the commands rank(ctrb(A,B))
if the output matches with the number of state variables, in this case n = 4, the system is controllable.
To control the system with the input
To get angular velocity with the angular postion, we can simply differentate the position with respect to time like following:
However, differentiation in the time domain corresponds to multiplication by s in the Laplace domain, which amplifies the high-frequency noise.
In our model, I used the same approximate differentiator I used in Control System Lab where its transfer function can be described as:
This transfer function would behave as a normal differentiator for low frequencies
The state-space representation of the estimator is:
where the state-space coefficients are:
In this section, we will implement the swing-up motion using energy control. The swing-up behavior is characterized by the ratio n of the maximum acceleration of the pivot to the acceleration due to gravity [3].
In this model, I used following control law for swing up motion:
Figure 1. Furuta Pendulum Model with inverted position.
Figure 2. Close up with Rotary Arm attached to ball bearing.
Figure 3. Rotary Arm has attached to optical encoder for pendulum angle measurement.
Figure 4. Sectional analysis with xy plane, AS5600 magnetic encoder has attached to the bottom of the motor.
Figure 5. Bottom plate where usb-c break board and main controller are located.
Figure 6. Rotary Pendulum with screws.
The final model will have only three 3D-printed parts: the encoder housing, top cover, and bottom cover, while all other parts will be CNC machined. To ensure proper functionality and design validation before machining, it would be advantageous to 3D print all components prior to CNC processing and it turned out the design had design flaws that required mulitple modifications.
All parts are 3D printed using the Bambu P1S printer located in the Hive, the ECE makerspace.
Figure 7. 3D printed parts using Bambu P1S printer.
3D printing video for prototyping.
3D printing video for prototyping.
Figure 8. Painting booth in ECE maker space.
Figure 9. Painting 3d printed top cover using spray paint.
Figure 10. Lathe training & Testing
Figure 11. CNC machined parts.
Figure 12. Schematic Design of MKS ESP32 FOC Driver Board.
https://en.wikipedia.org/wiki/List_of_moments_of_inertia
| Name | Material | Mass |
Inertia |
|---|---|---|---|
| Top cover | Plastic | ||
| Encoder | Steel | ||
| Arm Mount | Aluminum 6061 | ||
| Ball bearing | Steel |
Figure 13. Simulated inertia and mass of the top cover in Fusion 360.
Figure 14. Simulated inertia and mass of the encoder in Fusion 360.
Figure 15. Simulated inertia and mass of the arm mount in Fusion 360.
Table I. Mechanical properties of parts from Fusion 360.
| Name | Material | Mass |
Inertia |
|---|---|---|---|
| Top cover | Plastic | 0.018982 | |
| Encoder | Steel | 0.016612 | |
| Arm Mount | Aluminum 6061 | 0.026025 |
Table II. Mass measurements of components.
| Name | Material | Mass |
|---|---|---|
| Top cover | Plastic | 0.0217 |
| Arm Mount | Aluminum 6061 | 0.0272 |
| Pendulum | Aluminum 6061 | 0.0128 |
| Rotray Arm | Aluminum 6061 | 0.0038 |
The inertia of fasteners, ball bearing and magnets is neglected. Despite multiple inquiries to the motor manufacturer, they were unable to provide the rotor’s inertia or mass. The measurement of the rotor’s inertia will be covered in the motor characterization section.
Previously, we successfully derived the state-space model of the system with torque as the input.
However, torque control for a BLDC motor proved to be a significant challenge in this project. Fortunately, I found an open-source FOC library called SimpleFOC [3] and a compatible controller board. Nevertheless, to ensure seamless integration and optimal performance, I needed to understand the underlying theory behind Field-Oriented Control (FOC).
For motor control, I suggest to watch Motor Control Lectures by Dave Wilson [4].
Field Oriented Control (FOC) is suitable since it enables precise control of torque and speed by decoupling the motor’s stator current into two components: torque-producing and flux-producing.
BLDC motor test with closed loop angle control.
BLDC motor test with closed loop angle control.
To control motor torque via current, the torque constant was required. I used a GM5208-12 motor, but surprisingly, the manufacturer did not include this information in the datasheet. After reaching out to inquire about it and receiving no response, I measured the torque constant myself.
The goal was to measure
Figure 12. Cordless drill attached to the motor.
Figure 13.
I’ve tested with different rpm and measured
Table III. Torque constant with different RPM.
| RPM | Torque Constant |
||
|---|---|---|---|
| 429 | 20.4 | 44.9247749 | 0.26217807 |
| 423 | 21.3 | 44.2964564 | 0.27762766 |
| 323 | 17.2 | 33.8244809 | 0.29359552 |
| 267 | 13.6 | 27.9151451 | 0.28128795 |
| 381 | 18.2 | 39.8982267 | 0.26337218 |
| 252 | 12.4 | 26.3893783 | 0.27129678 |
| 309 | 16.1 | 32.3584043 | 0.28727041 |
Torque Constant: 0.277
Figure 14. Step current input of 0.2A.
Figure 15. Motor’s rotor velocity over time with step torque input.
After applying
Figure 16. Linear regression of the velocity with 0.2A of current input.
I applied a current of 0.2A and measured the rotor velocity using an encoder. I then plotted velocity over time and performed linear regression to determine acceleration.
Once I obtained a steady acceleration, I used the formula
Table IV. Moment of Inertia of the Rotor at Various Current Levels.
| Current (A) | Torque Constant (N**·m/A) | Torque Input (N·m) | Acceleration (rad/s^2) | Inertia
(kg·**m^2) |
I’ve conducted multiple tests with varying current inputs and selected the inertia value of 0.00179584 $kg \cdot m^2$, which provided the best fit with an
In a BLDC motor, the rotor is supported by ball bearings to maintain its central position, which introduces friction. Additionally, a slip ring is used to enable 360-degree rotation while transmitting encoder signals, which also introduces additional friction.
The slip ring is attached to the motor, and the friction of both the rotor and the slip ring is measured together.
Let’s assume friction is viscous (propotional to angular speed) which leads to:
With only friction acting on the system, Newton’s second law can be applied as follows:
Move terms involving
Integrate both sides:
This yields:
The equations indicates that the slope of
After cutting the power, I measured the motor’s angular velocity as it slowed down over time. I then used Excel to perform a linear regression on $\ln(\omega)$ to analyze the decay.
Figure 17. Linear regression of ln(ω) on Excel.
As figure 17 shows, the slope of
which yields to
On the Dynamics of the Furuta Pendulum.pdf
https://build-its-inprogress.blogspot.com/search/label/Pendulum
Swinging up a pendulum by energy control.pdf
[2] Control Bootcamp by Steve Brunton.
[3] Swinging up a pendulum by energy control
[4] Teaching Old Motors New Tricks by Dave Wilson.
close, clear, clc
% Define symbolic variables
syms theta1 theta2 theta1_dot theta2_dot theta1_ddot theta2_ddot m1 m2 ...
u u2 d1 d2 L1 L2 l1 l2 I1 I2 J0 J1 J2 g real
% Position vector of the pendulum center of mass in 3D space
x_p = L1*cos(theta1) - l2*sin(theta2)*sin(theta1);
y_p = L1*sin(theta1) + l2*sin(theta2)*cos(theta1);
z_p = -l2*cos(theta2);
p = [x_p; y_p; z_p];
% Velocity vector of the pendulum center of mass in 3D space
v = diff(p, theta1)*theta1_dot + diff(p, theta2)*theta2_dot;
% Calculate v^2
v_square = v' * v;
% Kinetic energy of the motor
T0 = 0.5 * J0 * theta1_dot^2;
% Kinetic energy of the rotary arm
T1 = 0.5 * J1 * theta1_dot^2;
% Kinetic energy of the pendulum
T2 = 0.5 * J2 * theta2_dot^2 + 0.5 * m2 * v_square;
% Total kinetic energy
T = T0 + T1 + T2;
% Total potential energy, zero potential is defined at hanging-down position
U = m2*g*z_p;
% Lagrange’s equation
L = T - U;
partial_theta1_dot = diff(L, theta1_dot);
partial_theta2_dot = diff(L, theta2_dot);
partial_theta1 = diff(L, theta1);
partial_theta2 = diff(L, theta2);
% Differentiate the expression w.r.t. time
partial_theta1_dot_t = diff(partial_theta1_dot, theta1)*theta1_dot ...
+ diff(partial_theta1_dot, theta2)*theta2_dot ...
+ diff(partial_theta1_dot, theta1_dot)*theta1_ddot ...
+ diff(partial_theta1_dot, theta2_dot)*theta2_ddot;
partial_theta2_dot_t = diff(partial_theta2_dot, theta1)*theta1_dot ...
+ diff(partial_theta2_dot, theta2)*theta2_dot ...
+ diff(partial_theta2_dot, theta1_dot)*theta1_ddot ...
+ diff(partial_theta2_dot, theta2_dot)*theta2_ddot;
% Generalized forces including friction
mu1 = -d1*theta1_dot + u;
mu2 = -d2*theta2_dot;
% Lagrange equations of motion with generalized forces
eqn1 = partial_theta1_dot_t - partial_theta1 == mu1;
eqn2 = partial_theta2_dot_t - partial_theta2 == mu2;
% Solve for theta1_ddot and theta2_ddot
sol = solve([eqn1, eqn2], [theta1_ddot, theta2_ddot]);
theta1_ddot_sol = simplify(sol.theta1_ddot);
theta2_ddot_sol = simplify(sol.theta2_ddot);
% Define the state vector x and input u
x = [theta1; theta2; theta1_dot; theta2_dot];
% Define the state derivative f(x,u)
f = [theta1_dot; theta2_dot; theta1_ddot_sol; theta2_ddot_sol];
% Compute the Jacobian matrices
A = jacobian(f, x);
B = jacobian(f, u);
% Evaluate at the equilibrium point theta1=0, theta2=pi, theta1_dot=0, theta2_dot=0
eq_point = [0; pi; 0; 0];
% Substitute the equilibrium point into A and B
A_lin = subs(A, x.', eq_point.');
B_lin = subs(B, x.', eq_point.');
% Simplify the linearized matrices
A_lin = simplify(A_lin);
B_lin = simplify(B_lin);
% Linearized matrices
disp('Linearized A matrix:');
disp(A_lin);
disp('Linearized B matrix:');
disp(B_lin);close, clear, clc
g = 9.80665; % m/s^2
m1 = 0.038; % Mass of rotary arm
m2 = 0.128; % Mass of pendulum with thum screw
L1 = 0.05; % Rotary arm length from pivot to tip
l1 = 0.5*L1; % Rotary arm length from pivot to center of mass
L2 = 0.08; % Total length of pendulum
l2 = 0.5*L2; % Distance between center of mass and pivot of pendulum
J0_rotor = 1.79584e-3;
J0_cover = 1.36e-5;
J0_mount = 1.843e-5;
J0 = J0_rotor + J0_cover + J0_mount;
I1 = m1*L1^2/12; % Rotary arm moment of inertia about its center of mass
I2 = m2*L2^2/12; % Pendulum moment of inertia about center of mass
J1 = I1 + m1*l1^2; % Rotary arm moment of inertia about pivot
J2 = I2 + m2*l2^2; % Pendulum moment of inertia about pivot
% Friction coefficients are approximated
d1 = 4.554e-4;
d2 = 1e-5;
%% Define system matrices
A = [0, 0, 1, 0;
0, 0, 0, 1;
0, (L1*g*l2^2*m2^2)/(J0*J2 + J1*J2 + J2*L1^2*m2 + J0*l2^2*m2 + J1*l2^2*m2), -(d1*(m2*l2^2 + J2))/(J0*J2 + J1*J2 + J2*L1^2*m2 + J0*l2^2*m2 + J1*l2^2*m2), -(L1*d2*l2*m2)/(J0*J2 + J1*J2 + J2*L1^2*m2 + J0*l2^2*m2 + J1*l2^2*m2);
0, (g*l2*m2*(m2*L1^2 + J0 + J1))/(J0*J2 + J1*J2 + J2*L1^2*m2 + J0*l2^2*m2 + J1*l2^2*m2), -(L1*d1*l2*m2)/(J0*J2 + J1*J2 + J2*L1^2*m2 + J0*l2^2*m2 + J1*l2^2*m2), -(d2*(m2*L1^2 + J0 + J1))/(J0*J2 + J1*J2 + J2*L1^2*m2 + J0*l2^2*m2 + J1*l2^2*m2)]
B = [0; 0; (m2*l2^2 + J2)/(J0*J2 + J1*J2 + J2*L1^2*m2 + J0*l2^2*m2 + J1*l2^2*m2); (L1*l2*m2)/(J0*J2 + J1*J2 + J2*L1^2*m2 + J0*l2^2*m2 + J1*l2^2*m2)]
%% Output
C = [0 1 0 0];
D = 0;
% Build System
x0 = [0; 0.1; 0; 0];
threshold = deg2rad(15); % Threshold angle to switch LQR controller
r = [0; pi; 0; 0]; % reference position
%% LQR Controller
Q = diag([1 1 1 1]);
R = 200;
K = lqr(A,B,Q,R)




















