atom
atom copied to clipboard
Add noise to specific transformation (used for odom in softbot)
From our discussion it seems the best way is to create an argument in calibrate.
This is implemented.
To run it :
rosrun atom_calibration calibrate -json $ATOM_DATASETS/softbot/dataset_perfect_simulation/dataset_corrected.json -v -ntfv 0.1 1 -ntfl "world:base_footprint"
It's using a custom parser to parse pairs of transformations : https://github.com/lardemua/atom/blob/7ddb800d15fcab58bfde8929b1bfb37bd08a10e5/atom_calibration/scripts/calibrate#L114-L115
It allows adding a certain noise to a list of unlimited transformations, even though I will only need to add one. It's implemented to be future-proof.
The new flags are -ntfl (noisy tf links) and -ntfv(noisy tf values), they are coded to be mutually inclusive meaning only works if either both or none are provided.
These are the results of adding 1 meter/1 rad of noise to the world-base_footprint transformation : Original
{'child': 'base_footprint',
'parent': 'world',
'quat': array([-0.53705174, -0.25723141, -0.47395355, 0.64867208]),
'trans': [-0.2705780038130975, -0.6439190834582494, 0.7109601381499732]}
With noise
{'child': 'base_footprint',
'parent': 'world',
'quat': [0.000198939124377559,
-0.0012093277765717638,
0.15914427290610855,
0.9872545762622423],
'trans': [-0.04164416173522156, 0.01992514094865932, -0.0010090617969430225]}
I also implemented a simple check to make the addNoiseToInitialGuess() more efficient : https://github.com/lardemua/atom/blob/7ddb800d15fcab58bfde8929b1bfb37bd08a10e5/atom_core/src/atom_core/dataset_io.py#L791-L793
Previously, if no noise was specified it would still compute it and add 0 to all collections.
What I didn't do because I wasn't sure if it would be useful would've been to add different noise to different transforms if multiple pairs were parsed in.
Hi @brunofavs ,
sorry for the delayed response. great work! Some comments, of course :-)
help="Pairs of links defining the transformations to which noise will be added, in the format link1:link2,linkA,linkB")
noisy_tf_values. You should specify in the help of the argparse that the 2 values we add are for rotation and translation? Or is it the other way? Also, the units.
This is confusing "link1:link2,linkA,linkB". Is it : or ,?
These are the results of adding 1 meter/1 rad of noise to the world-base_footprint transformation : Original
{'child': 'base_footprint', 'parent': 'world', 'quat': array([-0.53705174, -0.25723141, -0.47395355, 0.64867208]), 'trans': [-0.2705780038130975, -0.6439190834582494, 0.7109601381499732]} With noise
{'child': 'base_footprint', 'parent': 'world', 'quat': [0.000198939124377559, -0.0012093277765717638, 0.15914427290610855, 0.9872545762622423], 'trans': [-0.04164416173522156, 0.01992514094865932, -0.0010090617969430225]}
This is not correct. Notice how the quat changes from an array on input (I don't think it should be an array) to a list on the output. Adding noise should add noise, not change the type of the variables.
I also implemented a simple check to make the addNoiseToInitialGuess() more efficient : atom/atom_core/src/atom_core/dataset_io.py
Lines 791 to 793 in 7ddb800
if args['noisy_initial_guess'] == [0,0]: print("No noise added to transform's initial guess") return Previously, if no noise was specified it would still compute it and add 0 to all collections.
What I didn't do because I wasn't sure if it would be useful would've been to add different noise to different transforms if multiple pairs were parsed in.
This is a different subject. You should have created a new issue for this. I am not sure about the implications of your fix. As I told you, calibrate is a very large code. A change may have unintended consequences. These kind of changes outside the scope of your intervention should be discussed between us before being pushed. Or you could have created a PR for that ...
Apart from all the comments, great work.
Reopening so @brunofavs can do the suggested fixes.
Hey @miguelriemoliveira,
noisy_tf_values. You should specify in the help of the argparse that the 2 values we add are for rotation and translation? Or is it the other way? Also, the units.
I might've not been very clear on my initial comment. There are 2 flags : https://github.com/lardemua/atom/blob/4c2e33607a40a449499c563ed1fe0e68e870a16d/atom_calibration/scripts/calibrate#L114-L117
-ntfl defines pairs of links to which noise will be added
-ntfv specifies how much translation and rotation noise will be added.
Nevertheless, I touched up the -help to make it more clear.
This is not correct. Notice how the quat changes from an array on input (I don't think it should be an array) to a list on the output. Adding noise should add noise, not change the type of the variables.
I have to investigate this because it might be a greater issue we're facing, because I used the addNoiseToTF() function already developed in the past, I didn't touch the part where the noise is actually added.
This is a different subject. You should have created a new issue for this. I am not sure about the implications of your fix. As I told you, calibrate is a very large code. A change may have unintended consequences. These kind of changes outside the scope of your intervention should be discussed between us before being pushed. Or you could have created a PR for that ...
You are totally right, I shouldn't have made this change. It's only on my current branch but I will revert it and create a issue for that. I thought it was a really small thing not worthy of a issue but this kindof mentality is the root of possible problems in the future.