What is the internal inductance of the controller?

I’m using an Odrive 3.6 with a Maxon EC Frameless motor (Online shop for high precise drive systems by maxon | maxon group). I believe I am getting current ripple, and want to verify this using the 3-level calculation of current ripple found at this link from Maxon (https://support.maxongroup.com/hc/en-us/articles/360005046213). The equation uses L_int, of which Maxon writes, “Do not miss the inductance of the internal motor chokes of the controller to calculate the total inductance Ltot. There are always just two of the internal chokes (phase-to-phase) active.” I’m curious what the internal inductance of the chokes on the ODrive are so that I can apply it to this equation. Pardon me if I am entirely misunderstanding Maxon’s explanation of internal inductance, but let me know!

I can’t answer your question, but which Maxon motor are you using?

I’m trying to find the actual specifications.

Hi, ODrive doesn’t have output filter inductors (chokes), so the inductance is very small, essentially 0 extra inductance from the drive. Also when they say only 2/3 phases are active that assumes 120deg block commutation, which we don’t do, we do FOC.

A quick skim of that appnote, one thing that might help is that ODrive uses Space Vector Modulation FOC, which is more advanced than they have in there, but for the purposes of the formulas it’s closest to “4 quadrant, 3-level PWM”.

2 Likes

@madcowswe Thanks so much, this is very helpful–I determined that I do not need additional motor chokes for the motor. I am running into overheating/smoking problems and thought that current ripple might be the problem because of ODrive’s relatively low frequency, but the calculation shows otherwise. I’m on a Mars Rover team that uses ODrives everywhere, so I would really appreciate your time to help me solve the following problem! :slight_smile:


INFO:
I’m using this motor: Online shop for high precise drive systems by maxon | maxon group. Number 550154. I’m also using a 56V ODrive 3.6.
Quick Specs of the motor:

Nominal current (max cont. current) = 2.78 A
Stall current = 44 A
Torque constant = 0.114 Nm/A
Terminal resistance phase to phase = 1.1 Ohms
Terminal inductance phase to phase = 0.000864 H

PROBLEM:
My problem is overheating/smoking during calibration. I’ve determined that the ODrive is supplying too much current using an oscilloscope inline with the phase power lines, as well as using the ODrive to output current_meas_phA/B/C during calibration when the motors are turning. It output a peak of around 20A, which is way above the max continuous current. It doesn’t smoke unless it’s exposed to this kind of current for many seconds. I have current_lim = 2.78 and current_lim_margin = 19.0 (see calibration below). If I lower the margin any further, it throws CURRENT_LIMIT_VIOLATION.

Thus, the question becomes, how can I decrease the actual current (not the limit) that ODrive supplies to the motor down to around 2.78A? I have several questions that are related:

  1. Should I be using MOTOR_TYPE_GIMBAL for this motor? I’m currently using MOTOR_TYPE_HIGH_CURRENT, but I’m not sure if this motor has a low enough current/high enough resistance to use MOTOR_TYPE_GIMBAL. If so, we are intending to spin the motors pretty fast, so do we need mods to the shunt resistors?

  2. By documentation, “Terminal resistance phase to phase” is 1.1 Ohms, but when I output motor.config.phase_resistance after motor calibration, I got a value of 0.22830142080783844. From my understanding, the phase resistance is directly related to the current that the ODrive thinks it should supply (through the PI gain calculation), so this calibration value may be causing it to overshoot. How do these different values reconcile?

  3. By documentation, “Terminal inductance phase to phase” is 0.000864 H, but when I output motor.config.phase_inductance after motor calibration, I got a value of 0.0001180015315185301, which is very different. I understand phase resistance to be related to the current PI gain calculation, so this calibration value may also be causing it to overshoot. How do these values reconcile?

  4. What should I set my current_control_bandwidth to? I understand it’s also related to PI gains and current calculations.

  5. What other calibration values could be causing the ODrive to calculate a high current? I need to lower the actual current the ODrive sends to the motor down to 2.78A.

  6. Could you just give my calibration values a quick check to see if they all look correct?

Thank you so much!


Calibration Values:

       if PSUChoice:
            odrv.config.enable_brake_resistor = True
            odrv.config.brake_resistance = 2.0
        else:   
            odrv.config.enable_brake_resistor = False
            odrv.config.brake_resistance = 0.0

        odrv.config.dc_bus_undervoltage_trip_level = 8.0
        odrv.config.dc_bus_overvoltage_trip_level = 56.0
        odrv.config.dc_max_positive_current = 40.0
        odrv.config.dc_max_negative_current = -20.0
        odrv.config.max_regen_current = 0
        #================================================

        #=============MOTOR CONFIGURATION================
        axis.motor.config.pole_pairs = 7
       
        axis.motor.config.resistance_calib_max_voltage = 5.0
        
        axis.motor.config.motor_type = MOTOR_TYPE_HIGH_CURRENT      
        axis.motor.config.current_lim_margin = 19.0
        axis.motor.config.current_control_bandwidth = 1000
        axis.motor.config.current_lim = 2.78
        axis.motor.config.torque_constant = 0.114
        #================================================

        #================ENCODER CONFIGURATION====================
        axis.encoder.config.mode = ENCODER_MODE_HALL
        axis.encoder.config.cpr = 42
        axis.encoder.config.use_index = False
        axis.encoder.config.use_index_offset = False

        axis.encoder.config.calib_scan_distance = 2 * pi * (axis.motor.config.pole_pairs)
        axis.encoder.config.bandwidth = 350
        axis.motor.config.calibration_current = 2.78

        axis.config.calibration_lockin.current = 20
        axis.config.calibration_lockin.ramp_time = 0.4
        axis.config.calibration_lockin.ramp_distance = 3.1415927410125732
        axis.config.calibration_lockin.accel = 10
        axis.config.calibration_lockin.vel = 20

        axis.controller.config.vel_limit = 10
        
        axis.controller.config.pos_gain = 1
        axis.controller.config.vel_gain = \
            0.02 * axis.motor.config.torque_constant * axis.encoder.config.cpr
        axis.controller.config.vel_integrator_gain = \
            0.1 * axis.motor.config.torque_constant * axis.encoder.config.cpr
        
        # axis.trap_traj.config.vel_limit = 30
        axis.trap_traj.config.accel_limit = 2
        axis.trap_traj.config.decel_limit = 2

        axis.controller.config.input_mode = INPUT_MODE_PASSTHROUGH
        axis.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL

This will try to send 20A in the motor during encoder offset calibration. Try setting this to 2.78A as well.

2 Likes