Encoder on gearbox shaft

Hello,
I try to install encoder (AS5047D via AB interface) on driven shaft of gearbox(14:1), for my project it will be very usuful. Motor is eX8108-105KV. Odrive 3.6, firmware 0.5.1 and latest odrivetool.
First I try to use encoder on rotor of my drive. I do init of odrive by next command sequences:

odrv0.erase_configuration()
odrv0.axis0.motor.config.current_lim = 15
odrv0.axis0.controller.config.vel_limit = 10000
odrv0.axis0.motor.config.calibration_current = 3
odrv0.config.brake_resistance = 2.0
odrv0.axis0.motor.config.pole_pairs=21
odrv0.axis0.motor.config.motor_type=MOTOR_TYPE_HIGH_CURRENT
odrv0.axis0.encoder.config.cpr = 2000
odrv0.save_configuration()
odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

work well, after I can run by

odrv0.axis0.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL
odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis0.controller.input_vel=5    

Odrive and motor is OK

after I try to install encoder on shaft of gearbox (14:1 reduce speed ration) installed in motor

odrv0.axis0.motor.config.pole_pairs=273  // 21*14
odrv0.axis0.encoder.config.calib_range=0.1 
odrv0.axis0.encoder.config.calib_scan_distance=100 
odrv0.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE

work well, after I check errors: no errors

but when I try to start

odrv0.axis0.controller.config.control_mode = CONTROL_MODE_VELOCITY_CONTROL
odrv0.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL
odrv0.axis0.controller.input_vel=0.5    

current slowly increase up to 1.5 A, but no any movements of rotor or (seldom) high vibration of motor.
After

odrv0.axis0.requested_state = AXIS_STATE_IDLE
In [164]: dump_errors(odrv0)
axis0
  axis: no error
  motor: no error
  fet_thermistor: no error
  motor_thermistor: no error
  encoder: no error
  controller: no error
axis1
  axis: no error
  motor: no error
  fet_thermistor: no error
  motor_thermistor: no error
  encoder: no error
  controller: no error

I dont know what I should tune for run motor with encoder on shaft

If you put an encoder on the gearbox, it cannot be used for commutation. You need one on the motor itself.
You can use both encoders, though! There is experimental support for dual-encoders in the latest firmware.

A commutation encoder must always align precisely with the rotor. If the ODrive does not know the exact rotor angle, then commutation will fail i.e. it will energise the wrong coils, and no torque will be produced even though the motor gets hot.
A gearbox can have a non-integer ratio between the encoder and the motor, or it can become out of alignment due to finite stiffness & backlash.

You have exactly the same issue as @madness_Hero in his thread here: AS5047D affected by external magnet?

In his case, he had set the wrong pole_pairs but forced calibration to pass by adjusting calib_range.
But the effect is the same: The motor cannot produce torque due to a commutation failure.

Thanks for fast reply
I will try to use both encoders.

There is experimental support for dual-encoders in the latest firmware.

Do you mean using 2 encoder per motor?
I would love to use hall + incremental encoder for precise velocity control of hub motor.
I’m having problem finding some more info about this topic.

Yes, I started find out info about using encoders, but unfortunately I cannot find info about it.
I tried to find out here: https://github.com/madcowswe/ODrive/branches

I think as of v0.5.1 firmware, this is included. However, it is still “experimental”, because it ties up both axes i.e. you end up with a single axis ODrive, because the ODrive has only 2 encoder inputs.

You need to configure controller.config.load_encoder_axis to be the other axis, iirc.

1 Like

Thanks for nothing that there is no documentation about this. We’ll put something together.