Brushless Linear Motor
Final assembled linear brushless motor
Context
This project was carried out as part of the Travail d’Initiative Personnelle Encadrée (TIPE) during my final year of Higher school preparatory classes. In France, TIPEs are research projects that students must complete and present orally as part of the competitive exams for entrance into engineering schools.
The annual theme for the TIPE (Travaux d’Initiative Personnelle Encadrés) is set by the French Ministry of Higher Education and Research. For the 2021-2022 academic year, the theme was “Health and Prevention”. The theme serves more as a pretext than a strict guideline; since it is very broad, I decided to focus on actuators because this field particularly interests me.
Brief on Linear Brushless Motors
Brushless motors are widely used in many applications thanks to their efficiency, reliability, and low maintenance. They use electronic commutation instead of brushes to switch the current in the motor windings, knowing the rotor position through sensors or sensorless techniques. With technological progress, electronic circuits have become more powerful and affordable, which has led brushless motors to replace brushed motors in numerous applications.
Linear motors are essentially ‘unrolled’ versions of rotary motors. Instead of producing rotational motion, they generate linear motion directly. This design eliminates the need for additional mechanical components such as gears or belts, resulting in no cogging and improved precision and responsiveness.
Stator and “Rotor”
Of course, in a linear motor, there is no actual rotor. Instead, the moving part is called the forcer or mover. In the following sections, I will use the terms forcer and mover interchangeably.
Magnets can be mounted either on the stator or on the mover, but the most common configuration places the magnets on the stator and the windings on the mover. This design allows the travel length to be increased simply by extending the magnet track, without modifying the controller or its electrical characteristics. If the magnets were instead placed on the mover, the stator would require additional copper windings along the entire travel, either by duplicating the existing phases or by adding more commutation electronics. Furthermore, exposing long stretches of coils makes electromagnetic compatibility (EMC) compliance more difficult.
Iron Core vs. Coreless
Iron-core linear motors have a ferromagnetic core in the stator, which enhances the magnetic flux and increases the motor’s force density. However, they can suffer from cogging effects due to the interaction between the permanent magnets and the iron teeth, leading to non-uniform motion and bringing kind of cogging. Coreless linear motors, on the other hand, do not have an iron core in the stator. This design eliminates cogging effects, resulting in smoother motion and higher acceleration. However, coreless motors typically have lower force density compared to iron-core motors.
Number of Phases
Brushless motors can be designed with different numbers of phases, typically three. I use three-phase motors because they offer a good balance between simplicity, efficiency, and the wide availability of control hardware and algorithms. However, motors with two phases—such as small DC fans or stepper motors can also be built. Increasing the number of phases improves torque smoothness and provides greater fault tolerance, at the cost of increased complexity. I opted for a three-phase design for this project.
Sensors vs. Sensorless
Brushed DC motors rely on brushes to commutate the current in the windings, while brushless motors require the controller to know the rotor position to perform electronic commutation. This can be achieved with different methods:
Binary Hall Effect Sensors
Binary Hall effect sensors are commonly used in computer fans and cheap brushless motors. They provide 6 discrete position states per electrical revolution, which is sufficient for basic commutation. The advantage of those sensors is that they can almost directly drive MOSFETs in an H-bridge configuration, making the control circuit simple and cost-effective. However, they offer limited precision and can lead to torque ripple and noise.
Hall Effect Sensors (Analog and Encoders)
Hall-effect sensors measure the magnetic field strength and provide more precise rotor-position information than binary Hall switches. They output either an analog voltage or a digital signal proportional to the magnetic field. These sensors are usually placed along the motor’s axial direction: as the rotor magnet rotates, the magnetic field changes, and the sensors detect these variations to determine the rotor position. This position information is then used by the control algorithm to commutate the motor phases. They work even when the motor is stationary.
Sensorless Control
In sensorless control, the rotor position is estimated from the aback electromotive force (back-EMF) induced in the stator windings as the rotor moves. This approach eliminates the need for physical sensors, reducing both cost and complexity. However, sensorless control is less effective at low speeds or when starting from a standstill, because the back-EMF amplitude is very small. In a three-phase motor, the controller can measure the back-EMF on the unpowered phase. This is the method commonly used in drone motors. More advanced techniques inject a high-frequency signal into the windings and use an observer to infer rotor position. When the motor is low-speed or stationary, sensorless control can be challenging.
Optical Encoders
Optical encoders provide high-resolution position feedback by using a light source and a photodetector to read a patterned strip or disk attached to the rotor. This method offers precise position information, and works well at all speeds. However, optical encoders can be more expensive and complex to implement compared to other methods, especially hall-effect sensors.
Other Methods
Other position sensing methods includes resolvers, inductive sensors…
Theoretical Design
Magnetic Circuit
Magnet Configuration
The stator is made of two solid iron bars of 8mm x 40mm x 370mm. Each bar has 20 N52 magnets on one side, arranged in a an alternating north-south configuration. The magnets are 10mm x 10mm x 20mm each.
To choose the right pole pitch, I use a Finite Element Analysis (FEA), FEMM from David Meeker. This software is free and very easy to use for 2D magnetostatic simulations. I wanted the magnetic field to be as close as possible to a sine wave, to use easier control algorithms. After simulating different pole pitches, I found that a pole pitch of 30mm gives a good compromise between field strength and sinusoidal shape.
FEMM simulation of the magnetic field accross the stator (X, Z plane)
Plot of the magnetic field along the X axis at the center of the air gap
Copper Windings
The mover contains 3 copper windings, each made of 400 turns of 0.1mm diameter enameled copper wire. Because we use air-core windings, we need a lot of current to generate a significant magnetic field or increase the number of turns. The more turns we have, the higher the inductance of the winding, which limits the current slew rate for a given voltage. Because in my case the goal is to have a good precision at low speed, I prioritized having more turns over higher current.
To wind the coils, I designed 3D-printed mounts and used a hand drill to spin them while guiding the wire. At first, I tried counting the turns manually, but I quickly lost track. So I switched to using the weight of the wire instead: I weighed the first coil and then measured the spool’s weight before and after winding each new coil to estimate the wire length used.
This method wasn’t very precise, but it worked well enough — and I didn’t have the time to do it better anyway.
The three copper coils wound and ready to be installed
Coil Positioning
The coils pitch are determined by the pole pitch. To maximize the motor force, the coils should be placed 120 degrees apart in the stator magnetic field. Therefore, in our case the coils are spaced by 22.5mm .
Coil and magnet arrangement
Force Calculation
To prove that the motor would be able to generate force, I performed some calculations based on the magnetic field geoemetry.
Coil geometry
The force generated by a single coil in a magnetic field can be calculated using approximations on the coil geometry. The geometry of the coil will be approximated as a single rectangular loop of wire.
Simplified coil geometry model for force calculation
The coil has the following dimensions:
- Length:
- Width:
Laplace Force
- Allong AB:
- Allong BC:
- Allong CD:
- Allong DA:
Then using the symmetry of the coil and integrating along each segment, we obtain the total force on the coil:
- Along AB:
- Along CD using symmetry:
- Along BC:
- Along AD using symmetry:
Then the total force on the coil is given by:
Coil force in the z-x plane
Coil force in the z-y plane
Mover Force
The total motor force is given by the sum of the forces generated by each coil. Each coil is powered with a sinusoidal current, phase-shifted by 120 degrees.
To simplify the calculation, we will linearize the magnetic field around the center of the air gap along the Y axis.:
Along the Y axis: the field is considered constant and equal to .
Average magnetic field along the y axis
In the X axis, we approximate the field as a sine wave of amplitude B and wavelength :
For each coil the force is given by:
Where n is number of turns, k is the coil index (U, V or W) and the current in the coil.
The total motor force is then given by:
This gives us the final expression for the motor force:
where:
Current Waveforms
To maximize the motor force, the current waveforms should be sinusoidal and phase-shifted by 120 degrees.
Pseudo FOC Control
Knowing the geometry of the magnetic field, we can calculate the current waveforms needed to find the equilibrium position at a given setpoint . This gives us the current waveforms to nullify the force at the setpoint position.
Where is the peak current.
Knowing the current equilibrium values, we can know shift the currents to increase the force. This shift is nammed .
By adjusting , we can easily determine how to maximize the force for a given setpoint.
for
To control the mover force, I choosed to modulate the magnitude of the current using a coefficient . The direction of the force is controlled by the sign of .
This gives:
And similarly for and .
CAD Design
The motor parts were designed using SolidWorks. Majority of the parts were 3D-printed in PLA with a Creality Ender 3 printer.
Mover
The mover houses the three copper coils. It is designed to fit snugly between the two stator iron bars, with a small air gap to increase magnetic field strength. The mover was split into two halves to facilitate 3D printing and coil installation.
Mover design with aluminum plate for thermal management
Electronics
The mover also includes space for mounting the optical encoder, an optional accelerometer, and other sensors. It also has channel for the ribbon cable that connects the coils and electronics to the external controller.
Top view of the mover showing electronics compartments
Thermal Management
In the initial design, the mover was entirely in 3D-printed PLA. But after testing, I found that the PLA deformed under the heat generated by the coils during operation. This deformation caused misalignment and friction between the mover and stator. To solve this issue, I redesigned the mover to include aluminum plates on the sides where the coils are mounted. Aluminum mitigates the heat issue due to its high thermal conductivity, but it also adds some loss when the mover moves because of eddy currents. However, in this low-speed application, the losses are negligible compared to the benefits of improved thermal management.
Initial mover design with PLA only
Mover design with aluminum plate for thermal management
Coil channels
Wire channels were designed into the mover to route the coil wires neatly and prevent them from getting pinched or damaged during assembly.
Mover back view showing aluminum plate
Mover back view showing coil wire channels
Stator
The stator consists of two solid iron bars with neodymium magnets glued on one side. The magnets are arranged in an alternating north-south configuration to create the desired magnetic field pattern.
Stator CAD design showing magnet placement
Spacers and Mounts
Various spacers and mounts were designed to hold the stator bars in place and ensure proper alignment with the mover. These parts were also 3D-printed for ease of fabrication. Between the two stator bars, a 3D-printed spacer is placed to maintain a consistent air gap and provide mounts for endstops to calibrate the mover position. On top of the stator, they are a mount for the optical encoder strip.
Stator spacer design with endstop mounts
Complete Assembly
Complete motor assembly CAD model
Back view of the complete motor assembly CAD model
Front view of the complete motor assembly CAD model
Side view of the complete motor assembly CAD model
Electronics Design
The motor controller is based on an Arduino Mega 2560, chosen because it was what I had available at the time. For this controller, an Arduino Uno or any other microcontroller with sufficient PWM outputs could also work.
Driver Stage
The coils are driven using three half-bridge drivers. The chosen driver IC is the L6234 from STMicroelectronics. This IC integrates three half-bridges, each capable of handling up to 4A continuous current and 7 to 52V supply voltage. In this application the supply voltage is 12V.
This IC needs only a few external components to operate, like bootstrap capacitors and diodes for the high-side drivers.
The coils are connected in a delta configuration:
Delta connection of the three coils
The average caracteristics of the coils are:
- Resistance:
- Inductance:
PCB
Sadly no PCB was designed for this project. I built the driver stage on a perforated board using through-hole components. The connections were made with dupont terminals to facilitate debugging and modifications.
Driver board built on a perforated board
I would definitely design a custom PCB if I were to redo this project today. A custom PCB would improve reliability, and looks much better too!
Encoder
I opted for an optical encoder strip, commonly used in printers. The strip features alternating transparent and opaque sections, and an optical sensor detects the transitions as the carriage moves. This setup provides high-resolution position feedback, depending on the strip’s line density. I recovered this strip from an old printer. Its resolution is approximately 10 lines/mm, which yields a theoretical position resolution of about 25 µm, since we use two optical interrupters in quadrature, giving 4 states per line.
To know the direction of movement, I used two optical sensors spaced slightly apart to create a quadrature encoder setup. This configuration allows the detection of both position and direction of movement.
Optical encoder strip used for position feedback (approx 10 lines/mm)
Firmware
The firmware was written in C++ using the Arduino framework. It implements the control algorithm described earlier, along with position feedback from an optical encoder.
Global Variables
The sine function is precomputed to save Arduino resources, because trigonometric functions are not hardware-accelerated on this microcontroller.
#include <Arduino.h>
//##### pin Arduino #####
// L6234:
const int PIN_PWM_U = 46; // U = green / brown_white
const int PIN_EN_U = 47;
const int PIN_PWM_V = 44; // V = brown / blue_white
const int PIN_EN_V = 42;
const int PIN_PWM_W = 45; // W = blue / green_white
const int PIN_EN_W = 43;
// Linear optical encoder:
const int PIN_ENCODER_A = 3; // link to an interrupt
const int PIN_ENCODER_B = 4;
// Command potentiometer:
const int PIN_POT = A0;
// Limit Switch:
const int PIN_END_L = 18;
const int PIN_END_R = 19;
//##### Parameters #####
// Multitasking:
const int INTERVAL_SERIAL = 1000; // interval between two serial communication default= 1000 (ms)
const int INTERVAL_MOVE = 100; //interval between each PI compute
// Pre calculate sine:
const int N_SIN = 192; // size of pre compute sinus
const int PHASE_N90 = (3 * N_SIN) / 4;
const int PHASE_90 = N_SIN / 4;
const int PHASE_120 = N_SIN / 3;
const int PHASE_240 = (2 * N_SIN) / 3;
// Control engineering:
const int KP = 1; // Proportional coefficient
const int KI = 1; // Integral coefficient
const int KD = 0; // Deriavative coefficient
// Linear optical encoder:
const int OFFSET = 30;
const int TOTAL_LENGTH = 3400;
const int PERIOD_LENGTH = 340;
//##### Variables #####
// Pre calculate sine:
int pre_sin[192] = {128, 132, 136, 140, 144, 148, 152, 156, 160, 164, 168, 172, 176, 180, 184, 187,
191, 195, 198, 201, 205, 208, 211, 214, 217, 220, 223, 226, 228, 231, 233, 235, 237, 240, 241,
243, 245, 246, 248, 249, 250, 251, 252, 253, 253, 254, 254, 254, 255, 254, 254, 254, 253, 253,
252, 251, 250, 249, 248, 246, 245, 243, 241, 240, 237, 235, 233, 231, 228, 226, 223, 220, 217,
214, 211, 208, 205, 201, 198, 195, 191, 187, 184, 180, 176, 172, 168, 164, 160, 156, 152, 148,
144, 140, 136, 132, 128, 123, 119, 115, 111, 107, 103, 99, 95, 91, 87, 83, 79, 75, 71, 68, 64,
60, 57, 54, 50, 47, 44, 41, 38, 35, 32, 29, 27, 24, 22, 20, 18, 15, 14, 12, 10, 9, 7, 6, 5, 4,
3, 2, 2, 1, 1, 1, 1, 1, 1, 1, 2, 2, 3, 4, 5, 6, 7, 9, 10, 12, 14, 15, 18, 20, 22, 24, 27, 29,
32, 35, 38, 41, 44, 47, 50, 54, 57, 60, 64, 68, 71, 75, 79, 83, 87, 91, 95, 99, 103, 107, 111,
115, 119, 123
};
int index_U = 0; // index coil U
int index_V = index_U + PHASE_120; //index coil V 120°
int index_W = index_U + PHASE_240; //index coil W 240°
int vec = 0;
int amplitude = 0;
// Linear optical encoder:
volatile int pos = 0; //step number of linear encoder
// Multitasking:
unsigned int prev_millis_serial = 0;
unsigned int prev_millis_move = 0;
// Control engineering:
int set_point = 0;
int error = 0;
int last_error = 0;
long sum_error = 0;
float cmd = 0.0;Setup
void setup() {
Serial.begin(115200); //default= 115200
Serial.println(F("Linear Motor TIPE Antonin Pivard 2021-2022"));
attachInterrupt(digitalPinToInterrupt(PIN_ENCODER_A), encoder, CHANGE); //encoder interruption
pinMode(PIN_ENCODER_B, INPUT);
TCCR5B = TCCR5B & 0b11111000 | 0x01; // set pwm frequency to ~32kHz
pinMode(PIN_PWM_U, OUTPUT); // U = green / brown_white
pinMode(PIN_EN_U, OUTPUT);
pinMode(PIN_PWM_V, OUTPUT); // V = brown / blue_white
pinMode(PIN_EN_V, OUTPUT);
pinMode(PIN_PWM_W, OUTPUT); // W = blue / green_white
pinMode(PIN_EN_W, OUTPUT);
int v = 0;
digitalWrite(PIN_EN_U, v);// Disable coil before start control loop
digitalWrite(PIN_EN_V, v);
digitalWrite(PIN_EN_W, v);
analogWrite(PIN_PWM_U, 0);
analogWrite(PIN_PWM_V, 0);
analogWrite(PIN_PWM_W, 0);
}Move
This function output the computed command to PWM
void move(float cmd, int vec) {
index_U = int(cmd) + vec;
index_V = index_U + PHASE_120;
index_W = index_U + PHASE_240;
index_U %= N_SIN;
index_V %= N_SIN;
index_W %= N_SIN;
analogWrite(PIN_PWM_U, pre_sin[index_U]);
analogWrite(PIN_PWM_V, pre_sin[index_V]);
analogWrite(PIN_PWM_W, pre_sin[index_W]);
}Position Sensing
The optical encoder gives pulses as the mover moves. To count these pulses, I used interrupts. Interupts are triggered on both rising and falling edges of the encoder signals, and has to be as fast as possible to avoid missing pulses at high speed. Therefore, I wrote the interrupt handlers without using any Arduino functions, but directly manipulating the microcontroller registers.
volatile int pos = 0;
void encoder(void) {
// 19 cycles
if ( (PINE & 0b01000000) == (PING & 0b01000000) ) {
++pos;
} else {
--pos;
}
}Main loop
The main loop output logging data to track the behavior of the motor and the control loop responsible for command generation. In my test the control loop run at 100Hz
void loop() {
// Serial communication:
unsigned int cur_millis_serial = millis();
if (cur_millis_serial - prev_millis_serial >= INTERVAL_SERIAL) {
prev_millis_serial = cur_millis_serial;
Serial.print("set point: ");
Serial.println(set_point);
Serial.print("pos: ");
Serial.println(pos);
Serial.print("error: ");
Serial.println(error);
Serial.print("cmd: ");
Serial.println(cmd);
}
// Control loop:
unsigned int cur_millis_move = millis();
unsigned int delta_move = cur_millis_move - prev_millis_move;
if (delta_move >= INTERVAL_MOVE) {
prev_millis_move = cur_millis_move;
set_point = analogRead(PIN_POT);
set_point = map(set_point, 0, 1023, 0, 3000);
error = set_point - pos;
sum_error += error;
if (error > 0) {
vec = PHASE_N90;
} else if (error < 0) {
vec = PHASE_90;
}
cmd = error * KP + (sum_error * delta_move * KI + ((error - last_error) / (delta_move)) * KD) / 1000;
last_error = error;
move(cmd, vec);
}
}Full firmware
#include <Arduino.h>
//##### pin Arduino #####
// L6234:
const int PIN_PWM_U = 46; // U = green / brown_white
const int PIN_EN_U = 47;
const int PIN_PWM_V = 44; // V = brown / blue_white
const int PIN_EN_V = 42;
const int PIN_PWM_W = 45; // W = blue / green_white
const int PIN_EN_W = 43;
// Linear optical encoder:
const int PIN_ENCODER_A = 3; // link to an interrupt
const int PIN_ENCODER_B = 4;
// Command potentiometer:
const int PIN_POT = A0;
// Limit Switch:
const int PIN_END_L = 18;
const int PIN_END_R = 19;
//##### Parameters #####
// Multitasking:
const int INTERVAL_SERIAL = 1000; // interval between two serial communication default= 1000 (ms)
const int INTERVAL_MOVE = 100; //interval between each PI compute
// Pre calculate sin:
const int N_SIN = 192; // size of pre compute sinus
const int PHASE_N90 = (3 * N_SIN) / 4;
const int PHASE_90 = N_SIN / 4;
const int PHASE_120 = N_SIN / 3;
const int PHASE_240 = (2 * N_SIN) / 3;
// Control engineering:
const int KP = 1; // Proportional coefficient
const int KI = 1; // Integral coefficient
const int KD = 0; // Deriavative coefficient
// Linear optical encoder:
const int OFFSET = 30;
const int TOTAL_LENGTH = 3400;
const int PERIOD_LENGTH = 340;
//##### Variables #####
// Pre calculate sin:
int pre_sin[192] = {128, 132, 136, 140, 144, 148, 152, 156, 160, 164, 168, 172, 176, 180, 184, 187,
191, 195, 198, 201, 205, 208, 211, 214, 217, 220, 223, 226, 228, 231, 233, 235, 237, 240, 241,
243, 245, 246, 248, 249, 250, 251, 252, 253, 253, 254, 254, 254, 255, 254, 254, 254, 253, 253,
252, 251, 250, 249, 248, 246, 245, 243, 241, 240, 237, 235, 233, 231, 228, 226, 223, 220, 217,
214, 211, 208, 205, 201, 198, 195, 191, 187, 184, 180, 176, 172, 168, 164, 160, 156, 152, 148,
144, 140, 136, 132, 128, 123, 119, 115, 111, 107, 103, 99, 95, 91, 87, 83, 79, 75, 71, 68, 64,
60, 57, 54, 50, 47, 44, 41, 38, 35, 32, 29, 27, 24, 22, 20, 18, 15, 14, 12, 10, 9, 7, 6, 5, 4,
3, 2, 2, 1, 1, 1, 1, 1, 1, 1, 2, 2, 3, 4, 5, 6, 7, 9, 10, 12, 14, 15, 18, 20, 22, 24, 27, 29,
32, 35, 38, 41, 44, 47, 50, 54, 57, 60, 64, 68, 71, 75, 79, 83, 87, 91, 95, 99, 103, 107, 111,
115, 119, 123
};
int index_U = 0; // index coil U
int index_V = index_U + PHASE_120; //index coil V 120°
int index_W = index_U + PHASE_240; //index coil W 240°
int vec = 0;
int amplitude = 0;
// Linear optical encoder:
volatile int pos = 0; //step number of linear encoder
// Multitasking:
unsigned int prev_millis_serial = 0;
unsigned int prev_millis_move = 0;
// Control engineering:
int set_point = 0;
int error = 0;
int last_error = 0;
long sum_error = 0;
float cmd = 0.0;
void setup() {
Serial.begin(115200); //default= 115200
Serial.println(F("Linear Motor TIPE Antonin Pivard 2021-2022"));
attachInterrupt(digitalPinToInterrupt(PIN_ENCODER_A), encoder, CHANGE); //encoder interruption
pinMode(PIN_ENCODER_B, INPUT);
TCCR5B = TCCR5B & 0b11111000 | 0x01; // set pwm frequency to ~32kHz
pinMode(PIN_PWM_U, OUTPUT); // U = green / brown_white
pinMode(PIN_EN_U, OUTPUT);
pinMode(PIN_PWM_V, OUTPUT); // V = brown / blue_white
pinMode(PIN_EN_V, OUTPUT);
pinMode(PIN_PWM_W, OUTPUT); // W = blue / green_white
pinMode(PIN_EN_W, OUTPUT);
int v = 0;
digitalWrite(PIN_EN_U, v);// Disable coil before start control loop
digitalWrite(PIN_EN_V, v);
digitalWrite(PIN_EN_W, v);
analogWrite(PIN_PWM_U, 0);
analogWrite(PIN_PWM_V, 0);
analogWrite(PIN_PWM_W, 0);
}
void loop() {
// Serial communication:
unsigned int cur_millis_serial = millis();
if (cur_millis_serial - prev_millis_serial >= INTERVAL_SERIAL) {
prev_millis_serial = cur_millis_serial;
Serial.print("set point: ");
Serial.println(set_point);
Serial.print("pos: ");
Serial.println(pos);
Serial.print("error: ");
Serial.println(error);
Serial.print("cmd: ");
Serial.println(cmd);
}
// Control loop:
unsigned int cur_millis_move = millis();
unsigned int delta_move = cur_millis_move - prev_millis_move;
if (delta_move >= INTERVAL_MOVE) {
prev_millis_move = cur_millis_move;
set_point = analogRead(PIN_POT);
set_point = map(set_point, 0, 1023, 0, 3000);
error = set_point - pos;
sum_error += error;
if (error > 0) {
vec = PHASE_N90;
} else if (error < 0) {
vec = PHASE_90;
}
cmd = error * KP + (sum_error * delta_move * KI + ((error - last_error) / (delta_move)) * KD) / 1000;
last_error = error;
move(cmd, vec);
}
}
void move(float cmd, int vec) {
index_U = int(cmd) + vec;
index_V = index_U + PHASE_120;
index_W = index_U + PHASE_240;
index_U %= N_SIN;
index_V %= N_SIN;
index_W %= N_SIN;
analogWrite(PIN_PWM_U, pre_sin[index_U]);
analogWrite(PIN_PWM_V, pre_sin[index_V]);
analogWrite(PIN_PWM_W, pre_sin[index_W]);
}
void encoder() {
//19 cycles
if ((PINE & B00100000) == (PING & B00100000)) {
++pos;
} else {
--pos;
}
}Real world
Stator
To build the stator, I started by cutting two iron bars to the right dimensions. Then, I glued the neodymium magnets onto one side of each bar using a strong epoxy adhesive. I ensured that the magnets were positioned correctly with a 3D-printed spacer to maintain them.
I used solid iron bars instead of laminated ones because laminated bars are more difficult to source in small quantities.
3D-printed spacer used to position magnets during gluing
Mover
The mover was 3D-printed in PLA using a Creality Ender 3 printer. After printing, I installed the aluminum plates on the sides where the coils would be mounted to help with thermal management. Then I glued the copper coils onto the aluminum plates using epoxy adhesive, ensuring they were securely attached.
Assembled mover with coils and aluminum plates
Complete Assembly
Complete assembled linear brushless motor
CAD model of the complete motor assembly
Real world mover assembly