-
Notifications
You must be signed in to change notification settings - Fork 787
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
Regenerate processing time graph for Rtabmap process #1336
Comments
@matlabbe Thanks. This helps a lot. For our database, we are getting graph like this, We have Map assembling time, but its very less hence invisible in the graph. Below one is separate graph of Map assembling. From this graph, it seems Global map assembling is not time consuming process. Is it on expected line ? You mentioned in other thread as well as in paper, that Map assembling is computationally heavy process. Are we missing something ? Also, we did detailed time profile of STM, and other modules but can't able to find which function does Global map assembling. Is it part of Rtabmap.cpp or Corewrapper.cpp ? Can you help us pointing that function ? |
... (and more precisely) when there is a loop closure and graph deformation is over The global map assembling is called from the MapsManager called from here, but the actual implementation is in those files: https://github.com/introlab/rtabmap/tree/master/corelib/src/global_map (depending on the topic we are subscribing). The global maps are not generated if no one is subscribed on one of them. The biggest update spikes will happen when the map has to be fully updated because of a loop closure or memory management retrieved past data back in the current WM (or more explicitly when this is true). Depending on the GlobalMap flavor, the full update may take more or less time (e..g, 2d maps are relatively fast to regenerate). In this paper Table 10, the last two columns show a comparison depending on the map used and if a loop closure happened or not. As you can see, when there is no loop closure, appending new local grids to global map is relatively fast (maybe what you are seeing). |
Hi @matlabbe, continuing with above issues we kept different decimation on pointcloud, coming from pointcloudXYZ node with decimation kept as 1, 2 and 4. This can be viewed in below graphs For decimation 1 and decimation 2 the neighbors value are 105 and 292 respectively, shouldn't be it like for more data points neighbors should be more as compared to case for decimation 2 and decimation 4, can you help us with reason for which this behavior can be seen here. |
The number of neighbor links are roughly the same number of nodes added to the graph. I don't now what |
@matlabbe Thanks, is Rtabmap/UpdateRate same as Rtabmap/DetectionRate which is 30 in all three cases, for processing time |
@matlabbe If Memory management is disabled, and actual processing time exceeds the Rtabmap/detectionrate, then what happen ?
|
@samarth-eic Like what I thought, the processing time is high, so it cannot process in real-time at rate of 30 Hz (
A lot of time is used to create the local grids, that could be optimized like this:
Example by reprocessing on my computer with these values:
To improve proximity detection time, if you don't care not keeping the raw laser scans, is to downsample the scans with
@naitiknakrani-eic |
@matlabbe That's fantastic to know how these parameters really help in optimizing computation time. "the rate is limited either by Rtabmap/DetectionRate or actual maximum rate rtabmap can process based on the machine", Like this is the reason why we kept it at 30 in order to achieve as max throughput as possible. Keeping detection rate at 1, actually underutilized processing capabilities of NVIDIA boards. |
Here some reasons why we set
Where you would want to put more computation resources first is the visual odometry or lidar odometry, for which higher frequency usually means better accuracy and lower drift. Then equally important, robot controller and obstacle detection with low latency. Then lastly, re-localization/mapping. cheers, |
Hi @matlabbe Thanks for your explanation and sorry for delay in revert back. We were understanding code and logic for NormalSegmentation. It was surprise to see that the Rtabmap works and create occupancy with keeping NormalSegmentation = off. It is a process which takes lot of CPU resources and contributes to ~60% of total timing (Refer First Figure 1 of early response, Timing/total avg - 1266 ms and Timing/occupancy - 781 ms). This parameter skips the following function from file "rtabmap/corelib/include/rtabmap/core/impl
Can you please tell us in what scenario the segmentation is required and must ? what was original thought process behind implementing it ? |
The normal segmentation is based on that experiment: http://wiki.ros.org/rtabmap_ros/Tutorials/StereoOutdoorNavigation#Global_costmap :
We enable it by default because it is more safe in general and easier to use to detect small obstacles. When we disable it, we do a simple passthrought filtering at some height (e..g, 10 cm) over the ground, which is very fast to do, but requires more tuning to detect small obstacles and cannot handle a ground that is not perfectly flat (e.g., ramps or slopes). Here another example from this paper: For less-powerful computers and/or the robot is moving always on a flat floor, disabling it can give a good boost of performance. |
Hi @francoisferland @matlabbe,
Can you help me to regenerate processing time logs for creating graph as shown in figure below?
Any tools will be helpful ? If tools are not available, can you tell methodology used to derive these graph ?
Thanks
The text was updated successfully, but these errors were encountered: