Guide to using multiple encoders per axis (early-access)

As some of you might know @XJey5 and I have been working on an encoder refactor for some time now. We’ve gotten a request on how to currently make use of our firmware. We’ve got a relatively stable version on our devel-branch Files · devel · Project MARCH / Hardware / ODrive · GitLab and we intend to keep this branch useable and update this thread along with new changes. At the end we’d obviously like to merge it with ODrive’s firmware but that’ll still require some more time.

The current state of the firmware is such that you can use 2 incremental encoders and 2 absolute encoders. Other encoder types are not yet supported. You can choose which axis uses which encoder. Though the axis can only use 1 encoder at the time.

Important things of note:

  1. the firmware has been tested on successful motor & encoder calibration and actuation of motors in closed_loop_control. Other axis states have not yet been tested.
  2. saving the configuration of encoders has currently no use (working on it), the config will be loaded but the functionality of the encoder will not correspond to its indicated type.
  3. Always have an emergency button of some kind at the ready when actuating a motor (This should probably be the case regardless of firmware).
  4. we assume you have the firmware development tools (ODrive Firmware Developer Guide | ODrive) available and functional.
  5. we assume you use the odrivetool generated in the ODrive/tools/ directory

The next posts will feature the guide and add options.

Cheers

1 Like

Build and flash the code according to ODrive Firmware Developer Guide | ODrive

What’s new?

The first thing thing of note is that the encoders are no longer a subcomponent of the axes. A new entity has been added; the encoder_manager, which features all the encoders and their processors. The old encoders have been split into a configurable encoder and an encoder_processor which processes the sampled data and features the shadow_count, pos_estimate, vel_estimate, etc.

Configuring encoders:
Most encoder related things are managed in the encoder manager accessible with the command odrv0.encoder_manager in the odrivetool.

  1. Start by changing your encoder(s) to the desired type (incremental, absolute, etc.) using odrv#.encoder_manager.change_encoder_type( Encoder_Number, Encoder_Type, GPIO_Pin, False)
    Encoder_number : input the number of which encoder you want to change as an integer (currently 4 encoders are supported so numbers 0 up until 3 are valid).
    Encoder_Type : input which type of encoder you want to change to (0 = dummy, 1 = incremental, 259 = Orbis absolute encoder, 260 = Aksim2 absolute encoder) as an integer (the enums don’t always work properly when used as a function input argument)
    GPIO_Pin : In case of an encoder using an incremental input either 0 or 1 for using the corresponding encoder IO pins. In case of an absolute encoder input the desired GPIO pin for the chip select (ranging from 1 to 8 for hardware version 3.6).
    False: simply always input False here.
  2. Configure the encoder to your encoder’s specs in the odrv#.encoder_manager.encoder#.config
    Typically this only means adjusting the odrv#.encoder_manager.encoder#.cpr to the resolution of your encoder. (e.g. RM08IC = 4096 cpr, Orbis = 2**17 = 131072)
  3. Enable the sampling of the encoder by calling odrv#.encoder_manager.encoder#.enable()

Configure an axis for actuation:

  1. Make sure the encoder you intend to use with the motor is configured (or use and enable sensorless mode)
  2. Select the encoder you want to use with odrv#.axis#.select_encoder( Encoder_Number)
    Encoder_Number: input the number of the encoder you want to use as an integer (currently ranging from 0 till 3)
  3. Set odrv#.encoder_manager.encoder_processor#.use_axis = true for the same encoder number selected earlier
  4. Set odrv#.config.enable_brake_resistor = True (unless you want to only use regen current in that case set the limit to the appropriate number. Know what you’re doing before using regen_current and still use a braking resistor for overcurrent!)
  5. Configure your motor settings in odrv#.axis#.motor.config
    Typically this means adjusting the amount of pole_pairs and the torque constant (calculated as 8.27/the motor’s KV).
  6. Calibrate your encoder and motor using odrv#.axis#.requested_state = 3 (or use the enum AXIS_STATE_FULL_CALIBRATION_SEQUENCE).
    The ODrive should make a beep sound and start to actuate the motor so it barely moves in one direction and then switching to another.
  7. Set your controller to the desired control method in odrv#.axis#.controller.config
    For torque control this means setting odrv#.axis#.controller.config.control_mode = 1 and odrv#.axis#.controller.config.input_mode = 1
  8. Activate closed loop control using odrv#.axis#.requested_state = 8 (or the enum AXIS_STATE_CLOSED_LOOP_CONTROL)
  9. You can now actuate the joint using the appropriate input command (e.g. for torque control: odrv#.axis#.controller.input_torque or odrv#.axis#.controller.torque_setpoint

This guide is based on our internal use so if anything is unclear or you’d like to see something added please let us know.
On the same note please let us know if you encounter any problems using the firmware (such as the odrive freezing/crashing, etc.)

2 Likes

This is really interesting and something I’ve been waiting for.

I presume this is to enable efficient commutation AND accurate positional feedback on whatever end effector you have?

I understand that by placing an encoder as close to the end of the kinematic chain as possible, you improve positional accuracy as you’re essentially removing (potentially multiple) sources of backlash in the joints

But. Are there any downsides to using two encoders? My aim is to use a hall sensored motor and an AMT 10 series incremental encoder or possibly an absolute encoder on each motor for the Odrive.

Hall sensor would handle the commutation, the encoder is for position feedback. is it a sensible idea to mix and match absolute/incremental with this pre-release, and has it been tested internally like this?

Beware that Hall sensors are not good for producing fine-controlled torque at low speeds / stall, because they are too low resolution for the FOC to work properly. ODrive has to interpolate and predict the real motor position based on a PLL, and that doesn’t work well at low speeds / is completely ineffective at stall.
If you’re using a gearbox though, then probably low-speed torque fidelity isn’t an issue for you.

Hall sensors use the same inputs as incremental encoders on ODrive, so you would only be able to have one axis, using both incremental inputs. I’d recommend you have at least one absolute SPI encoder.

I have known some industrial systems that use three absolute encoders per axis. One for the motor, one for the load, and a second load encoder, geared-down so that it turns by no more than one revolution over the whole range of movement. This avoids the need for any homing sequence, so the machine can work in confined spaces where it may not be able to run a homing sequence if it were to suffer a power loss. (or sometimes the load encoder is an absolute multi-turn encoder, to achieve the same thing)

This is precisely why we started this project; the use of both an incremental and absolute encoder per axis. I should note though that the firmware is structured such that the axis uses 1 encoder and any additional encoders have their data read and processed for outside use (e.g. reading pos_estimate so an external controller can use the data).
We’ve tested the simultaneous use of an incremental and absolute encoder. They properly sample and transmit their data. We haven’t had the opportunity to test them both during the actuation of a motor though.

Hey everyone, I’ve got a hefty update on the current state of this firmware.

Let’s start with the good news:
Changed encoders and their configurations can now be saved and restored properly, saving you the hassle of doing a lot of setup everytime you reboot.
Selecting an encoder with an axis now immediately sets the encoder_processor.use_axis to true.
The odrivetool’s dump_error() function works again.
More feedback on function use and some additional errors have been added.

Now the major bad news:
After about 1 minute of actuating motors on both axis simultaneously, the firmware crashes :frowning:
The issue is being worked on but it’s rather obscure and very hard to debug so it might take a long while.

I’m happy to see the interest in this encoder refactor and we hope toensure its functionality soon.

Hello @Jorijs,

You guys have done an awesome work. I too tried to use 2 encoders (absolute and incremental) per axis and my firmware tweaking also stop functioning the axis0 after 0-2 minutes with an error called “error control deadline missed”.

Any new updates with your firmware development?

Thanks.