Choice of optical encoder

Hi

I am curious. Why did you guys choose an incremential instead of an absolute encoder? That means you always have to startup the robot from a defined position (e.g. laying on the floor).

Greetings
Yannick

Hi Yannick,

we started using the incremental encoder, because the TI Evaluation boards were made for that - the boards feature two quadrature decoders and the firmware is prepared to handle the incremental encoder input.

Most of the popular absolute encoders measure the orientation of a magnet which has to be mounted on the end of the motor shaft.
For our mechanical arrangement a codewheel which can be mounted anywhere on the motor shaft is advantageous. (screenshot)

Also in order to avoid a startup sequence you would need to have the absolute encoder on the output shaft of the module. On the motor shaft it wouldn’t help because with the 9:1 gear reduction there are 9 possible output angles when your encoder is at zero degrees.

Since we wanted to keep the complexity as low as possible we decided not to add a absolute encoder to the output shaft - instead we are using the index on the incremental encoder and a rough manual alignment of the joints to calibrate the robot at startup.

Best. Felix

1 Like

makes sense, thank you Felix!

Given that this post’s title is “Choice of optical encoder”, I would like to ask some questions related to the design choices. Although I have worked with robots before (autonomous drones) I am just starting with legged robots, for which I will appreciate your understanding if my questions are common knowledge in the area.

  • After looking at COTS encoder wheels, it is clear that as resolution increases so does price. Are there any concrete reasons to select the highest resolution encoder wheel of 5000cpr? If yes, what are these reasons?
  • What is important to measure with precision? is it the position of the shaft of the rotor, or the position of the output shaft of the module? I assume that the position of the output shaft of the module is more important since this is, under my understanding, the revolute joint in the dynamic model for which direct/inverse kynematics are solved.
  • From the previous discussion, I understand that due to the reduction ratio “here are 9 possible output angles when your encoder is at zero degrees”. Also, that there is a “rough manual alignment of the joints to calibrate the robot at startup”. Is this “rough manual alignment” used also to disambiguate the “9 possible output angles” problem described? I assume that the answer is yes, since once both the rotor shaft and the output shaft start at a known position, then the position of the output shaft could be tracked in the software. (ignoring backlash, belt stretching, etc)
  • if the answer to the previous question is yes, does this also mean that, after the manual alignment, the position of the output shaft is known with a resolution of 45,000cpr (due to the 9:1 reduction ratio)?
  • Finally, if the answer to both previous question is yes, is it really necessary to know the position of the output shaft with such high resolution? What could be those reasons?

At this point it might be clear that I am thinking if it is possible to use an encoder wheel with much lower resolution to reduce the cost and result with a robot that has the same performance as the one described in your excellent paper.

Sorry for the long post and thanks for your answers!

1 Like

Yes - we specifically selected the highest resolution optical encoder and code wheel that we could find in this size range.

It is common practice in robotics to also take the rising and falling edges of the A and B channels into account - so after that operation on the micro controller that gives us another factor of 4 resulting in 20.000 counts per revolution.

For the commutation of the brushless motors the resolution of the angular sensor seems to be less critical - from what I read resolutions around 500cpr should be sufficient.

For the behaviors that we are interested in the exact position of the output is also not that important. That is why we choose not to add another angular sensor at the output. As you have mentioned that causes errors because of the backlash and the elasticity of the timing belt transmissions that we cannot observe.

The reason why the high resolution encoder is important for us is because a high frequency and low noise velocity measurement is essential for high performance position and velocity control. Therefore we calculate and filter the angular velocity at 10kHz on the micro controller. And that is why we want to have the highest encoder resolution possible.

Depending on your application you might be able to use a lower resolution encoder.

Regarding leg calibration:
That’s right - the manual rough alignment allows us to make sure that the leg is in the expected position when we find the index. So as long as the leg is within +/-
20 degrees of the zero position it will be calibrated correctly.

1 Like

@fgrimminger Thanks for your clear answer! Now I get why that code wheel was used.

I would like to add a question. Why an adaptor was not developed instead of replacing the whole shaft ?
Reducing number of machined parts, do reduce the costs.

The original motor shaft is too short for our setup and sticks out of the top of the rotor.
If the motor shaft was relocated the flats would no longer be in the right position for the set screws. That’s why we decided to replace it.

I guess you could also design an adapter - not sure if that would be easier and cheaper.
Please let us know if you find a better solution.


Top: Original motor shaft / Bottom: Custom motor shaft