When we first started designing our robotic arm, stepper motors were the obvious choice. They are easy to find, simple to drive, and widely used in hobby projects like 3D printers. But as the design grew more ambitious, their limitations quickly surfaced:
• Missed steps: under load, they can slip without feedback, reducing reliability.
• Noise and vibration: motion is not always smooth.
• Scaling issues: wiring and size become problematic when building multiple joints.
We started looking for alternatives, and that’s where brushless DC motors (BLDCs) came in. These motors are everywhere, from drones to gimbals to electric cars, because they are compact, efficient, and capable of very smooth motion when paired with the right electronics.
Why BLDC Motors Need ControllersUnlike brushed DC motors, BLDC motors don’t spin when power is applied directly. They require a controller between the motor and the power supply.
Here’s why:
• A BLDC motor is built with three coils (stator) and permanent magnets (rotor).
• To rotate, the coils must be energized in the right sequence, creating a rotating magnetic field.
• If we apply three sinusoidal currents separated by 120°, the stator field can point in any direction.
• For maximum torque, this stator field must stay about 90° ahead of the rotor’s position a control method known as Field-Oriented Control (FOC).
To achieve this, the controller needs rotor position feedback (from a magnetic encoder or Hall sensors). That feedback closes the loop and allows the motor to generate smooth torque in the right direction.
This is the main difference: while brushed motors or steppers move blindly, BLDC motors must always be driven with feedback-aware controllers.
Our Plan: Modular BLDC Servo JointsWith this understanding, we set out to build a modular system:
• Each motor gets a compact controller board mounted right behind it.
• The board handles FOC, sensor feedback, and communication.
• All joints are connected via CAN bus, keeping wiring neat and daisy-chainable.
• At the system level, ROS 2 Control orchestrates the entire arm.
This way, every joint becomes a self-contained servo module, and the robotic arm remains scalable, clean, and future-ready.
Here’s how the hardware comes together step by step:
1. Prepare the REF_36V_220W_SLFOC board
• Start by bridging a small solder point between two pins P4.4 and P4.5
NOTE: This is required because the TLE5012B encoder uses a 3-wire SPI interface, so MOSI and MISO must be connected.
2. Solder the encoder
• Solder the TLE5012B to the board, ensuring it is precisely aligned with the motor’s magnet.
• Correct alignment is critical for accurate rotor position sensing.
NOTE: the small dot on the sensor must be on the top left position for the sensor to work.
3. Add connectors
• Solder the remaining headers for:
• Sensor SPI/IIF interface
• CAN bus connector
• Motor phase outputs (3 pins)
• Power input (2 pins)
4. Stack and link boards
• Use the onboard connector to stack the motor controller with the PCB adapter.
• Solder the 5-pin header to complete the connection.
5. Final connections
• Add the debugger pin header.
• Solder the XT30 2+2 connectors for power and CAN bus.
• We also should not forget to solder solder dots to bridge the ABC pins of the IIF interface.
NOTE: This step allows us to use IIF interface which is faster than SPI and more convenient to use inside the fast loop control system: But we will still need SPI to read the absolute position of the motor shaft.
• At this point, the boards can be daisy-chained together for multi-joint setups.
We can finally place our motor controller inside a 3D-printed case and attach it to various motors.
I tested it with the NEMA23, NEMA 17, GIMBAL MOTOR 4108, and an OUTRUNNER 5010 model, and it worked with all of them after some tweaking in the firmware[Motor Configuration]. I used a 24 V, 1 A power supply and a male XT30 2+2 connector, which allows me to easily connect my CAN cable and power the boards.
You also need to 3D-print a magnetic holder so that you can connect a Diametric magnet to the shaft; the holder length may vary depending on the shaft length of your motor.
NOTE: Diametric magnetization is when the magnetic poles are located on opposite sides or curved faces of the magnet, running across its diameter, while standard magnetization, the poles are on the flat, circular ends of the magnet.
👉 Next, we move on to the Firmware, where we adapt the Infineon REF-36 code for sensor-based FOC and add CAN protocol support for ROS 2 integration.
Firmware adaptationControl loop:
In this project, we converted the motor control from sensor-less FOC (Field Oriented Control) to sensor based FOC using an absolute position sensor. Originally, the firmware estimated the rotor position using mathematical algorithms. We modified the code to read the actual rotor position directly from an absolute sensor (TLE5012B) via SPI. This real position data is now used for the FOC algorithm, making the motor control more accurate and reliable, especially at low speeds or when starting from a standstill.
CAN Protocol Summary:
The protocol is based on Modbus Protocol in RTU mode, same used by MKS servos, for example.
Commands (first byte of CAN data):
CMD_POSITION_COMMAND (0xF5): Move to absolute position.
CMD_POSITION_READ (0x31): Read current position.
CMD_VELOCITY_READ (0x32): Read current velocity.
CMD_ENABLE_DISABLE (0xF3): Enable/disable motor.
CMD_EMERGENCY_STOP (0xF7): Emergency stop.
CMD_CALIBRATION (0xF8): Calibration.
CAN Data Format (8 bytes):
Byte 0: Command (see above)
Byte 1: Speed high byte (for position command) or enable/disable flag, etc.
Byte 2: Speed low byte (for position command).
Byte 3: Torque (for position command).
Byte 4-6: Position (24 bits, big endian).
Byte 7: CRC (sum of bytes 0-6).
Example: Set Position
CAN ID: joint ID (0x01-0x06)
Data: [0xF5, speedH, speedL, 0, posH, posM, posL, CRC]
Responses:
The Arduino/Raspberry sends ACKs or data back using the same CAN ID and command structure.
Flashing the Firmware
1. Connect the board
• Use an XMC Link to connect your board to the computer (as shown in the photo).
• Then connect your 24 V power supply to power the board.
2. Prepare the firmware
• This firmware includes CAN support and position sensor updates. We need to download or clone it.
• Also make sure you have ModusToolbox installed on your system.
3. Set up the project
• Open Eclipse for ModusToolbox.
• Create a New ModusToolbox Application and select the correct board (as shown in the setup).
• Import your cloned code into this new application.
4. Configure motor settings
• Before building and flashing the application, open:
user_under/psmm_foc/configuration
• Inside, you’ll find configuration files for 6 joints, with preset motor settings.
• If you are using a different motor, adjust one of these files or create a new configuration file specific to your motor.
5. Build and flash: Once the configuration is ready, build the project and flash it to the board.
6. GUI test
The firmware when paired with Micrium uC-Probe can be tested quite fast. We need to keep the XMC™ Link open and after downloading uC-Probe we can launch this file under GUI folder in your firmware:
1. Hardware Setup
Getstarted with Arduino IDE and XMC Boards
To start programming with XMC boards, you need to set up the Arduino IDE. Follow our step-by-step guide to get started with XMC for Arduino: documentation.
With everything prepared we’re ready to flash the first code example to the microcontroller. In order to do that you have to do the following steps in the Arduino IDE:
1.Select the right board
Once you have installed the XMC board family, you can select one of the supported boards from the menu: Tools > Board > Infineon’s XMC Microcontroller. In our case we have to choose the XMC1400 XMC2Go in order to select the correct board.
2. Flashing the Arduino
- Download the CAN communication Arduino code and the `const.h` header file from the Git repository.
- Place both files in the same folder in your Arduino IDE.
- Connect your XMC board to your computer via USB.
- Open the `.ino` file in the Arduino IDE, select the correct board and port, and
upload (flash) the code.
3. How the Arduino Code Works
- CAN Setup:
The code initializes the CAN bus at 500kbps and sets up a callback (`onReceive()`) to handle incoming CAN messages.
- onReceive():This function is called whenever a CAN message is received.
It:
- Checks the CAN ID to determine which joint the message is for.
- Parses the command in the first byte of the CAN data.
- Handles enable/disable, position, calibration, and other commands.
- Prints status and updates internal state.
- Command Functions:
- `setposition()`: Sends a position command to a joint.
- `switchonoff()`: Enables or disables a motor.
- `readPosition()`: Requests the current position of a joint.
- `calibration()`: Sends a calibration command.
- `sendCANComand()`: Packs the command and data into an 8-byte CAN frame, calculates CRC, and sends it.
- Serial Parsing:
The code listens for commands over the serial port (USB). You can send G-code or system commands (like `$EX` to enable joint X, `X1000` to move joint X to position 1000, etc.). The code parses these and translates them into CAN commands.
- printCAN():
Decodes and prints received CAN data for debugging and monitoring.
4. Testing the Arduino Setup
6. Summary
- First, set up the hardware and flash the Arduino with the provided code and header.
- Test CAN communication using the Arduino Serial Monitor and can-utils.
- Once working, you can move to ROS 2 integration using the new C++ interface.
https://github.com/yassinekallel/ROS2_BLDC
Once the motor and driver are ready, the next step is to integrate them into our robotics stack. For this we rely on ROS 2 Control, the standard framework in ROS 2 for commanding actuators.
At the highest level, ROS 2 Control works like this:
ROS 2 Controller → Controller Manager → Hardware Interface → Motor Driver → Motor
• We send position, velocity, or torque commands from ROS 2.
• ROS 2 Control translates these into hardware commands.
• The motor driver executes the command and reports back the current state.
This way, all motors can be controlled in a consistent, robot-agnostic way even if the underlying drivers use different protocols like CAN, RS485, or EtherCAT.
Our Setup
For our system we use CAN bus, since it’s robust and already supported by many BLDC drivers (including our Infineon REF_36V_220W_SLFOC boards, ODrive, and other servo modules like MKS servos).
• Each joint has its own BLDC controller board connected to the CAN bus.
• A USB-to-CAN adapter (CANable V2) links the bus to the ROS 2 PC.
• Power and phase wires go directly to the motor, while control happens via CAN.
Setting Up REF_36V_220W_SLFOC Board ROS2 Control
Before we dive into how ROS2_control works, let's first get the system set up and running.
[Raspberry Pi] ─USB─ [CANable v2] ─CAN Bus─ [Motor Controllers] ─ [BLDC Motors]
│ │
(CANH/CANL) (CAN IDs 0x01-0x06)
│ │
[120Ω Term] [120Ω Term]
Hardware Requirements
- Raspberry Pi (or PC with Ubuntu 22.04 Jammy)
- CANable v2 USB-CAN adapter
- BLDC Motors with MKS protocol controllers
- CAN Bus wiring (CANH/CANL with 120Ω termination)
Software Installation
1. Clone the Repository
https://github.com/yassinekallel/ROS2_BLDC
mkdir -p ~/refboard_ws/src
cd ~/refboard_ws/src
git clone https://github.com/yassinekallel/ROS2_BLDC.git
cd ROS2_BLDC
2. One-Command Setup (Recommended)
# Make scripts executable and install everything
chmod +x scripts/*.sh
./scripts/install_dependencies.sh
This script automatically:
- Installs ROS2 Humble (if not present)
- Installs ros2_control packages
- Sets up CAN utilities
3. Manual Setup (Alternative)
# Install ROS2 Humble
sudo apt update
sudo apt install ros-humble-desktop ros-humble-ros2-control ros-humble-ros2-controllers
# Install CAN utilities
sudo apt install can-utils
# Build the workspace
cd ~/refboard_ws
colcon build --packages-select refboard_base refboard_ros2_control
source install/setup.bash
4. CAN Interface Setup
# Connect CANable v2 to USB port, then:
sudo ip link set can0 up type can bitrate 500000
# Verify CAN interface is active
ip link show can0
5. Test the System
# Run the test script to verify everything works
cd ~/refboard_ws/src/ROS2_BLDC
./scripts/test_system.sh
Quick Motor TestBefore launching the full ROS2 system, test individual motors:
# Interactive MKS protocol testing
ros2 run refboard_base test_mks_can can0
# Try these commands:
# e 1 - Enable motor 1
# s 1 1000 - Move motor 1 to position 1000 steps
# p 1 - Read current position from motor 1
# d 1 - Disable motor 1
# quit - Exit
Launch the ROS2 Control System# Source the workspace
source ~/refboard_ws/install/setup.bash
# Launch the complete system
ros2 launch refboard_ros2_control refboard_ros2_control.launch.py can_interface:=can0
Now you should see:
- Joint state broadcaster publishing to
/joint_states
- Controllers loaded and ready to accept commands
- CAN communication established with your motors
ROS 2 Control Components
ROS2_BLDC/
├── refboard_base/ # MKS protocol implementation
│ ├── include/mks_protocol.hpp
│ ├── src/mks_protocol.cpp
│ └── test/test_mks_can.cpp
├── refboard_ros2_control/ # ROS2 control hardware interface
│ ├── src/refboard_hardware_interface.cpp
│ ├── config/refboard_controllers.yaml
│ └── launch/refboard_ros2_control.launch.py
└── scripts/ # One-command setup scripts
└── install_dependencies.sh
So your controller manager which is launched by your ROS to control node, is the part that's responsible for setting up your hardware interface which will be the part that talks to your actuator.
So you have your state interface which is the part that will be reading the different things like position, velocity and control from your actuator motor driver and you have the command interface which is the part that will be sending the commands. And in order to get that to work, you need a URDF file that describes your robot.
1. URDF / Robot Description
• In the URDF we define each joint (e.g., joint1).
• We specify which hardware interface plugin to use (for us: a CAN-based one).
• Example: define that joint1 accepts position and velocity commands.
2. Controller Configuration (YAML)
• We set which controllers to load.
• For example, a position_controllers/JointGroupPositionController if we want to send position commands.
3. Launch File
• Loads the URDF and controller config.
• Starts the controller manager, which launches both:
• The motor driver interface
• The joint state broadcaster (publishes joint_states)
4.Sending Commands
Once the system is running:
• We can publish to the command topic (e.g., /position_controller/commands).
• The driver translates this into CAN messages.
• The motor executes and ROS 2 gets back actual position/velocity via joint_states.
5.Visualization
Finally, to see the robot move in simulation:
• The joint state broadcaster publishes joint states.
• The robot state publisher uses these to update transforms.
• In RViz2, we can see the robot model moving in sync with the physical motors.
ConclusionBy combining our BLDC + FOC drivers with ROS 2 Control over CAN, we get:
• A modular servo system where each joint behaves like a standard ROS 2 actuator.
• Clean wiring (just power + CAN).
• Full compatibility with ROS 2 tools like RViz, MoveIt, and controllers.
This modular design is what allows us to scale from one joint to a complete robotic arm with minimal changes.
Comments