Issue with using incremental linear encoder as load encoder

We have an ODrive S1 with a D5065-270KV motor and an AMT21xB-V-OD RS485 rotary encoder. The motor is driving a linear stage through a ballscrew. The linear stage’s position is then measured with a linear incremental encoder. We configure the ODrive with the commutation encoder being the rotary encoder and the load encoder being the incremental encoder. When we go into Torque mode, the motor goes into spinout error very quickly.

The strange thing is, when we use the RS485 encoder as the load encoder, torque mode works perfectly, but when we switch to the incremental encoder as the load encoder, suddenly we get very unstable behaviour (stage is shaking) and we get spinout.

It is also useful that I communicate our settings for the following parameters:
axis0.controller.config.use_commutation_vel = False
axis0.controller.config.use_load_encoder_for_commutation_vel = False

With these parameters, how can the selection of the load encoder have an influence on Torque mode? I thought that only the commutation encoder was used to do the commutation, so I wouldn’t expect an influence.

In the end, we want to go into position control with the incremental encoder, off course, but we cannot even start the tuning when the torque mode is not even working properly.

Does anyone have an idea what the issue could be?

Update: I think I have found the issue. When setting the velocity limit too low and hitting that limit, in some way it created the unstable behaviour. Increasing the velocity limit resolved the issue.

This is an interesting issue :slight_smile:

What I think is going on here – by default, the ODrive limits torque based on the velocity and vel_limit – this comes from the load encoder: Controller — ODrive Documentation 0.6.11 documentation

I think when you’re moving the stage, the velocity is increasing/decreasing very fast, which leads to a corresponding change in torque, which then leads to a spinout error.

The velocity-based torque limiting is also dependent on vel_gain (since velocity limited torque mode is equivalent to torque limited velocity mode with vel_integrator_gain=0), so if the vel_gain is unstable, then the torque control will also be unstable.

The simplest thing here is to just set axis0.controller.config.enable_torque_mode_vel_limit to False. Raising the vel_limit as you did will also decrease the effect of torque limiting at lower speeds/torques, so that’s why your approach worked.

I’d note that since your commutation encoder is such high resolution (the AMT212-B-V-OD is a nice encoder), setting use_commutation_vel might be a good idea, especially if the “effective” resolution is higher than the linear encoder, given the linear encoder’s resolution and ballscrew pitch – especially if there’s any backlash in the system.