CyberGear Host Computer User Manual
Xiaomi CyberGear Micro Motor Module Host Computer User Manual

1.Motor wiring diagram
1.1 Main wiring diagram

1.2 USB-to-CAN module wiring diagram

2. Debugger User Guide
2.1 Hardware Configuration
The joint motor uses CAN communication, with two communication lines. It is connected to the debugger via a CAN-to-USB tool. The debugger requires the CH340 driver to be installed in advance and operates in AT mode by default.
Please note that our debugger is developed specifically for a particular CAN-to-USB tool. Therefore, you must use our recommended serial port tool for debugging. If you wish to port it to other debugger platforms, please refer to Chapter 3 of the manual for development.
The recommended CAN-to-USB tool is the USB-CAN module from YourCee. The corresponding serial protocol uses a frame header of 41 54 and a frame tail of 0D 0A.
2.2 Debugger Interface and Description

Mainly includes:
A. Module Selection
- Device Module
- Configuration Module
- Analysis Module
- Help Module
B. Submodule Selection
- Device Module includes:
- Connect or disconnect motor device
- Motor device information
- Motor encoder calibration
- Modify motor CAN ID
- Set motor mechanical zero position
- Motor program upgrade
- Configuration Module includes:
- Parameter table – view and modify motor parameters
- Upload parameters – upload parameters from motor to parameter table
- Download parameters – download parameters from parameter table to motor
- Export parameters – download parameter table data to local storage
- Restore factory settings – restore parameter table to factory defaults
- Clear warning – clear motor errors (e.g., overtemperature, etc.)
- Analysis Module includes:
- Oscilloscope – view parameter variation curves over time
- Frequency – adjust data refresh rate
- Channel – select which data to display
- Start/Stop plotting
- Export waveform data to local storage
- Help Module includes:
- User Manual – open the instruction manual
- About – view software information
C. Motor Information Query
- Device information
- Parameter table information
D. Data Bar
- Log Information
- Communication Log
E. Operation & Debugging Area
- Select Device
- Quick Operation Area – quickly control motor forward/reverse
- Motion Control Area – control motor operation in various modes
F. Submodule Display Area
2.3 Motor Settings
2.3.1 Motor Connection Settings

Connect the CAN-to-USB tool (install the CH340 driver; it operates in AT mode by default), select the Device Module, click the connection submodule, and choose the corresponding serial port to connect.
2.3.2 Basic Settings

- Modify the motor ID number.
- Motor magnetic encoder calibration. When the motor board and motor are reinstalled, or the motor wiring sequence is changed, the magnetic encoder calibration needs to be performed again.
- Set zero position (lost after power-off). Set the current position to 0.
- Motor program upgrade. When a motor program update is available, click the upgrade button and select the upgrade file to proceed with the upgrade.
2.3.3 Parameter Table

After successfully connecting to the motor, click the Parameter Table module under the Configuration Module. The log will display “All parameters loaded successfully,” indicating that the motor-related parameters have been successfully read. (Note: The parameter table must be configured while the motor is in standby mode. If the motor is running, the parameter table cannot be refreshed.) The interface will display the motor’s related parameters.
- Blue parameters are storage parameters inside the motor. They can be modified in the “Current Value” field following each parameter. Click Download Parameters to write the parameters from the debugger to the motor. Click Upload Parameters to upload the parameters from the motor to the debugger.
- Green parameters are observation parameters, which are acquired in real time and can be monitored live.
Note: Please do not arbitrarily change the motor’s torque limit, protection temperature, or over-temperature time. Our company assumes no legal liability for any personal injury or irreversible joint damage caused by improper operation of this product.
Parameter Table
Func Code | Name | Param Type | Access | Max | Min | Current Value (for reference) | Remarks |
0X0000 | Name | String | R/W | yyyyyyyyyyyyyy | |||
0X0001 | BarCode | String | R/W | yyyyyyyyyyyyyy | |||
0X1000 | BootCodeVersion | String | RO | 0.1.5 | |||
0X1001 | BootBuildDate | String | RO | Mar 16 2022 | |||
0X1002 | BootBuildTime | String | RO | 20:22:09 | |||
0X1003 | AppCodeVersion | String | RO | 0.1.5 | Motor program version number | ||
0X1004 | AppGitVersion | String | RO | 7b844b0fM | |||
0X1005 | AppBuildDate | String | RO | Apr 14 2022 | |||
0X1006 | AppBuildTime | String | RO | 20:30:22 | |||
0X1007 | AppCodeName | String | RO | dog_motor | |||
0X2000 | echoPara1 | uint16 | Config | 74 | 5 | 5 | |
0X2001 | echoPara2 | uint16 | Config | 74 | 5 | 5 | |
0X2002 | echoPara3 | uint16 | Config | 74 | 5 | 5 | |
0X2003 | echoPara4 | uint16 | Config | 74 | 5 | 5 | |
0X2004 | echoFreHz | uint32 | R/W | 10000 | 1 | 500 | |
0X2005 | MechOffset | float | Config | 7 | -7 | 4.619583 | Motor encoder angle offset |
0X2006 | MechPos_init | float | R/W | 50 | -50 | 4.52 | Reference angle for initial multi-turn |
0X2007 | limit_torque | float | R/W | 12 | 0 | 12 | Torque limit |
0X2008 | I_FW_MAX | float | R/W | 33 | 0 | 0 | Field-weakening current value, default 0 |
0X2009 | motor_index | uint8 | Config | 20 | 0 | 1 | Motor index, marks the joint position |
0X2010 | CAN_ID | uint8 | Config | 127 | 0 | 1 | This node ID |
0X2011 | CAN_MASTER | uint8 | Config | 127 | 0 | 0 | CAN master ID |
0X2012 | CAN_TIMEOUT | uint32 | R/W | 100000 | 0 | 0 | CAN timeout threshold, default 0 |
0X2013 | motorOverTemp | int16 | R/W | 1500 | 0 | 800 | Motor protection temperature value, temp(°C)*10 |
0X2014 | overTempTime | uint32 | R/W | 1000000 | 1000 | 20000 | Overtemperature time |
0X2015 | GearRatio | float | R/W | 64 | 1 | 7.75 | |
0X2016 | Tq_caliType | uint8 | R/W | 1 | 0 | 1 | Torque calibration method setting |
0X2017 | cur_filt_gain | float | R/W | 1 | 0 | 0.9 | |
0X2018 | cur_kp | float | R/W | 200 | 0 | 0.025 | |
0X2019 | cur_ki | float | R/W | 200 | 0 | 0.0258 | |
0X2020 | spd_kp | float | R/W | 200 | 0 | 2 | |
0X2021 | spd_ki | float | R/W | 200 | 0 | 0.021 | |
0X2022 | loc_kp | float | R/W | 200 | 0 | 30 | |
0X2023 | spd_filt_gain | float | R/W | 1 | 0 | 0.1 | |
0X2024 | limit_spd | float | R/W | 200 | 0 | 2 | |
0X2025 | limit_cur | float | R/W | 23 | 0 | 23 | |
0X3000 | timeUse0 | uint16 | RO | 5 | |||
0X3001 | timeUse1 | uint16 | RO | 0 | |||
0X3002 | timeUse2 | uint16 | RO | 10 | |||
0X3003 | timeUse3 | uint16 | RO | 0 | |||
0X3004 | encoderRaw | int16 | RO | 11396 | Magnetic encoder raw value | ||
0X3005 | mcuTemp | int16 | RO | 337 | MCU internal temperature, *10 | ||
0X3006 | motorTemp | int16 | RO | 333 | Motor NTC temperature, *10 | ||
0X3007 | vBus (mv) | uint16 | RO | 24195 | mV | Bus voltage | |
0X3008 | adc1Offset | int32 | RO | 2084 | ADC sampling channel 1 zero current offset | ||
0X3009 | adc2Offset | int32 | RO | 2084 | ADC sampling channel 2 zero current offset | ||
0X3010 | adc1Raw | uint16 | RO | 1232 | ADC raw value 1 | ||
0X3011 | adc2Raw | uint16 | RO | 1212 | ADC raw value 2 | ||
0X3012 | VBUS | float | RO | 24.195 | V | Bus voltage | |
0X3013 | cmdId | float | RO | 0 | A | Id loop command | |
0X3014 | cmdIq | float | RO | 0 | A | Iq loop command | |
0X3015 | cmdLocRef | float | RO | 0 | rad | Position loop command | |
0X3016 | cmdSpdRef | float | RO | 0 | rad/s | Speed loop command | |
0X3017 | cmdTorque | float | RO | 0 | Nm | Torque command | |
0X3018 | cmdPos | float | RO | 0 | rad | MIT protocol angle command | |
0X3019 | cmdVel | float | RO | 0 | rad/s | MIT protocol speed command | |
0X3020 | rotation | int16 | RO | 1 | Number of turns | ||
0X3021 | modPos | float | RO | 4.363409 | rad | Motor mechanical angle (without turn count) | |
0X3022 | mechPos | float | RO | 0.777679 | rad | Load-side mechanical angle (with turn count) | |
0X3023 | mechVel | float | RO | 0.036618 | rad/s | Load-side speed | |
0X3024 | elecPos | float | RO | 4.714761 | rad | Electrical angle | |
0X3025 | ia | float | RO | 0 | A | U line current | |
0X301A | ib | float | RO | 0 | A | V line current | |
0X301B | ic | float | RO | 0 | A | W line current | |
0X301C | tick | uint32 | RO | 31600 | |||
0X301D | phaseOrder | uint8 | RO | 0 | Calibration direction flag | ||
0X301E | iqf | float | RO | 0 | A | Iq filtered value | |
0X301F | boardTemp | int16 | RO | 359 | Board temperature, *10 | ||
0X3020 | iq | float | RO | 0 | A | Iq raw value | |
0X3021 | id | float | RO | 0 | A | Id raw value | |
0X3022 | faultSta | uint32 | RO | 0 | Fault status value | ||
0X3023 | warnSta | uint32 | RO | 0 | Warning status value | ||
0X3024 | drv_fault | uint16 | RO | 0 | Driver chip fault value | ||
0X3025 | drv_temp | int16 | RO | 48 | °C | Driver chip temperature | |
0X3026 | Uq | float | RO | 0 | V | Q-axis voltage | |
0X3027 | Ud | float | RO | 0 | V | D-axis voltage | |
0X3028 | dtc_u | float | RO | 0 | U phase output duty cycle | ||
0X3029 | dtc_v | float | RO | 0 | V phase output duty cycle | ||
0X3030 | dtc_w | float | RO | 0 | W phase output duty cycle | ||
0X3031 | v_bus | float | RO | 24.195 | V | Bus voltage in closed-loop | |
0X3032 | v_ref | float | RO | 0 | V | Closed-loop Vq/Vd combined voltage | |
0X3033 | torque_fdb | float | RO | 0 | Nm | Torque feedback value | |
0X3034 | rated_i | float | RO | 8 | A | Motor rated current | |
0X3035 | limit_i | float | RO | 27 | A | Motor maximum current limit |
2.3.4 Oscilloscope
This interface supports viewing the graphs generated from real-time observation data. The observable data includes motor Id/Iq current, temperature, real-time output speed, rotor (encoder) position, output position, etc.
Click the Oscilloscope module under the Analysis Module, select the appropriate parameters in the channel (refer to section 3.3.3 for parameter definitions), set the output frequency, and click Start Plotting to observe the data graph. Click Stop Plotting to stop the observation.

2.4 Control Demonstration

Jog Operation:Set the maximum speed. After clicking Run, click Jog Operation to make the motor run forward and reverse.


Control Mode Switching:In the motion mode interface, you can switch the motor control mode.
2.4.1 Zero Position Mode
Click the switch button on the right, and the motor will slowly return to the mechanical zero position.

2.4.2 Motion Control Mode
Click the switch button on the right, then set the five parameter values. Click Start or Continuous Send, and the motor will return feedback frames and run according to the target command. Click the switch button on the right again, and the motor will stop.

2.4.2 Current Mode
Manually switch to Current Mode, click the switch button on the right, then set the Iq current command value. Click Start or Continuous Send, and the motor will follow the current command. Click the switch button on the right again, and the motor will stop.
Click the switch button on the right of Control Mode, enter the amplitude and frequency for sinusoidal auto-test, then click the switch button on the right of Sinusoidal Auto-Test. The motor’s Iq (A) will run according to the set amplitude and frequency.

2.4.3 Speed Mode
Manually switch to Speed Mode, click the switch button on the right, then set the speed command value (-30~30 rad/s). Click Start or Continuous Send, and the motor will follow the speed command. Click the switch button on the right again, and the motor will stop.
Click the switch button on the right of Control Mode, enter the amplitude and frequency for sinusoidal auto-test, then click the switch button on the right of Sinusoidal Auto-Test. The motor’s speed (rad/s) will run according to the set amplitude and frequency.

2.4.4 Position Mode
Manually switch to Position Mode, click the switch button on the right, then set the position command value (rad). Click Start or Continuous Send, and the motor will follow the target position command. Click the switch button on the right again, and the motor will stop. The maximum position following speed can be modified by adjusting the speed setting.
Click the switch button on the right of Control Mode, enter the amplitude and frequency for sinusoidal auto-test, then click the switch button on the right of Sinusoidal Auto-Test. The motor’s position (rad) will run according to the set amplitude and frequency.

2.5 Firmware Update
Step 1: Click Upgrade in the Device Module and select the bin file to be burned.


Step 2: Confirm the upgrade. The motor will start updating the firmware. Once the progress is complete, the motor update is finished and it will automatically restart.
← Previous
Add link here
Next →
Add link here
On this page
- CyberGear Host Computer User Manual
- 1.Motor wiring diagram
- 1.1 Main wiring diagram
- 1.2 USB-to-CAN module wiring diagram
- 2. Debugger User Guide
- 2.1 Hardware Configuration
- 2.2 Debugger Interface and Description
- 2.3 Motor Settings
- 2.3.1 Motor Connection Settings
- 2.3.2 Basic Settings
- 2.3.3 Parameter Table
- 2.3.4 Oscilloscope
- 2.4 Control Demonstration
- 2.4.1 Zero Position Mode
- 2.4.2 Motion Control Mode
- 2.4.2 Current Mode
- 2.4.3 Speed Mode
- 2.4.4 Position Mode
- 2.5 Firmware Update