HebiRobotics / hebi-matlab-examples

Examples for the HEBI Robotics API for MATLAB
http://docs.hebi.us
Apache License 2.0
21 stars 15 forks source link

How is feedback volume 'deflection' calculated? #137

Closed Tom0514 closed 1 year ago

Tom0514 commented 1 year ago

Hello, everyone!

  I am doing a single joint test, the joint model is `X5-9`. But I ran into a doubt, `deflection` is not equal to the value after subtracting the equivalent motor position from the joint position. In theory, shouldn't they be the same?

Best regards, Xu.

ennerf commented 1 year ago

Deflection is calculated from two encoders that are located before and after the spring attached to the output, i.e., they are after the gear train. The motor position is the position of the motor itself, i.e., it is before the gear train.

motor -> [motor_position] -> gear train -> [deflection as offset from position] -> spring -> [position]

Tom0514 commented 1 year ago

Hello, ennerf! I did the calculations as follows:

t = log1.time;
deflection = log1.deflection;
position = log1.position;
motor_position_0 = log1.motorPosition./1742.222;
motor_position = motor_position_0 - motor_position_0(1);
figure; hold on;
plot(t, deflection, t, position - motor_position);
legend('feedbake deflection', 'calculate deflection');

The result obtained are not consistent. Is there any error in the above? Thanks!

Best regards, Xu.

Tom0514 commented 1 year ago

Then, my purpose is to realize the parameter identification of a single joint, a simplified dynamic model of a single joint is established by the Euler-Lagrangian method: formula

When identifying the friction force on the connecting rod side, I drive the joint at a constant low speed ( 0.2rad/sec ), and the joint is placed horizontally to ignore the influence of the connecting rod's gravity moment.

It can be seen from the formula that the joint output torque can be approximated as the friction torque on the connecting rod side, and at the same time, the output torque should be a positive number when rotating forward. However, the torque value fed back is as follows torque, which is not the same as my understanding.

Can you answer my doubts? Thank you so much!

ennerf commented 1 year ago

Edit: I somehow missed your code comment. It looks reasonable to me, but I'll ask someone else to double check.

The torque can be calculated using Hooke's law, i.e., effort = -stiffness * deflection. Note that the stiffness portion is negative, which may explain the sign error.

The springs in the X- and R-series actuators also have some hysteresis effects and newer models use non-linear springs, so the stiffness depends on multiple factors and is not straight forward to compute. Each spring gets calibrated independently before shipping.

You may want to take a look at the Encoders section in Scope's log-viewer for more details. In the log file below the J2_shoulder (red) joint shows a non-linear spring while J5_wrist2 (green) uses a more linear spring.

image

image

Tom0514 commented 1 year ago

Hello, thank you for your reply!

Edit: I somehow missed your code comment. It looks reasonable to me, but I'll ask someone else to double-check.

This code is just to verify deflection = theta_link - theta_motor/N, where theta_motor/N perform zero correction.

The torque can be calculated using Hooke's law, i.e., effort = -stiffness * deflection. Note that the stiffness portion is negative, which may explain the sign error.

I can get the corresponding torque value through Hooke's theorem, but it has positive and negative numbers throughout the constant positive speed operation (sorry, the expression in the previous reply is too absolute, and it has positive and negative numbers in the figure). From the point of view of the formula, it should not be positive or negative.

You may want to take a look at the Encoders section in Scope's log-viewer for more details. In the log file below the J2_shoulder (red) joint shows a non-linear spring while J5_wrist2 (green) uses a more linear spring.

I drew it and it's a linear spring. `relation`

ennerf commented 1 year ago

This code is just to verify deflection = theta_link - theta_motor/N, where theta_motor/N perform zero correction.

The deflection comes from two dedicated absolute magnetic encoders and is independent of the motor and gear train. The motor-position is based on hall sensors and is not used in the effort computation at all. Between non-linearities in the encoders, gear backlash etc., some deviation between the two values is to be expected.

I can get the corresponding torque value through Hooke's theorem, but it has positive and negative numbers throughout the constant positive speed operation (sorry, the expression in the previous reply is too absolute, and it has positive and negative numbers in the figure). From the point of view of the formula, it should not be positive or negative.

Could you send us a log file to support@hebirobotics.com? A subject line "hebi-matlab-examples#137" without any text would be enough.

Tom0514 commented 1 year ago

That is not the case. The deflection comes from two dedicated absolute magnetic encoders and is independent of the motor and gear train. The motor-position is based on hall sensors and is not used in the effort computation at all. Between non-linearities in the encoders, gear backlash etc., some deviation between the two values is to be expected.

Thank you for answering my doubts. The calculation given by the dynamic model of the joint is too ideal.

Could you send us a log file to support@hebirobotics.com? A subject line "hebi-matlab-examples#137" without any text would be enough.

OK, I'll send it right now. Thank you for your answer, much appreciated!

ennerf commented 1 year ago

The torque readings aren't great, but not out of whack for a 5 year old actuator. However, the commands are a bit weird.

You are using DIRECT_PWM, but something is making the command oscillate. Are you using some custom controller on top or maybe have safety limits set?

image

Tom0514 commented 1 year ago

Thank you so much! ennerf.

You are using DIRECT_PWM, but something is making the command oscillate. Are you using some custom controller on top or maybe have safety limits set?

There are no other controllers on the top layer, I just control the PID to achieve constant speed movement. The safety limit parameters are set as follows:

safetyParams = group.getSafetyParams();
safetyParams.positionLimitStrategy = 3;        % damped spring
safetyParams.positionMinLimit = -3*pi;
safetyParams.positionMaxLimit = +3*pi;
ennerf commented 1 year ago

There are no other controllers on the top layer, I just control the PID to achieve constant speed movement.

What PID controller are you referring to? You are using DIRECT_PWM, which bypasses all built-in PID controllers.

Please try switching to Strategy 3 or 4 (see documentation) and commanding velocity.

Tom0514 commented 1 year ago

What PID controller are you referring to? You are using DIRECT_PWM, which bypasses all built-in PID controllers.

Basically follow this example to write: ex1_custom_pid_1_controller.m The parameters used are P and D.

Please try switching to Strategy 3 or 4 (see documentation) and commanding velocity.

I saw in Choosing a Control Strategy that the Direct PWM strategy is suitable for system identification, so I used it. I also tried strategy 4 and set the parameter of effort PID to 0, but the effect was worse than strategy 1. I didn't tune the parameters of the position and velocity PID in strategy 4, because I found that even when the position and effort were set to zero, the velocity and effort still fluctuated, and I don't know if it can achieve a constant and precise speed tracking. So I use strategy 1 to track the position of the linear transformation, so as to realize the speed tracking indirectly.

ennerf commented 1 year ago

when the position and effort were set to zero, the velocity and effort still fluctuated

Did you zero the commands or the gains? The position/torque controller should be disabled, e.g.,

cmd = CommandStruct();
cmd.position = nan;
cmd.velocity = 0.2;
cmd.effort = nan;

If the targets are set to zero they will fight against the other controller.

Tom0514 commented 1 year ago

Did you zero the commands or the gains? The position/torque controller should be disabled, e.g.,

Sorry, I didn't express myself clearly. When the joint is not running, the speed and torque still fluctuate after setting the zero position in Scope. When I use strategy 4, I only send velocity commands:

cmd = CommandStruct();
cmd.velocity = 0.2;