MD FDCAN communication#

The easiest way to communicate with MD controllers is to use a CANdle device connected to a PC. Even though we are aware some customers want to integrate the MD controllers in their product with minimal setup to reduce the costs and the system’s complexity. This manual will guide you through the process of communicating with MD actuators from your custom FDCAN-capable master controller.

Hardware requirements#

The main requirement for the host system is to be equipped with an FDCAN peripheral (either a built-in one or an external one) and an FDCAN transceiver capable of speeds up to 8Mbps. Lower maximum speed transceivers can be used as well, however for the cost of limited update rates. Depending on your custom setup you should be able to integrate a 120 ohm terminating resistor on both ends of your CAN bus.

Note

MD controllers from version 2.0 can be upgraded to software controlled termination. Please contact us for more information

Communication Structure#

The communication stack is based on a register access using two frames - register read and register write. The list of available registers can be found at the end of this chapter. All fields are little-endian - least significant byte first, and all float fields are 4 bytes long encoded in IEEE-754 standard.

Default response#

The default response is sent by the drive in case a register write operation was successful.

BYTE 0 BYTE 1-2 BYTE 3 BYTE 4-7 BYTE 8-11 BYTE 12-15 BYTE 16-19 BYTE 20-23
NAME FRAME ID QUICK STATUS MOTOR TEMPERATURE MAIN ENCODER POSITION MAIN ENCODER VELOCITY MOTOR TORQUE OUTPUT ENCODER POSITION OUTPUT ENCODER VELOCITY
TYPE uint8_t uint16_t uint8_t [*C] float [rad] float [rad/s] float [Nm] float [rad] float [rad/s]
VALUE 0x0A 0x0000 - 0xFFFF 0 - 255 - - - - -

In case the operation initiated by a frame was unsuccessful the MDxx will not respond.

Write register frame#

Write register frame is used to modify values of the user-modifiable registers. Only registers with write access can be modified.

FRAME NAME DRIVE ID LENGTH BYTE 0 [ID] BYTE 1 BYTE 2-3 BYTE 4-X BYTE X+1-X+2 BYTE X+4-X+Y
WRITE_REGISTER 10-999 X (64 max) 0x40 0x00 reg ID value reg ID value

Params:

  • regID (uint16_t) - first register ID (please see the end of this section)

  • value (uint8_t/uint16_t/uint32_t/float/char[]) - first register value to be written

  • regID (uint16_t) - second register ID (please see the end of this section)

  • value (uint8_t/uint16_t/uint32_t/float/char[]) - second register value to be written

  • … (up to 64 bytes total)

When all registers write operations succeed the drive will respond with default response.

Read Register Frame#

Read register command is used to retrieve certain register values. The actuator will respond with a frame consisting of the addresses and values of the registers issued in the master request. The master request should have the following form:

FRAME NAME DRIVE ID LENGTH BYTE 0 [ID] BYTE 1 BYTE 2-3 BYTE 4-X BYTE X+1-X+2 BYTE X+4-X+Y
READ_REGISTER 10-999 X (64 max) 0x41 0x00 reg ID 0x00 reg ID 0x00

When all read operations succeed the 0x00 fields will be filled with appropriate register data when transmitted back to master by the MDxx controller.

FRAME NAME DRIVE ID LENGTH BYTE 0 [ID] BYTE 1 BYTE 2-3 BYTE 4-X BYTE X+1-X+2 BYTE X+4-X+Y
Response to register read 10-999 X (64 max) 0x41 0x00 reg ID reg value reg ID reg value

Warning

Frame payload length must not exceed 64 bytes.

Available registers#

reg name address read/write size limits description
canId 0x001 RW uint32_t [10-2000] FDCAN bus id number
canBaudrate 0x002 RW uint32_t [1e6;2e6;5e6;8e6] FDCAN bus baudrate
canWatchdog 0x003 RW uint16_t [0-2500] FDCAN bus watchdog period in ms
canTermination 0x004 RW uint8_t [0-1] CAN termination (available upon request)
motorName 0x010 RW char[24] - motor name
motorPolePairs 0x011 RW uint32_t [2;225] motor pole pair count
motorKt 0x012 RW float >0 motor torque constant
motorKt_a 0x013 RW float - -
motorKt_b 0x014 RW float - -
motorKt_c 0x015 RW float - -
motorIMax 0x016 RW float [1 - peak controller current] maximum phase current
motorGearRatio 0x017 RW float - actuator gear ratio (ex 2:1 should be 0.5) <1 - reducer >1 - multiplier
motorTorqueBandwidth 0x018 RW uint16_t [50-2500] torque bandwidth in Hz
motorFriction 0x019 not found not found - -
motorStriction 0x01A not found not found - -
motorResistance 0x01B RO float [5mOhm-20Ohm] motor resistance in d axis
motorInductance 0x01C RO float [5nH-100mH] motor inductance in d axis
motorKV 0x01D RW uint16_t - motor KV rating [RPM/V]
motorCalibrationMode 0x01E RW uint8_t [0;1] FULL = 0, NOPPDET = 1
motorThermistorType 0x01F RW uint8_t - -
outputEncoder 0x020 RW uint8_t [0;1;2;3] NONE = 0, AS5047_CENTER = 1, AS5047_OFFAXIS = 2, MB053SFA17BENT00 = 3, CM_OFFAXIS = 4, M24B_CENTER = 5, M24B_OFFAXIS = 6
outputEncoderDir 0x021 RW float - -
outputEncoderDefaultBaud 0x022 RW uint32_t - output encoder default baudrate
outputEncoderVelocity 0x023 RO float - output encoder velocity in rad/s (calculated in a 5kHz loop)
outputEncoderPosition 0x024 RO float - output encoder position in rad (read in 5kHz loop)
outputEncoderMode 0x025 RW uint8_t [0;1;2;3;4] NONE = 0, STARTUP = 1, MOTION = 2, REPORT = 3, MAIN = 4
outputEncoderCalibrationMode 0x026 RW uint8_t [0;1] FULL = 0, DIRONLY = 1
motorPosPidKp 0x030 RW float - position PID proportional gain
motorPosPidKi 0x031 RW float - position PID integral gain
motorPosPidKd 0x032 RW float - position PID derivative gain
motorPosPidWindup 0x034 RW float - position PID integral windup limit
motorVelPidKp 0x040 RW float - velocity PID proportional gain
motorVelPidKi 0x041 RW float - velocity PID integral gain
motorVelPidKd 0x042 RW float - velocity PID derivative gain
motorVelPidWindup 0x044 RW float - velocity PID integral windup limit
motorImpPidKp 0x050 RW float - impedance PD proportional gain
motorImpPidKd 0x051 RW float - impedance PD derivative gain
mainEncoderVelocity 0x062 RO float - main encoder velocity in rad/s (calculated in a 40kHz loop)
mainEncoderPosition 0x063 RO float - main encoder position in rad (read in 40kHz loop)
motorTorque 0x064 RO float - motor output shaft torque in Nm (read in 40kHz loop)
runSaveCmd 0x080 WO uint8_t other than 0 to run save non-volatile memory
runTestMainEncoderCmd 0x081 WO uint8_t other than 0 to run runs main encoder test routine
runTestOutputEncoderCmd 0x082 WO uint8_t other than 0 to run runs output encoder test routine
runCalibrateCmd 0x083 WO uint8_t other than 0 to run runs main calibration routine
runCalibrateOutputEncoderCmd 0x084 WO uint8_t other than 0 to run runs output encoder calibration routine
runCalibratePiGains 0x085 WO uint8_t other than 0 to run runs current PI loop calibration routine
runRestoreFactoryConfig 0x087 WO uint8_t other than 0 to run reverts config to factory state
runReset 0x088 WO uint8_t other than 0 to run resets the controller
runClearWarnings 0x089 WO uint8_t other than 0 to run clears all warnings
runClearErrors 0x08A WO uint8_t other than 0 to run clears non-critical errors
runBlink 0x08B WO uint8_t other than 0 to run blinks onboard LEDs
runZero 0x08C WO uint8_t other than 0 to run sets new zero position
runCanReinit 0x08D WO uint8_t other than 0 to run reinitializes can peripheral
calOutputEncoderStdDev 0x100 RO float - output encoder test result (standard deviation)
calOutputEncoderMinE 0x101 RO float - output encoder test result (min error)
calOutputEncoderMaxE 0x102 RO float - output encoder test result (max error)
calMainEncoderStdDev 0x103 RO float - main encoder test result (standard deviation)
calMainEncoderMinE 0x104 RO float - main encoder test result (min error)
calMainEncoderMaxE 0x105 RO float - main encoder test result (max error)
positionLimitMax 0x110 RW float - maximum valid position
positionLimitMin 0x111 RW float - minimum valid position
maxTorque 0x112 RW float - maximum torque
maxVelocity 0x113 RW float - maximum velocity
maxAcceleration 0x114 RW float - maximum acceleration
maxDeceleration 0x115 RW float - maximum deceleration
profileVelocity 0x120 RW float - profile velocity
profileAcceleration 0x121 RW float - profile acceleration
profileDeceleration 0x122 RW float - profile deceleration
quickStopDeceleration 0x123 RW float - quick stop deceleration in case of a non-critical error
positionWindow 0x124 RW float - position window within position is considered to be reached
velocityWindow 0x125 RW float - velocity window within velocity is considered to be reached
motionModeCommand 0x140 WO uint8_t - commands a motion mode change: IDLE = 0x00, POSITION_PID = 0x01, VELOCITY_PID = 0x02, RAW_TORQUE = 0x03, IMPEDANCE = 0x04, POSITION_PROFILE = 0x07, VELOCITY_PROFILE = 0x08
motionModeStatus 0x141 RO uint8_t - shows the currently set motion mode
state 0x142 RW uint16_t - returns the internal state machine state of the controller
targetPosition 0x150 RW float - sets target position in rad
targetVelocity 0x151 RW float - sets target velocity in rad/s
targetTorque 0x152 RW float - sets target torque in Nm
userGpioConfiguration 0x160 RW uint8_t - 0 - OFF, 1 - AUTO-BRAKE, 2 - GPIO INPUT
userGpioState 0x161 RO uint16_t - GPIO input state
reverseDirection 0x600 RW uint8_t - used to change the direction of the main encoder when using other encoders than the onboard one. Always recalibrate after changing this setting
shuntResistance 0x700 RO float [0.001 - 0.01] Current sense resistor value. Setting this register to a value that is not coherent with the hardware may damage the controller. In this cases warranty is not respected.
buildDate 0x800 RO uint32_t - software build date
commitHash 0x801 RO char[8] - commit hash
firmwareVersion 0x802 RO uint32_t - -
hardwareVersion 0x803 RO uint8_t - -
bridgeType 0x804 RO uint8_t - type of the mosfet driver
quickStatus 0x805 RO uint16_t - quick status vector
mosfetTemperature 0x806 RO float - power stage temperature
motorTemperature 0x807 RO float - motor temperature (if thermistor is mounted)
motorShutdownTemp 0x808 RW uint8_t - temperature at which the MD series motor controller will enter IDLE mode
mainEncoderErrors 0x809 RO uint32_t - main encoder errors
outputEncoderErrors 0x80A RO uint32_t - output encoder errors
calibrationErrors 0x80B RO uint32_t - calibration errors
bridgeErrors 0x80C RO uint32_t - bridge errors
hardwareErrors 0x80D RO uint32_t - hardware errors
communicationErrors 0x80E RO uint32_t - communication errors
motionErrors 0x810 RO uint32_t - motion errors