Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[iCubGenova09] estimated right leg wrench is different from zero when the leg is in a configuration different from the one used to calibrate #140

Open
GiulioRomualdi opened this issue Mar 1, 2022 · 31 comments

Comments

@GiulioRomualdi
Copy link
Member

GiulioRomualdi commented Mar 1, 2022

Today @isorrentino noticed that the wrench on the right leg estimated by wbd depends on the joint values.

She did the following experiment:

  1. the robot was on the pole
  2. no one was touching the robot
  3. she calibrated the FT when the joints legs were equal to 0
  4. she moved the joints leg from the motorgui
  5. Once the joint configuration is different from zero the norm of the contact force is higher than 30N

Some additional info (@isorrentino correct them if you spot an error):

  1. wbd commit: bf7d5ff
  2. we use the new ft mounted on the right leg
  3. icub-models commit: robotology/icub-models@d83ac82
  4. robots-configuration commit: ami-iit/robots-configuration@fab02fe

Here is the video of the dataset representing the experiment

measured_extenal_forces.mp4

robot_logger_device_2022_03_01_16_25_19.zip

cc @traversaro @prashanthr05 @HosameldinMohamed @S-Dafarra

@traversaro
Copy link
Member

traversaro commented Mar 2, 2022

TL;DR: I think (but I may be wrong) we are seeing the difference in behaviour of FT sensors for which over the years we developed algorithms and methods to calibrate in-situ secondary calibration matrices, see https://github.com/robotology/whole-body-estimators/tree/master/devices/wholeBodyDynamics#secondary-calibration-matrix for the related parameters (that we are currently missing). This has been sometimes called "phantom forces". If we assess that this is really the problem, it may be worth to check with francisco where the last software to compute this secondary calibration matrix is.

I think this is much easier to debug that some other strange "spiky" behaviour that you recenty also saw on the same robot. In this case, if we focus on the static case (as you are doing) the math of the problem of 3D force estimation (warning, you should have some LaTeX plugin to see the following) is just (some signs could be wrong, but I think you can get the logic):

$$ {}^{\texttt{base_link}} f^x = {}^{\texttt{base_link}} R_{\texttt{r_foot_front_ft_sensor}} f^{m}_{\texttt{r_foot_front_ft_sensor}} + {}^{\texttt{base_link}} R_{\texttt{r_foot_front_ft_sensor}} f^{m}_{\texttt{r_foot_rear_ft_sensor}} + \\ + {}^{\texttt{base_link}} R_{\texttt{r_leg_ft_sensor}} f^{m}_{\texttt{r_leg_ft_sensor}} - m_{\texttt{submodel_between_the_three_sensors}} {}^{\texttt{base_link}} g $$

Where $f^{m}_{\texttt{name_of_the_sensor}} \in \mathbb{R}^3$ is the force measured by the sensor name_of_the_sensor after removing the offset computed by wbd via calib all, ${}^{\texttt{base_link}} g \in \mathbb{R}^3$ is the gravitational acceleration and $m_{\texttt{submodel_between_the_three_sensors}} \in \mathbb{R}$ is the mass of the submodel induced by the three sensors.

If the forces measured by the feet FTs are indeed correctly small (i.e. they are quite similar to their offset) then the equation can be simplified to:
$$
{}^{\texttt{base_link}} f^x = {}^{\texttt{base_link}} R_{\texttt{r_leg_ft_sensor}} f^{m}_{\texttt{r_leg_ft_sensor}} - m_{\texttt{submodel_between_the_three_sensors}} {}^{\texttt{base_link}} g
$$
that is much easier to analyze. As a first step to debug, I would suggest to move the first joints of the leg, and then plot the $$f^{m}_{\texttt{r_leg_ft_sensor}}$$ as points in a 3D plot. If the FT sensor is working correctly, you should that the point lie on a sphere whose center is the offset of the FT sensor, and whose radius is the $$m_{\texttt{submodel_between_the_three_sensors}} | g |$$. In the past we did experiments in which this point instead lied on a elipsoid, and that is the reason why we tipically added on top of the FT sensor measure a "secondary calibration" that was calibrated "in situ" to account for this effects, see:

@isorrentino
Copy link
Collaborator

Hi @GiulioRomualdi thanks a lot for opening and documenting the issue. I have just two clarifications:

An additional comment is that I repeated the experiment on the right arm and also in this case the cartesian wrenches depend on the joint configuration.

So to recap the problems are two:

  • the fts after some time loose the calibration
  • the cartesian wrenches seem to be joint configuration dependent

@traversaro
Copy link
Member

  • the cartesian wrenches seem to be joint configuration dependent

Not sure if we can consider that an indipendent problem, that is just how the estimation algorithm work. That, coupled with how we are computing FT offset, means that in the configuration in which we have run calib all (i.e. where we computed the offset) the external estimated forces will always be equal to 0, and that would hide any ft sensor measure/model problem. If the FT sensors and the model work as expected, the external estimated forces will remain to zero even if you change configuration, but this will not be the case if instead either the model or the FT measures have some problems.

@traversaro
Copy link
Member

If we assess that this is really the problem, it may be worth to check with francisco where the last software to compute this secondary calibration matrix is.

I guess the software was this one: https://github.com/fjandrad/sensors-calib-inertial/commits/feature/integrateFTSensors, but we may need to double check with him.

@isorrentino
Copy link
Collaborator

@traversaro I wanted to kindly ask you to check one thing before going ahead with what you suggested. Since I'm not a super expert on WBD, could you check if I correctly added the new contact frame and sensor in https://github.com/ami-iit/robots-configuration/blob/devel_iCubGenova09/iCubGenova09/estimators/wholebodydynamics.xml, please? Just to be sure that is not the cause.

@prashanthr05
Copy link
Contributor

Happy memories from @DanielePucci robotology-legacy/codyco-modules#160

@prashanthr05
Copy link
Contributor

Francisco's repository on insitu-ft-analysis https://github.com/robotology-playground/insitu-ft-analysis

@DanielePucci
Copy link
Collaborator

I believe that this issue is of interests also for the current work @HosameldinMohamed is doing in https://github.com/ami-iit/element_ft-nonlinear-modeling

@isorrentino
Copy link
Collaborator

Here, the same on the arms. I just run the test.

Screenshot from 2022-03-02 10-50-32

cc @gabrielenava

@GiulioRomualdi
Copy link
Member Author

Stupid question, Are we sure the ft is correctly mounted in the model? yesterday @S-Dafarra mentioned that the problem could be related to a wrong weight in the robot, however since the force is not only on the z-axis I would say that the issue is not only related to that (on the leg the wrench components are written in the root link frame so the z is pointing upward)

Is the problem also happening in simulation?

@traversaro
Copy link
Member

traversaro commented Mar 2, 2022

however since the force is not only on the z-axis I would say that the issue is not only related to that (on the leg the wrench components are written in the root link frame so the z is pointing upward)

Mhh, I am afraid we can't exclude this problem. The problem is that a wrong weight induces a wrong offset on the z direction. Once you move the robot, the wrong offset in the z direction will influence a wrong force in all the directions.

@traversaro
Copy link
Member

however since the force is not only on the z-axis I would say that the issue is not only related to that (on the leg the wrench components are written in the root link frame so the z is pointing upward)

Mhh, I am afraid we can't exclude this problem. The problem is that a wrong weight induces a wrong offset on the z direction. Once you move the robot, the wrong offset in the z direction will influence a wrong force in all the directions.

Ah, but in that case the wrong offset will be an all axis in the frame of the FT sensor frame, but will be again just on Z once you project back the force in the base_link frame, I see.

Is the problem also happening in simulation?

As the simulation is using the same model also for the simulation, I do not think you will be able to see any difference between reality and the model (be it the weight of the model, or the wrong sensor frame) by just doing a simulation.

@HosameldinMohamed
Copy link
Collaborator

HosameldinMohamed commented Mar 2, 2022

As the simulation is using the same model also for the simulation, I do not think you will be able to see any difference between reality and the model (be it the weight of the model, or the wrong sensor frame) by just doing a simulation.

But I think it will give us some direction, such as:

  • Is the issue appearing in the simulation too? ---> Then links and sensors' frames are probably OK, the issue is not related to a wrong configuration.
  • Is the simulation giving good results? ---> Then we may check the configuration.

But actually, I feel that the results we're getting could make sense. I am not sure if you discussed this already, but:

Considering a linear FT sensor model:

$$ \boldsymbol{f} = \boldsymbol{C} \boldsymbol{r}+\boldsymbol{o}, $$

Where

  • $\boldsymbol{f} \in \mathbb{R}^6$ is the applied wrench.
  • $\boldsymbol{r} \in \mathbb{R}^6$ is the raw measurements of the sensors (in bit counts).
  • $\boldsymbol{C} \in \mathbb{R}^{6 \times 6}$, is the calibration matrix in [N(N.m)/bit] and
  • $\boldsymbol{o} \in \mathbb{R}^6$ is the offset.

The way to find $\boldsymbol{o}$ in the calibration setup, is to measure the force while $\boldsymbol{r} = \boldsymbol{0}$ (the sensor is unloaded). So $\hat{\boldsymbol{o}} = \boldsymbol{f}(\boldsymbol{0})$

What we do in wholeBodyDynamics is that we measure a force $\boldsymbol{f}_{calib}(\boldsymbol{r}_{calib})$, and we assign it as the new offset ($\hat{\boldsymbol{o}} = \boldsymbol{f}_{calib}(\boldsymbol{r}_{calib})$). Since this measurement is taken when the FT senor is loaded ($\boldsymbol{r}$ may not be $0$). It makes sense that the sensor changes it's behaviour when changing configuration, because then $\boldsymbol{r}$ changes.

Update: which means the calib process could be configuration dependent maybe? as @isorrentino pointed out in #140 (comment).

@HosameldinMohamed
Copy link
Collaborator

HosameldinMohamed commented Mar 2, 2022

Talking with @DanielePucci and @isorrentino, it may make sense to try to explore the in-situ calibration, because hopefully, we then overcome the need to do calib with wholeBodyDynamics, otherwise, the only option left is extending the FT sensors models.

Regarding the in-situ calibration. I never tested the code of Francisco in https://github.com/robotology-playground/insitu-ft-analysis. But looking at the wiki, it seems well documented. However, it seems to have a lot of steps. From collecting the data offline, then running many (MATLAB) scripts to compute the new calibration matrices. Then, I am not yet sure how to download these parameters to FT sensors or apply them to the measured forces.

We may think of automating the in-situ calibration process with C++ code. Where we apply the reference trajectories to the robot, then collect the data, then perform online calibration maybe?

@HosameldinMohamed
Copy link
Collaborator

For reference here's Francisco's knowledge transfer video https://www.youtube.com/watch?v=Mh0a2JoXmnU
and slides

@traversaro
Copy link
Member

We may think of automating the in-situ calibration process with C++ code. Where we apply the reference trajectories to the robot, then collect the data, then perform online calibration maybe?

This is in theory a good idea, but in general we experience that in a lot of cases it is important to be able to inspect the data if something went wrong or simply different from expected, hence the focus on collecting data, but then run the calibration/processing in high level languages such as Python or MATLAB.

@traversaro
Copy link
Member

traversaro commented Mar 3, 2022

Update: which means the calib process could be configuration dependent maybe? as @isorrentino pointed out in #140 (comment).

In our experience (see the papers mentioned in #140 (comment), if you want to start from something you can start from the first one, i.e. https://ieeexplore.ieee.org/abstract/document/7139477) a good model that is describing the behaviour is the following:

The ft \boldsymbol{f} is well described by an affice model that relates it to the raw measurements $\boldsymbol{r}+$
$$
\boldsymbol{f} = \boldsymbol{C} \boldsymbol{r}+\boldsymbol{o},
$$

However, for never well understood reason the matrix $\boldsymbol{C}$ is quite different form the matrix that was estimated trough calibration and is used inside the sensor, that we call $\tilde{\boldsymbol{C}}$.

This means that when we start WBD or call calib, if we assume that the reference force value $\boldsymbol{f}_{t_0}^{\texttt{model}}$ obtained by the rigid body model is sufficiently correct, we compute the offset by solving the equation:
$$
\boldsymbol{f}_{t_0}^{\texttt{model}} = \boldsymbol{\tilde{C}} \boldsymbol{r}_{t_0}+\boldsymbol{\tilde{o}}
$$

Where the solution is:
$$
\boldsymbol{\tilde{o}} = \boldsymbol{f}_{t_0}^{\texttt{model}} - \boldsymbol{\tilde{C}} \boldsymbol{r}_{t_0}
$$

while the offset $\boldsymbol{{o}}$ computed with the correct matrix $\boldsymbol{C}$ would be:
$$
\boldsymbol{{o}} = \boldsymbol{f}_{t_0}^{\texttt{model}} - \boldsymbol{{C}} \boldsymbol{r}_{t_0}
$$

Then, if the force transmitted through the FT sensor changes (for example due to a change of configuration of the robot) and so the raw measurents change as well, the FT sensor measure used by WBD would be:

$$ \tilde{\boldsymbol{f}}_{t} = \boldsymbol{\tilde{C}} \boldsymbol{r}_{t}+\boldsymbol{\tilde{o}} $$

while the correct measure would be:

$$ \boldsymbol{f}_{t} = \boldsymbol{{C}} \boldsymbol{r}_{t}+\boldsymbol{{o}} $$

for $\boldsymbol{r}_{t} = \boldsymbol{r}_{t_0}$ the two measure will coincide (thanks to how the value $\boldsymbol{\tilde{o}}$ is computed), but as soon as the robot moves, tou will see an error that can be written as:

$$ \boldsymbol{e}_t = {\boldsymbol{f}}_{t} - \tilde{\boldsymbol{f}}_{t} = \boldsymbol{{C}} \boldsymbol{r}_{t}+\boldsymbol{{o}} - \boldsymbol{\tilde{C}} \boldsymbol{r}_{t}+\boldsymbol{\tilde{o}} $$

So, you see that even if the error is caused a configuration-invariant calibration matrix, you still get a configuration-dependent error.

How we got rid of this problems in the past?

  • Instead of using $\boldsymbol{\tilde{C}}$ we used a new calibration matrix that was estimated insitu, and then using the new calibration matrix we estimated a new secondary calibration matrix $\boldsymbol{{C}}_2$ that was specified at the WBD level, such that we minimized the error $\boldsymbol{{C}}_2 \boldsymbol{\tilde{C}} - \boldsymbol{{C}}$ .
  • One of the reason why the offset needs to be computed soo frequently is due to the dependency on temperature of the measure. If that is compensated appropriately, it is not necessary anymore to re-run calib all everytime the robot starts, but we can just store the offset in the sensor or in the WBD configuration (this is what is discussed in https://ieeexplore.ieee.org/abstract/document/8794382)

Note: this is just what in the past explained well the data that we saw, nothing prevents that the situation is different now and the data can be explained better by other models. A good way to check if this is still the case, is to perform the plots described in #140 (comment) . If the measured force lay on an elipsoid, probably the problem is given by a wrong linear calibration matrix, as if you transform a sphere with a linear transformation you obtained an elipsoid.

Feel free to schedule a meeting if you want to discuss about this with a whiteboard that I guess is much more productive that discussing in issues.

@traversaro
Copy link
Member

@traversaro I wanted to kindly ask you to check one thing before going ahead with what you suggested. Since I'm not a super expert on WBD, could you check if I correctly added the new contact frame and sensor in https://github.com/ami-iit/robots-configuration/blob/devel_iCubGenova09/iCubGenova09/estimators/wholebodydynamics.xml, please? Just to be sure that is not the cause.

I guess the relevant change is ami-iit/robots-configuration@723ff7e, right? From what I see, you added a default contact on the origin of r_upper_leg, while before this change the default contact that was selected was the default contact on l_upper_leg. The configuration seems ok. Just as a remainder, the semantics of defaultContactFrames, that you can read in https://github.com/robotology/whole-body-estimators/blob/bf7d5ff892c38ed2346857477b603a3dd386e36e/devices/wholeBodyDynamics/README.md#wholebodydynamicsdevice :

Vector of default contact frames. If no external force read from the skin is found on a given submodel, the defaultContactFrames list is scanned and the first frame found on the submodel is the one at which origin the unknown contact force is assumed to be.

The related logic is:

@HosameldinMohamed
Copy link
Collaborator

@SanderRuijters

@isorrentino
Copy link
Collaborator

Hi @pattacini, yesterday I did the same test run in the past on the other fts, this time on the sensor mounted on the left upper leg. If I'm not mistaken, the sensor is the one calibrated in https://github.com/icub-tech-iit/task-force-miscellanea/issues/114, and if this is the case, something is causing miscalibration (cables touching the sensor? miscalibration due to mechanical stresses mounting it?)

Here is the norm of the forces measured by the sensor:

untitled

I'm also showing the joints of the left leg to understand when the leg was moving.

Unfortunately, I do not have the cartesian wrenches logged for this FT, but I expect they are not zero when the norm of the forces changes.

@pattacini
Copy link
Member

pattacini commented Jul 20, 2022

Hi @isorrentino

I can see that the final configuration of the leg $c_f$ (joints all zeroed) is different from the starting configuration $c_i$ (I suppose here that units are rad). Thus, it may be of help to repeat the experiment in a condition where $c_f = c_i$, and also for some $c_i$ where joints are not kept all zeroed. The latter is meant for exploring a set of configurations (4÷5, let's say).

It's true that the FT readouts should be independent of $c_i$ and $c_f$, up to some extent, and related only to the weight of the leg if there are no external forces, but I reckon that the above test could give us some insights too.

Also, the FT SN can be retrieved using the FirmwareUpdater for a double check.

cc @maggia80

@traversaro
Copy link
Member

traversaro commented Jul 20, 2022

If I'm not mistaken, the sensor is the one calibrated in icub-tech-iit/task-force-miscellanea#114, and if this is the case, something is causing miscalibration (cables touching the sensor? miscalibration due to mechanical stresses mounting it?)

Just to make sure that we are all aligned, I tried to plot the norms of forces of another sensor tested in a similar issue, that was considered "acceptable" without anyone contractinding this assesment:

plot_ft_sensor

done with:

plot(vecnorm(Fall'))

In this case, the max-min error is ~30 N, similar in the order of magnitude of max-min ~40 N observed in this issue. So, for the future it may be useful to agree before hand in a quantitative index to consider a sensor "acceptable", to avoid misunderstandings.

@GiulioRomualdi
Copy link
Member Author

GiulioRomualdi commented Jul 21, 2022

If I have to tell the truth in my opinion this is not acceptable. I raised this point during a meeting but unfortunately given the current calibration this is the best we are able to reach (we may think to figure out how to improve it. (cc to some people interested in the topic) @DanielePucci @isorrentino @HosameldinMohamed ).

Given the plot in #140 (comment) and assuming that the "real" norm is 145N. We can say that the sensor returns a force with an error of $\pm 15N$
$$f_m = 145N \pm 15N$$
where $f_m$ is the measured force.

In other words, the sensor has an accuracy of about 10% (that in my opinion is pretty high since we try to use this information to estimate the joint torques and the external wrenches)


This is just to say that it would be really nice if we try to solve (as a team) the problem all together, since I think we will all benefit if the FTs becomes more trustable 😃

@isorrentino
Copy link
Collaborator

In other words, the sensor has an accuracy of about 10% (that in my opinion is pretty high since we try to use this information to estimate the joint torques and the external wrenches)

I agree!

@DanielePucci
Copy link
Collaborator

I agree with @GiulioRomualdi on

This is just to say that it would be really nice if we try to solve (as a team) the problem all together, since I think we will all benefit if the FTs becomes more trustable 😃

Improving the FT sensor calibration may in turn enable better performances of the torque-control that is now suffering of zero or low torque gains during @lrapetti and @HosameldinMohamed physical HRI tasks https://github.com/ami-iit/element_ergonomy-control/issues/165#issuecomment-1190449021. It is also important for the finals of the ANA Avatar XPRIZE where we most likely need to identify precisely the weight of grasped objects up to three chilos.

We discussed briefly about possible action plans today with @GiulioRomualdi and @S-Dafarra, and a possibility could be that to make a cross research axis team that for a really short amount of time (one week or ten days) attempts preliminary actions for improving the model possibly with the support of @robotology/icub-tech-support-team

One action that we may take independently of the cross-team is to re-run the in-situ calibration and check validation results on both iCub 3 and iRonCub https://github.com/ami-iit/element_ft-nonlinear-modeling/issues/29

@HosameldinMohamed
Copy link
Collaborator

Improving the FT sensor calibration may in turn enable better performances of the torque-control that is now suffering of zero or low torque gains during @lrapetti and @HosameldinMohamed

Probably you meant @mebbaid

@pattacini
Copy link
Member

pattacini commented Jul 25, 2022

We know that in iCub Tech we calibrate the FT sensors with a simple linear model, which by the way enables us to achieve errors smaller than 3÷4% on validation sets.

We also know that the calibration/validation sets might be not good representatives of the real range of data that are generally experienced on the robot since the KUKA can lift limited weights, although we tried to put to test the calibration outcome with the old procedure where we could use heavier input weights and the results weren't that bad.

Further, it may also be that when mounting the sensor on the robot some other snags can have an impact. That's why we launched in the recent past the initiative of the FTWG tracked in https://github.com/icub-tech-iit/task-force-miscellanea/issues/108.

From our side, we're definitely open to integrating more sophisticated calibration models within the FW, but it would be nice to see first some decisive improvements from, for example, the in-situ calibration and/or nonlinear identification methods.

It would also help to have an estimate of the upper bound on the relative error of the FT quantities that the whole-body framework can tolerate.

@DanielePucci
Copy link
Collaborator

DanielePucci commented Jul 25, 2022

From our side, we're definitely open to integrating more sophisticated calibration models within the FW, but it would be nice to see first some decisive improvements from, for example, the in-situ calibration and/or nonlinear identification methods.

We understand this @pattacini, and we are happy to help: preliminary results that answer the point above are performed in https://github.com/ami-iit/element_ft-nonlinear-modeling/issues/36. On the other hand, it would be important to see the performance of the FT sensors on test datasets after installation and deployment are complete so as we may consider the installation successful if performance indexes to be discussed are met - e.g. errors within certain thresholds. I do not know if you already have these tests in place: if you do not, they would give us a direct metric of what happens when installing FTs on the robot - the test suit presented by @gsisinna in the last Product Increment may help.

It would also help to have an estimate of the upper bound on the relative error of the FT quantities that the whole-body framework can tolerate.

Giving the current priorities, we would struggle with giving you stability margins of the controller versus FT accuracies. So, I do not think this is happening soon. What we may say is that we are struggling with force estimates of external payloads - a task of the ANA Avatar XPRIZE final - as well as with increasing torque gains in torque-controlled demos - e.g. collaborative lifting of the ergoCub project https://github.com/ami-iit/element_ergonomy-control/issues/165#issuecomment-1190449021 CC @lrapetti. On the same line, @affafjunaidMOMIN and @gabrielenava of the iRonCub team are correcting FT readings along the z component for better estimates of the thrust force using a manual off-situ calibration, see, e.g., https://github.com/ami-iit/element_jet-cat-turbines/issues/354#issuecomment-1172337742.

@pattacini
Copy link
Member

Hi @DanielePucci

it would be important to see the performance of the FT sensors on test datasets after installation and deployment are complete so as we may consider the installation successful if performance indexes to be discussed are met - e.g. errors within certain thresholds. I do not know if you already have these tests in place...

There's no such a thing in place so far. We just work with the KUKA, but I agree that this check would help make installation more robust and give us insights into what weirdnesses are going on.

We can certainly adopt the test suite but, first, we should agree on what types of movements the robot needs to be performing for validation purposes together with what ground truth we're required to use alongside (probably iDynTree).

I can add up this task to the list1; however, I also deem that this won't happen any time soon because we have our main developers busy with the 4K Cameras2.

preliminary results that answer the point above are performed in https://github.com/ami-iit/element_ft-nonlinear-modeling/issues/36.

That's great and I can also see big potential here, although in my view we still need to validate the approach for external wrenches (and extend the procedure to include them) as nonlinear estimators tend to suffer from overfitting and clamping. New algorithms are welcome as now we have a powerful tool (Simulink + Embedded Coder) to port them into FW, though we ought to check whether there are enough resources onboard.

Giving the current priorities, we would struggle with giving you stability margins of the controller versus FT accuracies. So, I do not think this is happening soon

Got it 👍🏻
Probably worth being planned on anyway (after the final?), just to get a rough estimate of the impacts.

What we may say is that we are struggling with force estimates of external payloads - a task of the ANA Avatar XPRIZE final - as well as with increasing torque gains in torque-controlled demos - e.g. collaborative lifting of the ergoCub project

Given @lrapetti's answer3, investigations are underway; keep us posted.

On the same line, @affafjunaidMOMIN and @gabrielenava of the iRonCub team are correcting FT readings along the z component for better estimates of the thrust force using a manual off-situ calibration, see, e.g., https://github.com/ami-iit/element_jet-cat-turbines/issues/354#issuecomment-1172337742.

This is kind of expected as looking at the study it seems that you're trying to correct an error in the range of 4%, which is something our linear fitter cannot compensate for.

Footnotes

  1. https://github.com/icub-tech-iit/task-force-miscellanea/issues/108

  2. https://github.com/icub-tech-iit/study-icub-head/issues/14

  3. https://github.com/ami-iit/element_ergonomy-control/issues/165#issuecomment-1195249946

@DanielePucci
Copy link
Collaborator

DanielePucci commented Jul 30, 2022

Hi @pattacini

There's no such a thing in place so far. We just work with the KUKA, but I agree that this check would help make installation more robust and give us insights into what weirdnesses are going on.

Concerning this I was wondering a silly thing: are we sure that the Kuka based calibration explores all positive and negative values of forces and wrenches? I mean, this seems an important feature of the calibration since it would be important that the training dataset contains experiments that pull and push both forces and torques in all directions, namely, we excite all axes of both forces and torques in positive and negative directions. I do not know if we know this.

We can certainly adopt the test suite but, first, we should agree on what types of movements the robot needs to be performing for validation purposes together with what ground truth we're required to use alongside (probably iDynTree).

I can add up this task to the list1; however, I also deem that this won't happen any time soon because we have our main developers busy with the 4K Cameras2.

Got it thanks

That's great and I can also see big potential here, although in my view we still need to validate the approach for external wrenches (and extend the procedure to include them) as nonlinear estimators tend to suffer from overfitting and clamping. New algorithms are welcome as now we have a powerful tool (Simulink + Embedded Coder) to port them into FW, though we ought to check whether there are enough resources onboard.

This is also interesting, I am sure there is a lot of potential there. I agree on the validation, although let's say that at least the NN seems to improve the original calibration and the in-situ, which leaves space to the nonlinear models @HosameldinMohamed is developing along different directions https://github.com/ami-iit/element_ft-nonlinear-modeling/issues/4

@pattacini
Copy link
Member

pattacini commented Jul 31, 2022

Concerning this I was wondering a silly thing: are we sure that the Kuka based calibration explores all positive and negative values of forces and wrenches? I mean, this seems an important feature of the calibration since it would be important that the training dataset contains experiments that pull and push both forces and torques in all directions, namely, we excite all axes of both forces and torques in positive and negative directions. I do not know if we know this.

It's a legit doubt 👍🏻
Yep, we devised the calibration in order to explore the widest possible range of forces and torques along the 6 axes and in both push and pull configurations; plus, the validation set is collected in such a way that contains data points not seen during the training.
Also, on several occasions, we mounted calibrated sensors back on the KUKA for debugging purposes where we moved the manipulator in different configurations, and the outputs were consistent with the previous validation.

I agree that there are a number of quirks, although we still don't know exactly where they are. At any rate, putting in place with your help an automated test with iDynTree when mounting the sensor onboard the robot, which we can run by ourselves, would be a good starting point for the investigation.

@pattacini pattacini changed the title [iCubGenova09] estimated right leg wrench is different from zero when the leg is in a configuraion different from the one used to calibrate [iCubGenova09] estimated right leg wrench is different from zero when the leg is in a configuration different from the one used to calibrate Mar 8, 2023
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

7 participants