Reset odometry

classic Classic list List threaded Threaded
9 messages Options
Reply | Threaded
Open this post in threaded view
|

Reset odometry

senia
Hi,
I stumbled upon a problem(kind of asked previously here), in which I want to start calculating the odometry again when losing it(red screen) after some frames, saving the previous odometry and data too.
i.e, when I finish mapping I could export(for example) several poses files(two for each lost odometry event).
I saw that it's possible using ROS(from the answer in the attached link) - with "Odom/ResetCountdown", yet I didn't found this option in the standalone application.
Why are there differences between the two applications?
How hard is it to add it?
What is the fastest and easiest way to make it work that way?
Thanks.
Reply | Threaded
Open this post in threaded view
|

Re: Reset odometry

matlabbe
Administrator
Hi,

All parameters of the rtabmap library are both available in ROS and the standalone, but sometimes not exactly with the same name. For example, "Odom/ResetCountdown" is under Odometry panel with label:
Automatically reset odometry after X consecutive images on 
which odometry cannot be computed (value=0 disables auto-reset). 
When reset, the odometry starts from the last pose computed.

The problem when resetting the odometry to previous pose computed is that RTAB-Map doesn't know there is a discontinuity, creating only one graph. Well, I opened an issue about that.

Tip: To make sure you are looking the same parameter as in Parameters.h, you can mouse over the display item (spinbox, checkbox,...) of the parameter as in this screenshot:


cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Reset odometry

senia
Thank you, the opened-issue is right to the point.
Reply | Threaded
Open this post in threaded view
|

Reset Odometry and StartNewMapOnLoopClosure

arun
This post was updated on .



Hi Matlabbe,

I am now executing the Rtab without any threads or events so i can know the execution of your algorithms.I was using ROS Before and i was knowing how to reset the odom(Odom/ResetCountdown=1) and Rtabmap/StartNewMapOnLoopClosure=true in the launch file.
However now i am using cpp Project and i see, the same red screens with this error.I tried changing the parameters.h file in the rtabmap/core/....parameters.h .However the error still persists.Could you help me to resolve the error.Advance thanks.

Also as the usage of the file says,and as the example here for execution without threads,the calibration directory and calibration name are the same :
./rtabmap-noEventsExample 20 2 10 stereo_20hz stereo_20Hz stereo_20hz/left stereo_20hz/right .it should be given to the directory and file name right?like calib_dir: /home/user1/rtab_occupancy/stereo_20Hz
and calibname: stereo_20Hz_left.yaml

I would like to look into your occupancy grid mapping,which is my main objective.You could give me some suggestions.
Reply | Threaded
Open this post in threaded view
|

Re: Reset Odometry and StartNewMapOnLoopClosure

arun
Hi,
I managed to solve the issue above and its working good with c++ no events and stereo example.However i want to actually get local occupancy grid map from each of the pointclouds.I saw a post that describes the code for the mapping in the c++ rgbd example,however i see the execution is different in stereo case than from RGBD Case.Could you show how i can get the occupancy grid in the c++stereo,no threads and events example?Also provide some tips about ur algorithm about mapping to grids,that would be really intuitive.
Reply | Threaded
Open this post in threaded view
|

Re: Reset Odometry and StartNewMapOnLoopClosure

matlabbe
Administrator
Hi,

Try this:
ParametersMap odomParameters;
odomParameters.insert(ParametersPair(Parameters::kOdomAlignWithGround(), "true"));
// Overwrite some odometry parameters
//odomParameters.insert(ParametersPair(Parameters::kOdomResetCountdown(), "1"));
Odometry * odom = Odometry::create(odomParameters);

ParametersMap parameters;
parameters.insert(ParametersPair(Parameters::kRGBDCreateOccupancyGrid(), "true"));
//Overwrite default Grid parameters:
//parameters.insert(ParametersPair(Parameters::kGrid3D(), Parameters::defaultGrid3D()));
//parameters.insert(ParametersPair(Parameters::kGridCellSize(), Parameters::defaultGridCellSize()));
//parameters.insert(ParametersPair(Parameters::kGridRangeMax(), Parameters::defaultGridRangeMax()));
Rtabmap rtabmap;
rtabmap.init(parameters, "output.db");

After mapping, open the database in rtabmap-databaseViewer:
$ rtabmap-databaseViewer output.db
  In 3D View, select Grid and uncheck Cloud to better see the points used for the local grid. You can press "2" on keyboard to set colormap to red=obstacle and green=ground.


Under Grid sub panel in Core Parameters view, you can change Grid parameters to see what they do, then do Edit -> Regenerate local grid maps... to regenerate all the local grids.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Reset Odometry and StartNewMapOnLoopClosure

arun
Hi Mathiew,

Thanks alot for your support.I really appreciate your efforts in clearing the doubts.I can see the local maps now.

I face an issue with debugging with gdb. I have builded the repository with  ~/rtabmap-0.19.3-melodic/build$ cmake -DCMAKE_BUILD_TYPE=Debug .. and i can debug the codes. However i see ,in gdb i get error,saying "No Source available ",in certain files including rtabmap.cpp when i debug. I am not sure if the cmakeLists is rightly compiled for debugging purpose for all of nodes?I am following the No THREADS and EVENTS example.




Regards,
Arun Sid.



Reply | Threaded
Open this post in threaded view
|

Re: Reset Odometry and StartNewMapOnLoopClosure

matlabbe
Administrator
Hi Arun,

The lines are shown but gdb cannot open the files for some reason. I am not an expert of GDB so I cannot really help on this other than looking on Google. Depending at which level you want to debug (like inside third party functions), you may have to build the dependencies in debug too (like OpenCV).

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Reset Odometry and StartNewMapOnLoopClosure

arun
Thanks a lot Mathiew. I will have a look at it closely.