lardemua / atom

Calibration tools for multi-sensor, multi-modal robotic systems
GNU General Public License v3.0
247 stars 27 forks source link

PR2 eye to base calibration - Single Sensor #706

Closed manuelgitgomes closed 1 month ago

manuelgitgomes commented 9 months ago

Hello @miguelriemoliveira!

I am trying to do an eye to base calibration on the PR2.

For that I recorded a bag file with the pattern on the hand of the PR2 and with only a single camera and moved it around. It generated this ATOM dataset: train_20231114.tar.gz

I thought everything was fine with this calibration, but unfortunately I did not fix the pattern, which it is (w.r.t. the end-effector).

Some things in ATOM seem to not align that much with eye to base calibration.

One example is this one: https://github.com/lardemua/atom/blob/30aba658f3a8c9f184e2a7fb2987b2ffeb5df528/atom_calibration/src/atom_calibration/calibration/visualization.py#L479-L491

In this block of code, we can see that the pattern visualization is not correctly done, as only one is rendered.

Another thing that does not seem right to me is the calibration results. The final residual table is:

+------------+-----------------------+                                                                                                                                             
| Collection | azure_rgb_camera [px] |                                                                                                                                             
+------------+-----------------------+                                                                                                                                             
|    000     |    15.1885 (0.5702)   |                                                                                                                                             
|    001     |    3.2207 (0.1209)    |                                                                                                                                             
|    002     |    10.9150 (0.4098)   |                                                                                                                                             
|    003     |    21.7006 (0.8147)   |                                                                                                                                             
|    004     |    30.3252 (1.1385)   |                                                                                                                                             
|    005     |    7.8314 (0.2940)    |                                                                                                                                             
|    006     |    9.1158 (0.3422)    |                                                                                                                                             
|    007     |   182.9993 (6.8703)   |                                                                                                                                             
|    008     |    9.6382 (0.3618)    |                                                                                                                                             
|    009     |    9.9364 (0.3730)    |                                                                                                                                             
|    010     |    16.1682 (0.6070)   |                                                                                                                                             
|    011     |    15.5045 (0.5821)   |                                                                                                                                             
|    013     |    10.7652 (0.4042)   |                                                                                                                                             
|    014     |    11.4116 (0.4284)   |                                                                                                                                             
|    015     |    11.8892 (0.4464)   |                                                                                                                                             
|    016     |    12.9904 (0.4877)   |                                                                                                                                             
|    017     |    7.4318 (0.2790)    |                                                                                                                                             
|    018     |    6.3122 (0.2370)    |                                                                                                                                             
|    019     |    10.9426 (0.4108)   |                                                                                                                                             
|    020     |    4.0670 (0.1527)    |                                                                                                                                             
|    021     |    6.8273 (0.2563)    |                                                                                                                                             
|    022     |    8.6981 (0.3265)    |                                                                                                                                             
|    023     |    10.1374 (0.3806)   |                                                                                                                                             
|    024     |    7.0010 (0.2628)    |                                                                                                                                             
|    025     |    8.4502 (0.3172)    |                                                                                                                                             
|    026     |    9.6708 (0.3631)    |                                                                                                                                             
|    027     |    6.7554 (0.2536)    |                                                                                                                                             
|    028     |    90.5383 (3.3990)   |                                                                                                                                             
|    029     |   148.0577 (5.5585)   |                                                                                                                                             
|    030     |    15.2118 (0.5711)   |                                                                                                                                             
|    031     |    17.2025 (0.6458)   |                                                                                                                                      
|    032     |    9.9321 (0.3729)    |
|    033     |   117.7812 (4.4218)   |
|    034     |    7.8145 (0.2934)    |
|    035     |    7.2236 (0.2712)    |
|    036     |    19.6845 (0.7390)   |
|    037     |    9.5812 (0.3597)    |
|    038     |    12.5422 (0.4709)   |
|    040     |    6.1946 (0.2326)    |
|    041     |    4.4140 (0.1657)    |
|    042     |    6.0199 (0.2260)    |
|    043     |    6.1293 (0.2301)    |
|    044     |    21.7106 (0.8151)   |
|    045     |    16.9495 (0.6363)   |
|    047     |    17.5260 (0.6580)   |
|    049     |    15.4382 (0.5796)   |
|    050     |    4.6917 (0.1761)    |
|    051     |    6.8912 (0.2587)    |
|  Averages  |    21.4048 (0.8036)   |
+------------+-----------------------+

So, they do not look good. However, these values do not seem to correlate with the images seen. As an example, collection 7: image

And collection 29: image

I think it would be better to "dumb down" the system and create a fully simulated system to test eye-to-base calibration. Do you have any suggestions?

(tagging @v4hn for visibility)

v4hn commented 9 months ago

As @manuelgitgomes just noticed when we looked at this, orientation is swapped for the example pictures which leads to a huge error.

manuelgitgomes commented 9 months ago

By removing those bad collections, the residuals are:

+------------+-----------------------+                                                                                                                         
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+                                                                                                                         
|    000     |    12.0162 (0.7222)   |                                                                                                                         
|    001     |    5.7008 (0.3426)    |                                                                                                                         
|    002     |    9.3775 (0.5636)    |                                                                                                                         
|    003     |    15.7684 (0.9477)   |                                                                                                                         
|    004     |    26.1714 (1.5729)   |                                                                                                                         
|    005     |    4.6277 (0.2781)    |                                                                                                                         
|    006     |    11.1520 (0.6702)   |                                                                                                                         
|    008     |    5.6891 (0.3419)    |                                                                                                                         
|    009     |    5.9908 (0.3600)    |                                                                                                                         
|    010     |    12.8599 (0.7729)   |                                                                                                                         
|    011     |    12.4873 (0.7505)   |                                                                                                                         
|    013     |    9.5303 (0.5728)    |                                                                                                                         
|    014     |    6.3634 (0.3824)    |                                                                                                                         
|    015     |    15.0248 (0.9030)   |                                                                                                                         
|    016     |    18.8047 (1.1302)   |                                                                                                                         
|    017     |    9.9150 (0.5959)    |                                                                                                                         
|    018     |    8.3855 (0.5040)    |                                                                                                                         
|    019     |    6.1178 (0.3677)    |                                                                                                                         
|    020     |    3.1083 (0.1868)    |                                                                                                                         
|    021     |    8.4815 (0.5097)    |                                                                                                                         
|    022     |    4.5496 (0.2734)    |                                                                                                                         
|    023     |    11.3295 (0.6809)   |                                                                                                                         
|    024     |    4.6800 (0.2813)    |                                                                                                                         
|    025     |    8.7752 (0.5274)    |                                                                                                                         
|    026     |    7.0909 (0.4262)    |                                                                                                                         
|    027     |    7.2625 (0.4365)    |                                                                                                                         
|    030     |    10.5304 (0.6329)   |                                                                                                                         
|    031     |    10.7403 (0.6455)   |                                                                                                                         
|    032     |    6.3535 (0.3818)    |
|    034     |    2.8870 (0.1735)    |
|    035     |    4.9506 (0.2975)    |
|    036     |    12.8989 (0.7752)   |
|    037     |    5.8663 (0.3526)    |
|    038     |    10.0403 (0.6034)   |
|    040     |    2.8287 (0.1700)    |
|    041     |    6.3734 (0.3830)    |
|    042     |    6.2179 (0.3737)    |
|    043     |    5.2187 (0.3136)    |
|    044     |    17.3222 (1.0411)   |
|    045     |    14.5976 (0.8773)   |
|    047     |    17.7994 (1.0697)   |
|    049     |    10.6008 (0.6371)   |
|    050     |    2.2183 (0.1333)    |
|    051     |    6.4088 (0.3852)    |
|  Averages  |    9.2071 (0.5533)    |
+------------+-----------------------+

So the error is a lot less, but still far from something good. It went from 18 pixels to 9, which is good.

I could not find the bug (at least not yet), but I will carry this on tomorrow.

To clarify, the values I told you before (around 0.25 pixels) are not correct and were gathered with an error. These are the real values for the first bag file.

Tomorrow I will try to calibrate with the large bagfile and see what results we have.

miguelriemoliveira commented 9 months ago

Hi @manuelgitgomes ,

where is the repo for the calibration package? I wanted to look at the config.yml. Also, please post the pdf that summarizes the calibration.

manuelgitgomes commented 9 months ago

where is the repo for the calibration package? I wanted to look at the config.yml. Also, please post the pdf that summarizes the calibration.

It is in:

https://github.com/manuelgitgomes/tams_pr2

The package is tams_pr2_atom_calibration.

miguelriemoliveira commented 9 months ago

As @manuelgitgomes just noticed when we looked at this, orientation is swapped for the example pictures which leads to a huge error.

I am not sure to what @v4hn is referring to, but I think it may be one problem we had in the past. Chessboard detection is ambiguous, as it sometimes detects the pattern straight up, sometimes upside down. This will of course lead to large calibration errors.

From the images it does not see to be the problem, since the line closest to the hand is always yellow to red (left to right).

But I remember that this was a clear problem, and was one of the big reasons why we decided to use charuco patterns instead.

I would recommend using a charuco. It would also have the advantage of generating partial detections of the pattern.

miguelriemoliveira commented 9 months ago

It is in:

https://github.com/manuelgitgomes/tams_pr2

The package is tams_pr2_atom_calibration.

The config.yaml looks ok (the calibration pattern definition).

manuelgitgomes commented 9 months ago

From the images it does not see to be the problem, since the line closest to the hand is always yellow to red (left to right).

This is because these are the "bad" collections. On the good ones, it is reversed.

Chessboard detection is ambiguous, as it sometimes detects the pattern straight up, sometimes upside down.

It should not, as I discussed with @v4hn. Calibration patterns are asymmetrical. Left corners have black squares, right corners have white squares. The detection should not be ambiguous.

miguelriemoliveira commented 9 months ago

Concerning the pdf, it looks strange:

image

  1. the transformation that has parent head_plate_frame has twice the word "to be calibrated".

The problem is that in the config.yaml you defined the same transformation head_plate_frame to azure_kinect_camera_base for two different sensors, azure_kinect_rgb and azure_kinect_depth. We must have one separate transformation for each sensor. It will not work like this.

  1. The selection of transformations for the cameras is not well selected. You should have one independent transformation per sensor, so that it is possible to position it independently of other sensors. Your structure does not ensure this.

For example, narrow_stereo_l_stereo_camera_optical_frame should have transformation narrow_stereo_l_stereo_camera_frame to narrow_stereo_l_stereo_camera_optical_frame to be calibrated, instead of the current narrow_stereo_l_stereo_camera_optical_frame to narrow_stereo_r_stereo_camera_frame, which will also affect another sensor, in this case narrow_stereo_r_stereo_camera_optical_frame.

My suggestion is that you rewrite the config.yml and post here the new pdf. I can take a look at it and let you know if it makes sense.

miguelriemoliveira commented 9 months ago

It should not, as I discussed with @v4hn. Calibration patterns are asymmetrical. Left corners have black squares, right corners have white squares. The detection should not be ambiguous.

From what I recall they were ambiguous. You can select a different number of corners in rows and columns, so the detection does not rotate 90 degrees, but you still had the problem of rotating 180 degrees. Anyways, I do not use patterns in two or three years, since charucos are much nicer, so I may be missing something.

manuelgitgomes commented 9 months ago

but you still had the problem of rotating 180 degrees.

I don't think that should happen. When it is on 0º the black squares are on the left and and when the rotation is 180º the white squares are on the left, right?

manuelgitgomes commented 9 months ago

Hello!

I found the culprit!

https://github.com/lardemua/atom/blob/30aba658f3a8c9f184e2a7fb2987b2ffeb5df528/atom_calibration/src/atom_calibration/collect/patterns.py#L25-L29

These lines of code switch the detection around in some situations (seems like when the pattern is rotated from 90º to 270º). By taking these off and gathering a new dataset, every thing worked. Table of residuals:

+------------+-----------------------+                                                                                                                
| Collection | azure_rgb_camera [px] |                                                                                                                
+------------+-----------------------+                                                                                                                
|    000     |    6.6219 (0.0667)    |                                                                                                                
|    001     |    6.5799 (0.0663)    |                                                                                                                
|    002     |          ---          |                                                                                                                
|    003     |    30.7730 (0.3100)   |                                                                                                                
|    004     |    3.6021 (0.0363)    |                                                                                                                
|    005     |    6.5337 (0.0658)    |                                                                                                                
|    006     |    8.1633 (0.0822)    |                                                                                                                
|    007     |    12.4739 (0.1257)   |                                                                                                                
|    008     |    12.5648 (0.1266)   |                                                                                                                
|    009     |    13.7287 (0.1383)   |                                                                                                                
|    010     |    12.9055 (0.1300)   |                                                                                                                
|    011     |          ---          |                                                                                                                
|    012     |          ---          |                                                                                                                
|    013     |    7.3196 (0.0737)    |                                                                                                                
|    014     |    11.2203 (0.1130)   |                                                                                                                
|    015     |    13.0153 (0.1311)   |                                                                                                                
|    016     |    7.5070 (0.0756)    |                                                                                                                
|    017     |    7.5101 (0.0757)    |                                                                                                                
|    018     |    7.9034 (0.0796)    |                                                                                                                
|    019     |    2.1649 (0.0218)    |                                                                                                                
|    020     |    3.0513 (0.0307)    |                                                                                                                
|    021     |    4.9789 (0.0502)    | 
|    022     |    9.4401 (0.0951)    |                                                                                                      
|    023     |    2.9836 (0.0301)    |                                                                                                                
|    024     |    7.8162 (0.0787)    |                                                                                                                
|    025     |    7.6606 (0.0772)    |                                                                                                                
|    026     |    3.2460 (0.0327)    |                                                                                                                
|    027     |          ---          |                                                                                                                
|    028     |          ---          |                                                                                                                
|    029     |          ---          |                                                                                                                
|    030     |    18.3316 (0.1847)   |                                                                                                                
|    031     |    14.5779 (0.1468)   |                                                                                                                
|    032     |    12.3011 (0.1239)   |                                                                                                                
|    033     |    6.4195 (0.0647)    |                                                                                                                
|    034     |    16.3021 (0.1642)   |                                                                                                                
|    035     |    6.0978 (0.0614)    |                                                                                                                
|    036     |    4.5206 (0.0455)    |                                                                                                                
|    037     |    12.2501 (0.1234)   |                                                                                                                
|    038     |          ---          |                                                                                                                
|    039     |    8.2521 (0.0831)    |                                                                                                                
|    040     |          ---          |                                                                                                                
|    041     |          ---          |                                                                                                                
|    042     |    2.4247 (0.0244)    |                                                                                                                
|    043     |    7.6367 (0.0769)    |                                                                                                                
|    044     |    1.9844 (0.0200)    |                                                                                                                
|    045     |    4.7425 (0.0478)    |                                                                                                                
|    046     |          ---          |                                                                                                                
|    047     |          ---          |                                                                                                                
|    048     |    17.9399 (0.1807)   |                                                                                                                
|    049     |          ---          |                                                                                                                
|    050     |          ---          |                                                                                                                
|    051     |          ---          |                                                                                                                
|    052     |          ---          |                                                                                                                
|    053     |    13.5165 (0.1362)   |                                                                                                                
|    054     |    5.2350 (0.0527)    |                                                                                                                
|    055     |    4.7866 (0.0482)    |
|  Averages  |    8.9532 (0.0902)    |
+------------+-----------------------+

And collection 7:

image

@miguelriemoliveira is that block of code important or can be deleted?

miguelriemoliveira commented 9 months ago

@miguelriemoliveira is that block of code important or can be deleted?

That was written by @eupedrosa . Eurico, do you remember why it was there?

For now just comment.

miguelriemoliveira commented 9 months ago

I am still underwhelmed by the results.

We are getting 8 pixels of average error. We should have less, or have a good explanation as to why we cannot get better results.

Usually we get subpixel accuracy, so we should have better figures ...

miguelriemoliveira commented 9 months ago

@manuelgitgomes the summary.pdf continues to appear wrong. Did you change and push? I would like to inspect it...

miguelriemoliveira commented 9 months ago

I don't think that should happen. When it is on 0º the black squares are on the left and and when the rotation is 180º the white squares are on the left, right?

Not sure. As I said I do not use checkerboards in a long time. But one thing you can do is manually verify all the labeled images to see if they are consistent.

eupedrosa commented 9 months ago

@miguelriemoliveira is that block of code important or can be deleted?

That was written by @eupedrosa . Eurico, do you remember why it was there?

For now just comment.

Sometimes the order of the detected points were reversed. Instead of starting at 0,0 it would start at the last one. With charuco you never have this problem.

At the time it was a hack to work with the dataset that I had. Maybe it was an overfitted hack ;) It may be safe to remove. Nonetheless, it seems you still have some issues with the calibration.

manuelgitgomes commented 9 months ago

@manuelgitgomes the summary.pdf continues to appear wrong. Did you change and push? I would like to inspect it...

Hello @miguelriemoliveira

Sorry, I misunderstood it and missed you comment.

the transformation that has parent head_plate_frame has twice the word "to be calibrated".

This is because the azure frames are provided by the azure driver and not the urdf. Therefore, I changed to the closest frame on the urdf. I can change the frames into the urdf but that would deviate from the norm.

We must have one separate transformation for each sensor. It will not work like this.

Why is that? When calibrating mobile manipulators, we had 2 sensors estimating the same additional_tf (at least in softbot2) and everything worked out. I cannot see a way that this would not work.

For example, narrow_stereo_l_stereo_camera_optical_frame should have transformation narrow_stereo_l_stereo_camera_frame to narrow_stereo_l_stereo_camera_optical_frame to be calibrated, instead of the current narrow_stereo_l_stereo_camera_optical_frame to narrow_stereo_r_stereo_camera_frame, which will also affect another sensor, in this case narrow_stereo_r_stereo_camera_optical_frame.

That would just detach the optical frame from the camera frame, which seems wrong to me. The optical frame should only be a fixed and standardized frame rotation from the sensor frame. I know that the way I presented it is not the most common, but to change would mean to change the urdfs of the PR2 and it would create a very custom solution, deviating from all others PR2. I want to abstain from that as much as I can. The way I did things is not optimal, but it should work as, again, we did something similar in softbot2.

miguelriemoliveira commented 9 months ago

Sometimes the order of the detected points were reversed. Instead of starting at 0,0 it would start at the last one. With charuco you never have this problem.

At the time it was a hack to work with the dataset that I had. Maybe it was an overfitted hack ;) It may be safe to remove. Nonetheless, it seems you still have some issues with the calibration.

Thanks @eupedrosa .

miguelriemoliveira commented 9 months ago

the transformation that has parent head_plate_frame has twice the word "to be calibrated".

This is because the azure frames are provided by the azure driver and not the urdf. Therefore, I changed to the closest frame on the urdf. I can change the frames into the urdf but that would deviate from the norm.

We must have one separate transformation for each sensor. It will not work like this.

Why is that? When calibrating mobile manipulators, we had 2 sensors estimating the same additional_tf (at least in softbot2) and everything worked out. I cannot see a way that this would not work.

I still think that will be a problem once you try to calibrate all sensors. Yes, we did calibrate transformations that were in the chain of two or more sensors. But that is not the same as here, because we always had one transformation specific and unique for each sensor. We could have some shared to be calibrated transformations, but only as additional transforms. Note that if you do not have a unique to be calibrated transformation per sensor you cannot expect the sensor to be positioned independently from other sensors.

For example, narrow_stereo_l_stereo_camera_optical_frame should have transformation narrow_stereo_l_stereo_camera_frame to narrow_stereo_l_stereo_camera_optical_frame to be calibrated, instead of the current narrow_stereo_l_stereo_camera_optical_frame to narrow_stereo_r_stereo_camera_frame, which will also affect another sensor, in this case narrow_stereo_r_stereo_camera_optical_frame.

That would just detach the optical frame from the camera frame, which seems wrong to me. The optical frame should only be a fixed and standardized frame rotation from the sensor frame. I know that the way I presented it is not the most common, but to change would mean to change the urdfs of the PR2 and it would create a very custom solution, deviating from all others PR2. I want to abstain from that as much as I can.

I agree that it is preferable not to touch (calibrate) the camera_frame to camera_frame_optical. These are, as you say, standardized transforms one should leave unchanged. But note that preferable does not mean impossible. In this case, you selected a transformation that makes calibration nonviable (because its not an unique transformation for the sensor, as said above). In this case, might as well mess up a standard transformation than to select a transformation that will not work.

The way I did things is not optimal, but it should work as, again, we did something similar in softbot2.

Can you post the softbot2 summary.pdf. I do not think it will be the same, but I am curious to see.

Note that all these comments should not apply to the results you posted above, as they are calibrations made with a single sensor, right?

In any case let's talk tomorrow for a while about this. Are you available at 9 PT time?

manuelgitgomes commented 9 months ago

Note that if you do not have a unique to be calibrated transformation per sensor you cannot expect the sensor to be positioned independently from other sensors.

Yes, that is an error I assumed. I know that the transformation between the RGB and the Depth camera would stay the same. What I can do is to create these transformations in a copy of a urdf and estimate them. Then apply them to the configuration of the azure drivers. That is an option.

In this case, you selected a transformation that makes calibration nonviable (because its not an unique transformation for the sensor, as said above).

I understand that it is suboptimal and that it has never been done by us, but I do not fully understand how this would (at least conceptually) fail. Is this because, in the chain between the sensor and the pattern, there is a transform that the sensor cannot help in the estimation? Would this create a running target problem? Nevertheless, if you think it is better to change the optical frame, I can do it.

Can you post the softbot2 summary.pdf. I do not think it will be the same, but I am curious to see.

It is not the same because each camera has a single transform. What I meant about being the same is that 2 tfs are estimated along the chain.

Note that all these comments should not apply to the results you posted above, as they are calibrations made with a single sensor, right?

Exactly!

miguelriemoliveira commented 9 months ago

Note that if you do not have a unique to be calibrated transformation per sensor you cannot expect the sensor to be positioned independently from other sensors.

Yes, that is an error I assumed. I know that the transformation between the RGB and the Depth camera would stay the same. What I can do is to create these transformations in a copy of a urdf and estimate them. Then apply them to the configuration of the azure drivers. That is an option.

What you are talking about is to use ATOM to calibrate the azure body w.r.t to the head plate. You can do that but using a single sensor, not both. Or at least we never tried this configuration before. Remember, the PR2 is the most complex robot we have ever worked with. The first experiments should map directly to what we did before, not to try something completely new we are not even sure works.

Moreover, why would you not use ATOM to calibrate both azure cameras. You know it is well capable of doing so, so why opt not to?

In this case, you selected a transformation that makes calibration nonviable (because its not an unique transformation for the sensor, as said above).

I understand that it is suboptimal and that it has never been done by us, but I do not fully understand how this would (at least conceptually) fail.

I can try to explain in a meeting. I need to draw, texting is difficult.

Is this because, in the chain between the sensor and the pattern, there is a transform that the sensor cannot help in the estimation? Would this create a running target problem? Nevertheless, if you think it is better to change the optical frame, I can do it.

I am really convinced it will not work as you have it now.

Can you post the softbot2 summary.pdf. I do not think it will be the same, but I am curious to see.

It is not the same because each camera has a single transform. What I meant about being the same is that 2 tfs are estimated along the chain.

So you see. Its not the same. Each camera has a single transform, unique to it. That's why the calibration worked, I think.

Note that all these comments should not apply to the results you posted above, as they are calibrations made with a single sensor, right?

Exactly!

Right. In any case I would start by correcting the config.yml and make sure we all agree that the summary.pdf is actually a correct configuration for calibration.

Then I would focus on the single sensor calibration, and on trying to understand why we have such large errors for that single sensor calibration. So these are two separate problems, perhaps divide them in two issues? What do you think?

manuelgitgomes commented 9 months ago

As talked with @miguelriemoliveira, here is a small example of the result of a calibration with a single collection:

+------------+-----------------------+
| Collection | azure_rgb_camera [px] |
+------------+-----------------------+
|    000     |    0.1747 (0.9427)    |
|  Averages  |    0.1747 (0.9427)    |
+------------+-----------------------+

I think what might be wrong in the "full" calibration is that the joint states/positions are not 100% correct. We assume they are, which might be why this is not completely correct.

miguelriemoliveira commented 9 months ago

As talked with @miguelriemoliveira, here is a small example of the result of a calibration with a single collection:

I @manuelgitgomes ,

I agree, it could be the problem of the arm and head links / joints not being well calibrated.

But, first I would like to exclude more simple hypothesis. When capturing the dataset, you did wait for a long time after the arm was stopped before capturing a collection? I wanted to make sure that lack of synchrony is not a problem ...

Another thing is, can you do single collection calibrations using other collections? Just to make sure collection 000 is not the only one that will produce great results if calibrated alone.

manuelgitgomes commented 9 months ago

But, first I would like to exclude more simple hypothesis. When capturing the dataset, you did wait for a long time after the arm was stopped before capturing a collection? I wanted to make sure that lack of synchrony is not a problem ...

I captured a new dataset being extra conservative in those measure. I also took the worse collections off (a lot of them) and it gave me these results:

+------------+-----------------------+                                                                                                                         
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+                                                                                                                         
|    000     |    2.8495 (0.2720)    |      
|    004     |    4.0907 (0.3905)    |                                                                                                                
|    005     |    8.0774 (0.7711)    |                                                                                                                         
|    007     |    3.8237 (0.3650)    |                                                                                                                         
|    008     |    6.5360 (0.6239)    |                                                                                                                         
|    010     |    6.9422 (0.6627)    |                                                                                                                         
|    011     |          ---          |                                                                                                                         
|    012     |    4.9627 (0.4738)    |                                                                                                                         
|    015     |    7.8159 (0.7461)    |                                                                                                                         
|    016     |    5.4920 (0.5243)    |                                                                                                                         
|    017     |    5.2971 (0.5057)    |                                                                                                                         
|    019     |    6.1937 (0.5913)    |                                                                                                                         
|    020     |    8.3206 (0.7943)    |                                                                                                                         
|    021     |    2.4748 (0.2363)    |                                                                                                                         
|    022     |    5.0225 (0.4795)    |                                                                                                                         
|    023     |    2.4022 (0.2293)    |                                                                                                                         
|    024     |    4.3760 (0.4177)    |                                                                                                                         
|    025     |          ---          |                                                                                                                         
|    026     |          ---          |                                                                                                                         
|    030     |    9.4622 (0.9033)    |                                                                                                                         
|    032     |    2.5859 (0.2469)    |                                                                                                                         
|    033     |    3.3999 (0.3246)    |                                                                                                                         
|    035     |          ---          |                                                                                                                         
|    036     |    7.7451 (0.7394)    |                                                                                                                         
|    037     |          ---          |                                                                                                                         
|    038     |    3.9265 (0.3748)    |                                                                                                                         
|    039     |    6.6371 (0.6336)    |                                                                                                                         
|    040     |    4.7807 (0.4564)    |                                                                                                                         
|    041     |          ---          |                                                                                                                         
|    042     |          ---          |                                                                                                                         
|    043     |          ---          |                                                                                                                         
|    044     |          ---          |                                                                                                                         
|    045     |          ---          |                                                                                                                         
|    046     |          ---          |                                                                                                                         
|    047     |          ---          |
|    048     |    10.0260 (0.9571)   |
|  Averages  |    5.5517 (0.5300)    |
+------------+-----------------------+

So, better results, but not that better, and possibly overfitted.

Another thing is, can you do single collection calibrations using other collections? Just to make sure collection 000 is not the only one that will produce great results if calibrated alone.

For collections 1, 10, 20 and 30 respectively:

+------------+-----------------------+                                                                                                                         
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+                                                                                                                         
|    001     |    0.2535 (0.9361)    |                                                                                                                         
|  Averages  |    0.2535 (0.9361)    |                                                                                                                         
+------------+-----------------------+  
+------------+-----------------------+                                                                                                                         
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+                                                                                                                         
|    010     |    0.1595 (0.9247)    |                                                                                                                         
|  Averages  |    0.1595 (0.9247)    |                                                                                                                         
+------------+-----------------------+   
+------------+-----------------------+                                                                                                                         
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+                                                                                                                         
|    020     |    0.2207 (0.9824)    |                                                                                                                         
|  Averages  |    0.2207 (0.9824)    |                                                                                                                         
+------------+-----------------------+   
+------------+-----------------------+                                                                                                                         
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+
|    030     |    0.1822 (0.8801)    |
|  Averages  |    0.1822 (0.8801)    |
+------------+-----------------------+

I am really inclined in believing the problem is in the arm joints.

v4hn commented 9 months ago

I am really inclined in believing the problem is in the arm joints.

From what I've seen so far, that's definitely the biggest part of the remaining error.

miguelriemoliveira commented 9 months ago

I am really inclined in believing the problem is in the arm joints.

From what I've seen so far, that's definitely the biggest part of the remaining error.

About this, you can try to add those transformations as additional transforms to be calibrated as well, but we have tried it before only for one or two joints. To do it for all the joints in the arm and head could be too many unknowns.

I am working on a mechanism where we can say, for this transform, only optimize the roll or pitch degree of freedom. If you have an idea of what could be the problems with the arm we could somehow guide the optimization better.

For example, do you think the problem is much more in the angular measurements of the joints in comparison to the dimensions of the links? Would that be a sensible claim, or do we really not know.

One experiment we could do is to run a calibration moving the arm but not the head, to see if the head joints are more problematic than the arm. Would the results in that case be better? How about with the reverse experiment. Move the head and leave the arm still.

@manuelgitgomes , can you please share the "new dataset done with extra care" so I can experiment from my side. I still want to check a few things.

manuelgitgomes commented 9 months ago

Hello!

After calibrating the PR2 with the joint offset calibration, I obtained the results:

+------------+-----------------------+                                                                                                                         
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+                                                                                                                         
|    000     |    2.1676 (0.1764)    |                                                                                                                         
|    001     |    2.0953 (0.1705)    |                                                                                                                         
|    002     |          ---          |                                                                                                                         
|    004     |    1.9132 (0.1557)    |                                                                                                                         
|    005     |    1.5095 (0.1229)    |                                                                                                                         
|    007     |    3.8107 (0.3101)    |                                                                                                                         
|    008     |    2.7891 (0.2270)    |                                                                                                                         
|    009     |    3.5230 (0.2867)    |                                                                                                                         
|    010     |    1.6343 (0.1330)    |                                                                                                                         
|    011     |          ---          |                                                                                                                         
|    012     |          ---          |                                                                                                                         
|    013     |    3.0766 (0.2504)    |                                                                                                                         
|    014     |    2.9835 (0.2428)    |                                                                                                                         
|    015     |    3.2144 (0.2616)    |                                                                                                                         
|    016     |    2.1902 (0.1783)    |                                                                                                                         
|    017     |    0.9187 (0.0748)    |                                                                                                                         
|    018     |    2.1704 (0.1766)    |                                                                                                                         
|    019     |    3.2836 (0.2672)    |                                                                                                                         
|    020     |    1.1954 (0.0973)    |                                                                                                                         
|    021     |    1.9191 (0.1562)    |                                                                                                                         
|    022     |    3.2916 (0.2679)    |                                                                                                                         
|    023     |    1.2041 (0.0980)    |                                                                                                                         
|    024     |    2.7941 (0.2274)    |                                                                                                                         
|    025     |    2.7196 (0.2213)    |                                                                                                                         
|    026     |    1.7987 (0.1464)    |                                                                                                                         
|    027     |          ---          |                                                                                                                         
|    028     |          ---          |                                                                                                                         
|    029     |          ---          |                                                                                                                         
|    031     |    2.2258 (0.1812)    |                                                                                                                         
|    032     |    1.5041 (0.1224)    |                                                                                                                         
|    033     |    2.4969 (0.2032)    |                                                                                                                         
|    035     |    2.7539 (0.2241)    | 
|    036     |    2.1792 (0.1774)    |
|    037     |    2.5041 (0.2038)    |
|    038     |          ---          |
|    039     |    1.8976 (0.1544)    |
|    040     |          ---          |
|    041     |          ---          |
|    043     |    0.6060 (0.0493)    |
|    044     |    2.6726 (0.2175)    |
|    045     |          ---          |
|    046     |          ---          |
|    047     |    3.2025 (0.2606)    |
|    048     |          ---          |
|    049     |          ---          |
|    050     |          ---          |
|    051     |          ---          |
|    053     |    1.8167 (0.1479)    |
|  Averages  |    2.3049 (0.1876)    |
+------------+-----------------------+

Therefore, much better results.

I cannot yet visualize the final result, so take it with a grain of salt. I will work on #717 to try and achieve a good visualization.

miguelriemoliveira commented 9 months ago

Therefore, much better results.

Better, I agree. It went down to half, from 5 to 2.5 pixels on average. Later, I think we should try to improve it by optimizing also the other joint parameters. I have never tried it, so I am not sure the optimization will be able to converge, but its worth a shot.

miguelriemoliveira commented 9 months ago

One question: could it be that the joint biases are non-linear? For the shadow hand perhaps, since the actuations are based in strings, but for the arm joints I do not think so. What do you think?

Also, even if we could come up with a great non linear fitting for correcting the joint values, how would we pass that result to the xacro?

v4hn commented 9 months ago

we should try to improve it by optimizing also the other joint parameters

I guess you refer to the whole set of DH parameters. That will surely add a lot of redundancy to the solution space and I would propose to do that only if we get more evidence along the kinematic chains, e.g., another marker on the elbow or support for contour fitting in the image based on a 3d model.

I also mentioned to Manuel just now that it's worth thinking about the theoretical accuracy you can get because the joint encoders in the PR2 have a minimal resolution of 0.005rad in the joint. Simulating encoder-resolution noise with simulate_joint_noise with rviz set to the camera frame (but without adding noise to the head pan/tilt joints) yields this impression of the best accuracy you can expect:

https://github.com/lardemua/atom/assets/680358/95177c8c-785c-44ee-bfc8-482a6aba6899

That might easily be a few pixels in camera images depending on the joint configuration.

could it be that the joint biases are non-linear? For the shadow hand perhaps, since the actuations are based in strings, but for the arm joints I do not think so. What do you think?

No, for the joints they are not.

The tuning curves of the hall effector sensors in the shadow hand are not perfectly linear, but we discussed that already and it's not relevant (yet).

Also, even if we could come up with a great non linear fitting for correcting the joint values, how would we pass that result to the xacro?

We don't. Transfer functions are not modelled in URDF (which is good imho). The one for the TAMS PR2 shadow-hand is here (as piecewise-linear) and applied by the driver node.

miguelriemoliveira commented 9 months ago

I guess you refer to the whole set of DH parameters.

I am referring to the parameters in the xacro joint node. Origin xyz rpy and axis xyz.

That will surely add a lot of redundancy to the solution space and I would propose to do that only if we get more evidence along the kinematic chains, e.g., another marker on the elbow or support for contour fitting in the image based on a 3d model.

I also think it will add a lot of redundancy, probably too much. But still, its worth a shot since everything is already implemented. I think think we should run it just to make sure it does not converge, as expected.

Your idea of additional markers sounds great. It would require #677 , which would have to be developed but does not sound difficult to do. We could add a calibration pattern on the forearm, another on the arm, etc.

That would provide more data to guide the larger optimization problem. I like the idea.

I also mentioned to Manuel just now that it's worth thinking about the theoretical accuracy you can get because the joint encoders in the PR2 have a minimal resolution of 0.005rad in the joint. Simulating encoder-resolution noise with simulate_joint_noise with rviz set to the camera frame (but without adding noise to the head pan/tilt joints) yields this impression of the best accuracy you can expect:

I agree we should have a clue about the theoretical accuracy we can achieve. Your initial insight seems to be quite complete already.

manuelgitgomes commented 9 months ago

That would provide more data to guide the larger optimization problem. I like the idea.

I have been having some discussions with Michael about possible routes to go from here.

This would be interesting, but Michael suggested to do that with the addition of a new modality: touch. Since we have touch sensors on both end-effectors, we can do something very interesting. I tried exemplifying in a figure:

image

One option would be to have one end-effector, let's say the shadow hand (red arm, green finger tip) as an example, touch the opposite arm (blue arm). From the robot_state_publisher, we would know where the estimated pose of the opposite arm is (dotted purple arm). From the pose of the shadow hand finger where the contact was detected, we can estimate where that contact would have occurred in the estimated pose and calculate the distance d (in pink). This distance could be used as a residual, and it could be dependent on the joints on the chain from the touch sensor to the contact link.

This is still a very rough idea, but what is your opinion @miguelriemoliveira?

miguelriemoliveira commented 9 months ago

This is still a very rough idea, but what is your opinion @miguelriemoliveira?

I like the idea. It is far-fetched, but in a good sense. It reminds me of touch sensing in industrial manipulators.

https://www.youtube.com/watch?v=8IDIv8VtV90

I am working with this a bit on the company project, and the main problem is that when you touch something along a linear axis, you don't really know what you touched. The solution we use in industrial touch sensing is to touch sense planes only. Other surfaces create redundancy.

Look at this example.

image

Lets consider the red sensing axis. The white dot is the start of the sensing motion, and the small red arrow the sensing direction. The red sphere is the collision between the sensing direction and the plane marked with red points.

Now assume that the red plane that is being touched is not a plane at all, but rather a cylinder. That way we would not know if the distance to the intersection is due to the curvature of the cylinder or due to the cylinder being further away.

I am not sure if I am explaining well, but in your example (BTW, the Hamburg cold is terrible for your drawing skills) , I am not sure it would work because the distance between when you expected to touch the arm vs when you actually touched the arm could depend not only on the calibration but also on the shape of the arm. But again, I am still thinking about it ...

In any case, in my opinion, these latest developments are enough already to produce a very good paper. I mean, we added joint calibration to atom, we proved it improves in both simulated and real data.

I know I will loose a lot of popularity with this, but should we not consider the possibility of writing a paper with these results : - )?

manuelgitgomes commented 9 months ago

I am not sure it would work because the distance between when you expected to touch the arm vs when you actually touched the arm could depend not only on the calibration but also on the shape of the arm.

The arm is shaped like a rectangular (or a trapezoidal) prism, so it is not a cyllinder. I think this solves most of your issues with it, right?

I know I will loose a lot of popularity with this, but should we not consider the possibility of writing a paper with these results : - )?

Honestly, I have no idea. We have had very successful papers using ATOM and not changing the methodology, as is the case now. This could result in a paper yes, but it might depend on the reviewer, as some are very strict with cases like this.

Nevertheless, if this is to be written, I prefer to write this after going home. I do not think that my time here is best spent writing a paper, while I could be working on a more complex thing that might have changes on methodology/adding a new modality, etc..., and write a paper about that at the end of my stay. Then we could better see if this paper is warranted and I can take a month of my time to write it. Is this reasonable?

miguelriemoliveira commented 9 months ago

Yes, I think so. Let's discuss more towards the end of your stay.

manuelgitgomes commented 9 months ago

Hello!

After recording a xacro file with the chessboard and changing the joint states manually, I have this video:

https://github.com/lardemua/atom/assets/58152228/81968fd0-3e42-4c30-8bf7-14bf24963a4c

This does not seem really good... Does this seem like 2 pixels for you? Could the error be in the visualization?

miguelriemoliveira commented 9 months ago

Hi @manuelgitgomes ,

strange. I think we should have better results. Visually, it looks more than 2 pixels.

manuelgitgomes commented 9 months ago

The visualization was bad due to #773, because the camera intrinsics were not updated in the bagfile.

If I try to calibrate only the extrinsics, I have:

https://github.com/lardemua/atom/assets/58152228/738323a2-4bc9-44b6-9a53-89ebd11bdf50

manuelgitgomes commented 9 months ago

Results of the larger dataset (Avg. 13px):

calibration_results.csv

miguelriemoliveira commented 9 months ago

Hi @manuelgitgomes ,

The results are quite nice already. However, I am missing the big picture. What was the video when we had no calibration? Is the improvement notorious?

manuelgitgomes commented 9 months ago

The results are quite nice already. However, I am missing the big picture. What was the video when we had no calibration? Is the improvement notorious?

Yes, there are notorious improvements:

https://github.com/lardemua/atom/assets/58152228/80e736c6-8584-4f18-bed7-b32bf54c5477

I also made a t-sne visualization for our data. It generates the TSNE embedding for the joint states of each collection. This then is plotted and colored accordingly to the residual of that collection at the end of the calibration. The objective is to figure out if there is any connection between the joint states and the errors.

We had these results.

Small dataset: image

Large dataset: image(1)

In the large dataset we can see 4 large clusters. These might be because I used 4 different poses for the head pan joint. We can see some concentration of the yellow (large residuals) in some clusters, there might be a correlation in there.

miguelriemoliveira commented 9 months ago

Hi @manuelgitgomes ,

is it just me? I don't see any obvious improvement. Can you please send a side by side screenshot of the original and the calibrated that clearly shows the improvement?

miguelriemoliveira commented 9 months ago

About the graphs, I have no experience with those so no comments.

manuelgitgomes commented 9 months ago

is it just me? I don't see any obvious improvement. Can you please send a side by side screenshot of the original and the calibrated that clearly shows the improvement?

Example of old: image

Of new: image

The overlap between the expected pose of the arm is better in the new when compared to the old.

miguelriemoliveira commented 9 months ago

Ahhh, great! I like it. It definitely looks better.

You can now tell @v4hn your work is done and you will be visiting Germany for the remainder of your time there : -)

Are you going to do the experiment where you try to optimize all joint parameters? I know we expect it to fail, but I wanted to make sure it does fail.

v4hn commented 9 months ago

The overlap between the expected pose of the arm is better in the new when compared to the old.

I'm not convinced. The arm fits better, but the gripper tip fits worse, doesn't it? Why would I want higher accuracy at the elbow at the cost of worse accuracy in the gripper? 😂

Your work is done

That's ONE arm, right? 🤷🥊

miguelriemoliveira commented 9 months ago

I'm not convinced. The arm fits better, but the gripper tip fits worth, doesn't it? Why would I want higher accuracy at the elbow at the cost of worse accuracy in the gripper

@v4hn makes a good point. Unless we want to start a new trend in elbow based manipulation we should get better results ...

manuelgitgomes commented 9 months ago

Hello @miguelriemoliveira.

Yesterday, I recorded a new big bagfile and dataset with some bugs corrected.

The results are not good and I cannot figure out why. We are having an error of around 13 pixels.

I tried to divide this dataset into 4 different one, one for each head pan joint state. The errors achieved were smaller (4.6, 6, 7.5, and 6.5), but far from perfect. The estimation of joint offsets between calibrations was at max 0.025 radian, which is significant.

What do you think might be the problem?

miguelriemoliveira commented 9 months ago

Hi @manuelgitgomes ,

perhaps we can start new issues for new focused topics. This is now very long.

About the problem, I am not sure. We can talk a bit if you want ...

Can you run the joint calibration atom example fine in your system?

https://github.com/lardemua/atom/tree/noetic-devel/atom_examples/jcpbbot

Another question: using the previous dataset, do you still get the results we had before?

manuelgitgomes commented 8 months ago

Hello @miguelriemoliveira and @v4hn

So, some improvements here. I used the same poses for calibration that Pradeep used in his article. When using the full dataset, I get these residuals:

+------------+-----------------------+                                                                                                                         
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+                                                                                                                         
|    000     |         7.8983        |                                                                                                                         
|    001     |         6.4473        |                                                                                                                         
|    003     |         3.7911        |                                                                                                                         
|    004     |         2.1774        |                                                                                                                         
|    005     |         4.1398        |
|    006     |         2.1575        |
|    007     |         6.4122        |
|    008     |         6.1659        |
|    010     |         1.8288        |
|    011     |         4.0807        |
|    012     |         5.0716        |
|    013     |         2.8953        |
|    014     |         4.6414        |
|    015     |         7.1114        |
|    016     |         2.7614        |
|    017     |         2.4105        |
|    018     |         2.1460        |
|    019     |         2.3421        |
|    020     |          ---          |
|    023     |         4.3039        |
|    024     |         2.7767        |
|    025     |         7.5943        |
|    026     |         4.2474        |
|    027     |         7.7379        |
|    029     |         5.1731        |
|    030     |         9.5112        |
|    031     |         3.0053        |
|  Averages  |         4.5703        |
+------------+-----------------------+

Which are way better than the previous ones with the head moving and even comparable to the ones Pradeep achieved (0.5 pixels in 480p camera, while we have a 2K camera).

To try and evaluate this, I split the dataset in 2 (#808) to have train and test dataset. I calibrated the train dataset:

+------------+-----------------------+                                                                                                               [
| Collection | azure_rgb_camera [px] |                                                                                                                         
+------------+-----------------------+                                                                                                                         
|    000     |         6.3040        |                                                                                                                         
|    001     |         2.8596        |                                                                                                                         
|    003     |         2.9819        |                                                                                                                         
|    005     |         1.7385        |                                                                                                                         
|    007     |         3.5621        |                                                                                                                         
|    008     |         3.1022        |                                                                                                                         
|    010     |         2.3968        |                                                                                                                         
|    012     |         3.4409        |                                                                                                                         
|    013     |         3.1641        |                                                                                                                         
|    015     |         5.0994        |                                                                                                                         
|    016     |         3.7723        |                                                                                                                         
|    018     |         3.2393        |                                                                                                                         
|    019     |         5.3756        |                                                                                                                         
|    023     |         6.4788        |                                                                                                                         
|    026     |         3.6310        |                                                                                                                         
|    027     |         4.8777        |                                                                                                                         
|    031     |         4.6758        |                                                                                                                         
|  Averages  |         3.9235        |                                                                                                                         
+------------+-----------------------+      

And then tried an evaluation, but I am not fully certain this is the correct one. Since this is a single camera calibration, I ran an intercollection rgb to rgb evaluation. Because the pattern is fixed to the end-effector, I used that as world frame:

rosrun atom_evaluation inter_collection_rgb_to_rgb_evaluation -train_json $ATOM_DATASETS/pr2/train_20240105/atom_calibration_azure_rgb_camera_train.json -test_json $ATOM_DATASETS/pr2/train_20240105/dataset_test.json -ss azure_rgb_camera -st azure_rgb_camera -wf l_gripper_l_finger_tip_frame -uic

And got the results:

Averages   |  21.6276  |   11.0925   |   16.5317   |  694.8040  |  99.2284 

These results seem bad, honestly. I might have ran the wrong evaluation.

However, I want to put things in perspective. When running the same evaluation with the calibrated dataset as test dataset as well:

rosrun atom_evaluation inter_collection_rgb_to_rgb_evaluation -train_json $ATOM_DATASETS/pr2/train_20240105/atom_calibration_azure_rgb_camera_train.json -test_json $ATOM_DATASETS/pr2/train_20240105/atom_calibration_azure_rgb_camera_train.json -ss azure_rgb_camera -st azure_rgb_camera -wf l_gripper_l_finger_tip_frame -uic 

I got the results:

 Averages   |  15.1850  |    8.8323   |   10.4911   |  757.2637  |  100.9587

So, not much better, this might indicate this is the wrong evaluation.

Other thing to consider is the results of Pradeep, which are only presented in this graph for camera calibration: image

The errors are of the same magnitude we have here, with a much smaller resolution...

Do you have anything to say about this?