2025-10-18
This tutorial will go through the 📄motor.h and
📄motor.cc
files line-by-line with a focus on analyzing the Motor3508
class implementation. You can find the files covered at https://github.com/illini-robomaster/iRM_Embedded_2026/blob/embedded_tutorial/shar-
ed/libraries/motor.h
https://github.com/illini-robomaster/iRM_Embedded_2026/blob/embedded_tutorial/shar-
ed/libraries/motor.cc
https://github.com/illini-robomaster/iRM_Embedded_2026/blob/embedded_tutorial/shar-
ed/bsp/bsp_can.h
You can find the example at https://github.com/illini-robomaster/iRM_Embedded_2026/blob/main/examples/mo-
tor/m3508_speed.cc
The 3508 motor uses CAN bus communication for:
Receiving: Send motor current commands from controller to motor
Feedback: Receive telemetry data from motor to controller
This should be familiar if you have read the previous tutorial. The
IDs we use are chosen for a reason. Motors send feedback on IDs 0x201–0x208
(or 0x1FF + id),
and commands are received by all motors in the group on ID
0x200
(or 0x1FF).
We will start by examining the Motor3508 class definition in 📄motor.h.
Let’s look at the Motor3508 class declaration:
/**
* @brief DJI 3508 motor class
*/
class Motor3508 : public MotorCANBase {
public:
/* constructor wrapper over MotorCANBase */
Motor3508(bsp::CAN* can, uint16_t rx_id);
/* implements data update callback */
void UpdateData(const uint8_t data[]) override final;
/* implements data printout */
void PrintData() const override final;
/* override base implementation with max current protection */
void SetOutput(int16_t val) override final;
int16_t GetCurr() const override final;
uint16_t GetTemp() const override final;
private:
volatile int16_t raw_current_get_ = 0;
volatile uint8_t raw_temperature_ = 0;
};The Motor3508 class inherits from MotorCANBase,
which provides the base functionality for our DJI motors. You should
know what inheritance is in programming languages. Here it helps us:
Reuse common functionality
Maintain consistent interfaces across different motor types (important!)
Implement different behavior for different motor types
The base class MotorCANBase
provides the following default functionality:
CAN object/CAN ID storage
Common data (theta\_,
omega\_)
Standard interface methods (GetTheta(), GetOmega(), etc.)
Take a look:
//====================================... (truncated)
// MotorCanBase(DJI Base)
//====================================... (truncated)
/**
* @brief base class for CAN motor representation
*/
class MotorCANBase : public MotorBase {
public:
/**
* @brief base constructor
*
* @param can CAN instance
* @param rx_id CAN rx id
*/
MotorCANBase(bsp::CAN* can, uint16_t rx_id);
/**
* @brief base constructor for non-DJI motors
* @param can CAN instance
* @param rx_id CAN rx id
* @param type motor type
*/
MotorCANBase(bsp::CAN* can, uint16_t rx_id, uint16_t type);
/**
* @brief update motor feedback data
* @note only used in CAN callback, do not call elsewhere
*
* @param data[] raw data bytes
*/
virtual void UpdateData(const uint8_t data[]) = 0;
/**
* @brief print out motor data
*/
virtual void PrintData() const = 0;
/**
* @brief get rotor (the cap spinning on the back of the motor) angle, in [rad]
*
* @return radian angle, range between [0, 2PI]
*/
virtual float GetTheta() const;
/**
* @brief get angle difference (target - actual), in [rad]
*
* @param target target angle, in [rad]
*
* @return angle difference, range between [-PI, PI]
*/
virtual float GetThetaDelta(const float target) const;
/**
* @brief get angular velocity, in [rad / s]
*
* @return angular velocity
*/
virtual float GetOmega() const;
/**
* @brief get angular velocity difference (target - actual), in [rad / s]
*
* @param target target angular velocity, in [rad / s]
*
* @return difference angular velocity
*/
virtual float GetOmegaDelta(const float target) const;
virtual int16_t GetCurr() const;
virtual uint16_t GetTemp() const;
virtual float GetTorque() const;
/**
* @brief transmit CAN message for setting motor outputs
*
* @param motors[] array of CAN motor pointers
* @param num_motors number of motors to transmit
*/
static void TransmitOutput(MotorCANBase* motors[], uint8_t num_motors);
/**
* @brief set ServoMotor as friend of MotorCANBase since they need to use
* many of the private parameters of MotorCANBase.
*/
friend class ServoMotor;
volatile bool connection_flag_ = false;
protected:
volatile float theta_;
volatile float omega_;
private:
bsp::CAN* can_;
uint16_t rx_id_;
uint16_t tx_id_;
};Notice the virtual
keyword, both in 3508 and the base. The virtual
keyword in the base class enables polymorphism, allowing
different motor types to be treated through the same interface while
providing different implementations. Setting something as virtual
forces all its child classes to provide an implementation. Since C++ is
strictly typed, we also have to match the typing no matter what, which
makes it useful for defining interfaces.
The override final
keywords in the Motor3508
indicate:
override:
These functions override virtual functions from the base class.
final:
No further classes can override these functions.
Notice the volatile
keyword on the member variables:
private:
volatile int16_t raw_current_get_ = 0;
volatile uint8_t raw_temperature_ = 0;The volatile
keyword tells the compiler that these variables can change unexpectedly
(e.g., from CAN interrupts). This prevents certain optimizations that
might interfere with real-time data updates.
Now let us examine the Motor3508
implementation in 📄motor.cc.
//====================================... (truncated)
// Motor3508
//====================================... (truncated)
Motor3508::Motor3508(CAN* can, uint16_t rx_id) : MotorCANBase(can, rx_id) {
can->RegisterRxCallback(rx_id, can_motor_callback, this);
}
void Motor3508::UpdateData(const uint8_t data[]) {
const int16_t raw_theta = data[0] << 8 | data[1];
const int16_t raw_omega = data[2] << 8 | data[3];
raw_current_get_ = data[4] << 8 | data[5];
raw_temperature_ = data[6];
constexpr float THETA_SCALE = 2 * PI / 8192; // digital -> rad
constexpr float OMEGA_SCALE = 2 * PI / 60; // rpm -> rad / sec
theta_ = raw_theta * THETA_SCALE;
omega_ = raw_omega * OMEGA_SCALE;
connection_flag_ = true;
}
void Motor3508::PrintData() const {
print("theta: % .4f ", GetTheta());
print("omega: % .4f ", GetOmega());
print("raw temperature: %3d ", raw_temperature_);
print("raw current get: % d \r\n", raw_current_get_);
}
void Motor3508::SetOutput(int16_t val) {
constexpr int16_t MAX_ABS_CURRENT = 14690; // ~20A
output_ = clip<int16_t>(val, -MAX_ABS_CURRENT, MAX_ABS_CURRENT);
}
int16_t Motor3508::GetCurr() const { return raw_current_get_; }
uint16_t Motor3508::GetTemp() const { return raw_temperature_; }Motor3508::Motor3508(CAN* can, uint16_t rx_id) : MotorCANBase(can, rx_id) {
can->RegisterRxCallback(rx_id, can_motor_callback, this);
}The constructor does two things:
Calls the base class constructor with a pointer to the CAN
instance (can)
and the receive ID (rx\_id).
Registers a callback function to handle incoming CAN data.
Exercise: Look through the code for RegisterRxCallback
and figure out how it is implemented. Starting point: look at what it
does in .
The RegisterRxCallback
function sets up an interrupt handler that will automatically
call can\_motor\_callback
whenever a CAN message with the specified ID is received.
static void can_motor_callback(const uint8_t data[], void* args) {
MotorCANBase* motor = reinterpret_cast<MotorCANBase*>(args);
motor->UpdateData(data);
}The concept of callbacks (or sometimes a “hook”) is extremely important for embedded systems. Imagine if everything had to poll everything else for what they need. That would be very messy and ugly.
reinterpret\_cast
converts the generic void pointer back to our MotorCANBase*
(remember what a void pointer is?).
From the motor we just recast, we call UpdateData
on the data we received.
This works for any motor type that inherits from MotorCANBase.
If you read the first tutorial, this should seem very familiar!
The UpdateData
function is where the metaphorical magic happens. We parse (decode) the
received data based on whatever was written on the datasheet of our
motor.
void Motor3508::UpdateData(const uint8_t data[]) {
const int16_t raw_theta = data[0] << 8 | data[1];
const int16_t raw_omega = data[2] << 8 | data[3];
raw_current_get_ = data[4] << 8 | data[5];
raw_temperature_ = data[6];
constexpr float THETA_SCALE = 2 * PI / 8192; // digital -> rad
constexpr float OMEGA_SCALE = 2 * PI / 60; // rpm -> rad / sec
theta_ = raw_theta * THETA_SCALE;
omega_ = raw_omega * OMEGA_SCALE;
connection_flag_ = true;
}You can find the datasheet for the C620 controller (used to control the M3508) here: https://rm-static.djicdn.com/tem/17348/RoboMaster %20C620%20Brushless%20DC%20Motor%20Speed%20Controller%20V1.01.pdf.
From examining the code, or reading the data sheet (page 17), we can figure out that the 3508 motor sends 8 bytes of data per CAN frame in the following format:
| Bytes | Decoded as | Description |
|---|---|---|
0 |
raw\_theta |
Rotor angle (upper 8 bits) |
1 |
Rotor angle (lower 8 bits) | |
2 |
raw\_omega |
Rotational speed (upper 8 bits) |
3 |
Rotational speed (lower 8 bits) | |
4 |
raw\_current\_get\_ |
Torque current (upper 8 bits) |
5 |
Torque current (lower 8 bits) | |
6 |
raw\_temperature\_ |
Motor temperature (8 bits) |
7 |
Null | Unused |
Remeber what a CAN data frame is from tutorial 2? From the datasheet,
| Data | Format/Units |
|---|---|
|
0
to 8192
(0∘ to 360∘) |
|
RPM |
|
-16384
to 16384
(−20A to 20A) |
|
∘C |
We use bit shifting operations combine individual bytes into 2-byte values:
const int16_t raw_theta = data[0] << 8 | data[1];This is equivalent to (and better than): raw\_theta = (data[0] * 256) + data[1]
data[0] << 8:
Shift the high byte left by 8 bits (multiply by 256)
| data[1]:
Combine with the low byte using bitwise OR
Let us act it out, step by step (binary $a_i, b_j \in \Z/2\Z$):
a0 |
a1 | a2 | a3 | a4 | a5 | a6 | a7 |
|---|
b0 |
b1 | b2 | b3 | b4 | b5 | b6 | b7 |
|---|
a0 |
a1 |
a2 |
a3 |
a4 |
a5 |
a6 |
a7 |
0 |
0 |
0 |
0 |
0 |
0 |
0 |
0 |
|---|
a0 |
a1 |
a2 |
a3 |
a4 |
a5 |
a6 |
a7 |
b0 |
b1 |
b2 |
b3 |
b4 |
b5 |
b6 |
b7 |
|---|
Don’t worry too much about intermediate types: C++ automatically
converts your data when using bitshift operators, and everything is
implicitly converted back to uint16\_t
on assignment. One thing we have to worry about, though, is sign
extension – you will encounter this in ECE 110, if you take it
(search it up if not). This is why we store data as uint8\_t.
The constexpr
variables define conversion factors:
constexpr float THETA_SCALE = 2 * PI / 8192; // digital -> rad
constexpr float OMEGA_SCALE = 2 * PI / 60; // rpm -> rad / secThese convert raw motor data to the units we want:
Position: 8192 encoder counts = 2π rad (one rotation)
Velocity: 1 RPM = 2π/60 rad/s
void Motor3508::SetOutput(int16_t val) {
constexpr int16_t MAX_ABS_CURRENT = 14690; // ~20A
output_ = clip<int16_t>(val, -MAX_ABS_CURRENT, MAX_ABS_CURRENT);
}This critical safety function prevents damage to the motor:
Clips the output command to ±14690 units (ignore the comment, it wasn’t changed when changing the limit).
Uses the clip
to enforce limits (notice the template – you should be familiar from the
first tutorial!).
void Motor3508::PrintData() const {
print("theta: % .4f ", GetTheta());
print("omega: % .4f ", GetOmega());
print("raw temperature: %3d ", raw_temperature_);
print("raw current get: % d \r\n", raw_current_get_);
}This function provides formatted output for debugging:
\% .4f:
Print float with 4 decimal places, signed.
\%3d:
Print integer with minimum 3 characters width.
\% d:
Print signed integer with space for positive numbers.
\textbackslash r\textbackslash n:
Both types of newlines.
Let’s examine how multiple motors are controlled simultaneously through CAN.
The TransmitOutput
static method (from MotorCANBase) sends commands to multiple motors in a
single CAN frame:
void MotorCANBase::TransmitOutput(MotorCANBase* motors[], uint8_t num_motors) {
uint8_t data[8] = {0};
RM_ASSERT_GT(num_motors, 0, "Meaningless empty can motor transmission");
RM_ASSERT_LE(num_motors, 4, "Exceeding maximum of 4 motor commands per CAN message");
for (uint8_t i = 0; i < num_motors; ++i) {
RM_ASSERT_EQ(motors[i]->tx_id_, motors[0]->tx_id_, "tx id mismatch");
RM_ASSERT_EQ(motors[i]->can_, motors[0]->can_, "can line mismatch");
const uint8_t motor_idx = (motors[i]->rx_id_ - 1) % 4;
const int16_t output = motors[i]->output_;
data[2 * motor_idx] = output >> 8;
data[2 * motor_idx + 1] = output & 0xFF;
}
motor_val = motors[0]->output_;
motors[0]->can_->Transmit(motors[0]->tx_id_, data, 8);
}This function packs up to 4 motor commands into one 8-byte CAN message:
| CAN Bytes | Motor ID | Data |
|---|---|---|
| 0-1 | Motor 1 (ID 0x201) | Current command (16-bit) |
| 2-3 | Motor 2 (ID 0x202) | Current command (16-bit) |
| 4-5 | Motor 3 (ID 0x203) | Current command (16-bit) |
| 6-7 | Motor 4 (ID 0x204) | Current command (16-bit) |
You can find this on page 15 of the manual (at the bottom of ).
The line const uint8\_t motor\_idx = (motors[i]->rx\_id\_ - 1) \% 4;
maps motor RX IDs to array indices:
Motor with RX ID 0x201
index 0 CAN bytes 0-1
Motor with RX ID 0x202
index 1 CAN bytes 2-3
Motor with RX ID 0x203
index 2 CAN bytes 4-5
Motor with RX ID 0x204
index 3 CAN bytes 6-7
The bit manipulation to pack 16-bit motor commands into bytes (The comments aren’t a part of the original file):
data[2 * motor_idx] = output >> 8; // High byte
data[2 * motor_idx + 1] = output & 0xFF; // Low byteThis is the reverse of the parsing operation we saw earlier - splitting a 16-bit value into two 8-bit bytes for transmission. Exercise: draw it out like I did in . Or at least think about it.
The MotorCANBase
constructor automatically determines the correct TX ID based on the
motor’s RX ID:
constexpr uint16_t RX1_ID_START = 0x201;
constexpr uint16_t RX2_ID_START = 0x205;
constexpr uint16_t RX3_ID_START = 0x209;
constexpr uint16_t TX1_ID = 0x200;
constexpr uint16_t TX2_ID = 0x1ff;
constexpr uint16_t TX3_ID = 0x2ff;This creates three motor groups:
Group 1: Motors 0x201–0x204
send feedback on 0x200.
Group 2: Motors 0x205–0x208
send feedback on 0x1FF.
Group 3: Motors 0x209–0x20C
send feedback on 0x2FF.
Let’s examine an example: 📄m3508\_speed.cc.
#include "bsp_print.h"
#include "cmsis_os.h"
#include "controller.h"
#include "main.h"
#include "motor.h"
#define TARGET_SPEED 30
float kp = 0;
float ki = 0;
float kd = 0;
int16_t out = 0;
bsp::CAN* can = nullptr;
control::MotorCANBase* motor = nullptr;
void RM_RTOS_Init() {
print_use_uart(&huart1);
can = new bsp::CAN(&hcan1, true);
motor = new control::Motor3508(can, 0x201);
}
void RM_RTOS_Default_Task(const void* args) {
UNUSED(args);
control::MotorCANBase* motors[] = {motor};
control::PIDController pid(20, 15, 30);
while (true) {
float diff = motor->GetOmegaDelta(TARGET_SPEED);
pid.Reinit(kp, ki, kd);
out = pid.ComputeConstrainedOutput(diff);
motor->SetOutput(out);
control::MotorCANBase::TransmitOutput(motors, 1);
motor->PrintData();
osDelay(10);
}
}You should be able to understand this. If you weren’t here for the PID lecture, wait for the next tutorial.
We analyzed the following concepts in the Motor3508 implementation:
Class inheritance and polymorphism
virtual
functions and method overriding
volatile
keyword for real-time data
constexpr
for compile-time calculations
Static methods for shared functionality
More CAN
Interrupts and callbacks
Bit manipulation for data packing/unpacking
Encoder data parsing
Current limiting for motor protection
Multi-motor coordination
This tutorial provided an analysis of the Motor3508 code implementation, demonstrating how embedded motor control systems are designed and implemented in practice. Same as previous tutorials: if there are any concepts you do not completely understand, search them up and ask an LLM for clarification.