Encoder Wheel Test

Hello!

We chose to go for the encoder wheels from the encoder kit and have machined away the flange from the encoder wheels included in the kit. Now we are trying to determine whether this was successful and have some questions regarding the expected behavior of the encoder.

We have bonded 2 shafts with different code wheels and tested them both by modifying the example.py script from the master_board repository to spin the motor at a constant velocity and following a sine wave pattern with a pd controller. The script plots reference, actual and error values for both position and velocity. We also connected channel A and B from the encoder to an oscilloscope, using channel I (the revolutions index) as an external trigger.

These are the scripts used to generate the motor motion:
Constant Velocity
Sine wave pattern

These are our results for the two encoder wheels :

We also discovered a problem when testing the encoder. When the motor spins at a constant velocity for a certain amount of time, or a certain amount of revolutions, the motor stops before the script ends, and we need to reconnect power to the driver board in order to get the motor spinning again.

Our questions are as follows:

  1. The position tracking looks very good, but the velocity error is very high. Should the velocity error be more stable? If so, do you have any suggestions on how to fix this? We suspected that the “wobble” on the first encoder caused this, but the second encoder has a lot less “wobble” and still results in the same velocity error.

  2. Do you see anything in our results that could be caused by damage to the encoder wheels? The pulses from the encoder, measured on the oscilloscope, are of different lengths, but seem to be consistent in frequency. Again, we suspect “wobble” or some other property of the shaft rather than damage to the encoder wheel.

  3. Is this an appropriate way of testing whether the encoder wheels has been damaged? If not, do you have any suggestions on how to modify our method to be able to tell if the machining was successful?

  4. Regarding the motor stopping after a number of seconds or revolutions. Is this the expected behavior? If not, do you have any suggestions on how to fix it? We suspect some security function limiting the amount of revolutions the motor can do, as it will not do many revolutions during operation in the robot.

Sorry for the long post, we wanted to be thorough. Any help is greatly appreciated.

Best regards,
Kevin

Hello Kevin,

thanks for the plots and the videos.
I think the machining was successful and that your encoders are working fine.

The encoders are very reliable and tolerate a bit of wobbling of the codewheel.
(as long as the codewheel doesn’t touch the encoder and gets scratched)

Every time the index pulse is detected the firmware will check if the number of encoder ticks since the last index pulse is correct. If ticks were lost the card will disable itself and will switch the red led on. So if the code wheel was damaged or installed in the wrong orientation you will know immediately.

We test our codewheels the same way - just by running or torque-controlling the motors.

I don’t know the answers to your other questions (1. and 4.).

Best wishes,
Felix

Hi Kevin,

The position tracking looks very good, but the velocity error is very high. Should the velocity error be more stable? If so, do you have any suggestions on how to fix this? We suspected that the “wobble” on the first encoder caused this, but the second encoder has a lot less “wobble” and still results in the same velocity error.

I don’t have any measurements right now but some noise on the velocity is expected.

You can try to use the PD controller running on the cards. With this, you can use much higher gains as it is running at 10 khz on the cards. You find a C++ demo for this here:

Regarding the motor stopping after a number of seconds or revolutions. Is this the expected behavior? If not, do you have any suggestions on how to fix it? We suspect some security function limiting the amount of revolutions the motor can do, as it will not do many revolutions during operation in the robot.

Yes, there is a safety mechansim built in. When the position measurements overflow, the motor will stop. In your code you enable this via the call to robot_if.GetDriver(i).EnablePositionRolloverError() here:

Hope that helps.

Best,
Julian

1 Like

Hello,

Regarding the velocity error: I am not familiar with the example.py of master_board, so I’m not sure what is the expected behaviour, but when looking at the plots it seems that the position and velocity reference don’t add up. For a velocity of 200 rad/ms, the position reference should increase by that amount but it actually only increases by something around 75 rad/ms (which matches with the actually measured velocity).

Maybe there is a bug in this example script?

Best,
another Felix

Thank you all for quick and helpful replies!

Every time the index pulse is detected the firmware will check if the number of encoder ticks since the last index pulse is correct. If ticks were lost the card will disable itself and will switch the red led on.

This is perfect, we can now go forward assuming the machining was successful. Thank you!

Regarding the velocity error: I am not familiar with the example.py of master_board, so I’m not sure what is the expected behaviour, but when looking at the plots it seems that the position and velocity reference don’t add up.

You are absolutely correct. We introduced a bug when modifying the code, so that the velocity reference was miscalculated. However, after fixing this bug and verifying on the plot that the position and velocity references match up, we still see a substantial velocity error. See plot below.

You can try to use the PD controller running on the cards. With this, you can use much higher gains as it is running at 10 khz on the cards. You find a C++ demo for this here:

We were able to reduce the velocity error a little bit by messing with the kd and kp values and also by running the motor at higher speeds. The test in the original post were at about 200 rpm, below is a plot from running the motor at 1000rpm. The current gets saturated at these values, so there is probably more tuning that can be done to reduce the velocity error.

Constant 1000rpm. KD = 1, KP = 0.05

We do have a couple of follow up questions, they probably don’t fit in this topic, but since they are related to this thread I will post them here. Hope that’s okay.

Yes, there is a safety mechansim built in. When the position measurements overflow, the motor will stop. In your code you enable this via the call to robot_if.GetDriver(i).EnablePositionRolloverError() here:

  1. Is it possible to disable the rollover error in a way that allows us to run the motor at constant velocity indefinetly? If I comment out robot_if.GetDriver(i).EnablePositionRolloverError() the motor speeds up after reaching a certain position rather that stopping.

Also. I cannot figure out how to properly shut down the master board at the end of my script. I make sure the ‘robot_if.Stop()’ method gets called, but I still need to reboot the master board every time I run a new script, otherwise the motor won’t run.

The reason I am asking this is because I would like to send commands to the board inside an infinite loop and plot the motors trajectory when I stop the script. However, if I stop the script with a keyboardinterrupt, it will never reach the end, where I want to call my plot function. And if I try catching the keyboardinterrupt, the board doesn’t shut down correctly. Seems like the keyboardinterrupt is being caught somewhere else and that the proper shutdown of the master board happens there.

  1. How do I properly shut down the communication with the master board at the end of my script. Should robot_if.Stop() be enough?

You’ve been very helpful so far! Hope you have some answers to the above questions as well. If you need any more documentation to answer them, or if they belong in a different topic, please tell me.

Best regards,
Kevin

I don’t know. I don’t think we ever made tests with rotating the motor for a long time. Looking at the code for the rollover error, it doesn’t say anything either as well:

https://github.com/open-dynamic-robot-initiative/udriver_firmware/blob/master/firmware/mw_dual_motor_torque_ctrl/src/dual_motor_torque_ctrl.c#L206

This seems a problem/bug in the way you program your script. From what I know there is nothing interfering with the keyboard handling/interrupts. What you could do is run the script for N seconds, then terminate the loop and do the plotting (though I know it’s not the same than stopping the application via the keyboard).

Yes, calling robot_if.Stop() should be enough.

Out of interest: Why are you looking at spinning the motor at constant velocities and relative high speeds? For robotic applications lower speeds and keeping the motor angle in a closer range seems more common. As a demo application, this could boil down to tracking a sine motion with the motor.

Best,
Julian

Turns out I was wrong about this one. As soon as you send the SendInit package, a keyboard handler is setup. The code is here: https://github.com/open-dynamic-robot-initiative/master-board/blob/master/sdk/master_board_sdk/src/master_board_interface.cpp#L79