PointCloud2 data displayed in RViz but not in RTAB-Map.

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

PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
This post was updated on .
Hi there!

I am trying to get RTAB-Map Visualizer working properly with my setup.

The setup is a Global Shutter-type LiDAR system having an IMU unit. It takes samples simultaneously, similar to Flash LiDAR.

So in ROS2 Jazzy, I am publishing the LiDAR data in PointCloud2 format, in a topic named /metrio_data. That program also looks for IMU data, then are processed and thus a TF is broadcasted for each frame.

Here below is the way I initialize that, in my ROS 2 node called 'grab_and_publish':

# TF info
self.t = TransformStamped()
self.t.header.frame_id = "odom"
self.t.child_frame_id = "base_link"

# PC2 info
self.pc2_header = Header()
self.pc2_header.frame_id = "base_link"
self.pc2_fields = [PointField(name='x', offset=0, datatype=PointField.FLOAT32, count=1),
                            PointField(name='y', offset=4, datatype=PointField.FLOAT32, count=1),
                            PointField(name='z', offset=8, datatype=PointField.FLOAT32, count=1),
                            PointField(name='intensity', offset=12, datatype=PointField.FLOAT32, count=1)]

super().__init__("grab_and_publish")
self.data_pub = self.create_publisher(PointCloud2, "metrio_data", 10)
# Initialize the transform broadcaster
self.tf_broadcaster = TransformBroadcaster(self)


Then how I publish those data:

# PC2
self.pc2_header.stamp = self.get_clock().now().to_msg()
pc2_data = point_cloud2.create_cloud(self.pc2_header, self.pc2_fields, processed_data)
self.data_pub.publish(pc2_data)

# TF
self.t.transform.translation.x = processed_data[0]
self.t.transform.translation.y = processed_data[1]
self.t.transform.translation.z = processed_data[2]
self.t.transform.rotation.x = processed_data[3]
self.t.transform.rotation.y = processed_data[4]
self.t.transform.rotation.z = processed_data[5]
self.t.transform.rotation.w = processed_data[6]
self.t.header.stamp = self.get_clock().now().to_msg()
self.tf_broadcaster.sendTransform(self.t)


By doing so, I can see the results in RViz. The pointCloud2 data are displayed properly and TF based on IMU works too.
--> So everything looks ok on the RViz side.

__________

Then I wanted to show this in RTAB-Map too, and potentially taking advantage of the loop closure detection.

First I tried by launching via this command:

ros2 launch rtabmap_launch rtabmap.launch.py use_rtabmapviz:=true subscribe_depth:=false subscribe_rgb:=false subscribe_scan:=false subscribe_stereo:=false subscribe_scan_cloud:=true scan_cloud_topic:=/metrio_data subscribe_odom_info:=true frame_id:=base_link odom_frame_id:=odom

The Visualizer starts, but it did not work (no data coming in). In the log it seems that RTAB-Map still expects rgbd data. It seems like the parameters I input that way, in the command line, have no effects.

Then I tried by creating a launch file called rtabmap_lidar_only.py and run it via: ros2 launch rtabmap_metrio_package rtabmap_lidar_only.py

The launch file (into which I also remapped for scan_cloud):

from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        Node(
            package='rtabmap_ros',
            executable='rtabmap',
            name='rtabmap',
            output='screen',
            parameters=[
                {'frame_id': 'base_link'},
                {'odom_frame_id': 'odom'},
                {'map_frame_id': 'map'},
                {'subscribe_scan_cloud': True},
                {'scan_cloud_topic': '/metrio_data'},
                {'subscribe_depth': False},
                {'subscribe_rgb': False},
                {'subscribe_scan': False},
                {'subscribe_stereo': False},
                {'subscribe_rgbd': False},
                {'rgbd_odometry': False},
                {'subscribe_odom_info': True},
                {'qos_scan_cloud': 2},
                {'approx_sync': True},
                {'publish_tf': True},
                {'use_sim_time': False}
            ],
            remappings=[
                ('scan_cloud', '/metrio_data')
            ]
        )
    ])


As I did not get any output in RTAB-Map Visualizer, I used that launch file found here (in the accepted answer):
https://robotics.stackexchange.com/questions/91511/is-it-possible-to-use-rtabmap-ros-with-only-scan-data

I replaced the topic names and remapped accordingly, but still no luck. Here is also what I get when I run it:

ros2_ws$ ros2 launch rtabmap_metrio_package rtabmap_lidar_only.py
[INFO] [launch]: All log files can be found below /home/pierre/.ros/log/2025-07-18-08-53-57-277033-pierre-PO5-650
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [rtabmap-1]: process started with pid [1340447]
[rtabmap-1] libpng warning: iCCP: known incorrect sRGB profile
[rtabmap-1] libpng warning: iCCP: known incorrect sRGB profile
[rtabmap-1] libpng warning: iCCP: known incorrect sRGB profile


Also, by running rqt-graph (with any attempt above), I do see the /metrio_data topic, the grab_and_publish node, the TF and RViz. However, RTAB-Map_viz is nowhere to be found.

Please see attached picture of the rqt_graph below.




My questions:

* Any idea about why I do get my data and TF correctly sent to RViz, but not in RTAB-Map?

* Also, do you think the loop closure detection can work with only PC2 + IMU data? Local proximity detection maybe?


Notes:
   * RTAB-Map version:
      2.21.10

   * When RTAB-Map Viz is launched, I do get (every time):
      The configuration file "/home/pierre/.rtabmap/rtabmap.ini" does not exist, it will be created with default parameters.
      and
      RTAB-Map needs a working directory to put the database. By default, the directory "/home/pierre/Documents/RTAB-Map" is used.

Thanks a lot in advance for your help,
Pierre
 
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

matlabbe
Administrator

You may try this launch file: https://github.com/introlab/rtabmap_ros/blob/ros2/rtabmap_examples/launch/lidar3d.launch.py
$ ros2 launch rtabmap_examples lidar3d.launch.py lidar_topic:='/metrio_data frame_id:=base_link

Notes:

* You should not publish odom->base_link TF unless you are computing odometry
* The example above will generate odometry for you
* Ideally, if the sensor provides a timestamp, you should use it for the imu and lidar data.
* Only proximity detection will work without a camera.
* For the rtabmap_viz messages/warnings, if you save at least once the config (ctrl-s), it won't warn you again.
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
Hello Mathieu,

Thank you a lot for your help.

I'll try this very soon and let you know.

Bien à vous,
Pierre
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
In reply to this post by matlabbe
Hello Mathieu,

So now I am using the same timestamp for PC2 data and IMU.

I tried the lidar3d.launch.py by running:
ros2 launch rtabmap_examples lidar3d.launch.py lidar_topic:=/metrio_data frame_id:=base_link

I got an error about deskewing:
Failed to deskew input cloud, aborting odometry update!
Input cloud has these fields: x y z intensity
Input cloud doesn't have "t", "time", "stamps" and "timestamp" field!


I do not have per-point timestamps. So I tried to disable the deskewing functionality, by running:
ros2 launch rtabmap_examples lidar3d.launch.py lidar_topic:=/metrio_data frame_id:=base_link deskewing:=false deskewing_slerp:=false

No change, I still get that same issue. Are those custom parameters (deskewing and deskewing_slerp) not taken into account?
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

matlabbe
Administrator
Hi, normally you would have only need to launch it with "deskewing:=false" ("deskewing_slerp" is ignored if" deskewing" is false):
ros2 launch rtabmap_examples lidar3d.launch.py lidar_topic:=/metrio_data frame_id:=base_link deskewing:=false

[...]
[icp_odometry-1] [INFO] [1753150230.146584051] [icp_odometry]: IcpOdometry: qos                    = 1
[icp_odometry-1] [INFO] [1753150230.146599767] [icp_odometry]: IcpOdometry: scan_cloud_max_points  = -1
[icp_odometry-1] [INFO] [1753150230.146604915] [icp_odometry]: IcpOdometry: scan_cloud_is_2d       = false
[icp_odometry-1] [INFO] [1753150230.146608782] [icp_odometry]: IcpOdometry: scan_downsampling_step = 1
[icp_odometry-1] [INFO] [1753150230.146625780] [icp_odometry]: IcpOdometry: scan_range_min         = 0.000000 m
[icp_odometry-1] [INFO] [1753150230.146632368] [icp_odometry]: IcpOdometry: scan_range_max         = 0.000000 m
[icp_odometry-1] [INFO] [1753150230.146636384] [icp_odometry]: IcpOdometry: scan_voxel_size        = 0.100000 m
[icp_odometry-1] [INFO] [1753150230.146640781] [icp_odometry]: IcpOdometry: scan_normal_k          = 20
[icp_odometry-1] [INFO] [1753150230.146646013] [icp_odometry]: IcpOdometry: scan_normal_radius     = 0.000000 m
[icp_odometry-1] [INFO] [1753150230.146650149] [icp_odometry]: IcpOdometry: scan_normal_ground_up  = 0.000000
[icp_odometry-1] [INFO] [1753150230.146654202] [icp_odometry]: IcpOdometry: deskewing              = false
[icp_odometry-1] [INFO] [1753150230.146657980] [icp_odometry]: IcpOdometry: deskewing_slerp        = true
[...]
Can you confirm that the log above shows "IcpOdometry: deskewing = false" on your end?

I looked in this file, and the error msg "Failed to deskew input cloud, aborting odometry update!" could only happen if "deskewing" parameter is true.

If you have still the problem, can you record a small rosbag and share it so I can test it?

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

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
This post was updated on .
Hello Mathieu,

[message edited to correct a mistake about deskewing]

Thanks again for your precious help. This is greatly appreciated.

I ran:
ros2 launch rtabmap_examples lidar3d.launch.py lidar_topic:=/metrio_data frame_id:=base_link deskewing:=false

deskewing is still True in the log. Please see the icp-odometry log below:

cat icp_odometry_98175_1753198462493.log
[INFO] [1753198462.518863773] [icp_odometry]: Odometry: frame_id               = base_link
[INFO] [1753198462.518927942] [icp_odometry]: Odometry: odom_frame_id          = icp_odom
[INFO] [1753198462.518931696] [icp_odometry]: Odometry: publish_tf             = true
[INFO] [1753198462.518934057] [icp_odometry]: Odometry: wait_for_transform     = 0.200000
[INFO] [1753198462.518937786] [icp_odometry]: Odometry: log_to_rosout_level    = 4
[INFO] [1753198462.518953219] [icp_odometry]: Odometry: initial_pose           = xyz=0.000000,0.000000,0.000000 rpy=0.000000,-0.000000,0.000000
[INFO] [1753198462.518956161] [icp_odometry]: Odometry: ground_truth_frame_id  =
[INFO] [1753198462.518958583] [icp_odometry]: Odometry: ground_truth_base_frame_id = base_link
[INFO] [1753198462.518961132] [icp_odometry]: Odometry: config_path            =
[INFO] [1753198462.518963393] [icp_odometry]: Odometry: publish_null_when_lost = true
[INFO] [1753198462.518965671] [icp_odometry]: Odometry: publish_compressed_sensor_data = false
[INFO] [1753198462.518967859] [icp_odometry]: Odometry: guess_frame_id         =
[INFO] [1753198462.518970105] [icp_odometry]: Odometry: guess_min_translation  = 0.000000
[INFO] [1753198462.518972701] [icp_odometry]: Odometry: guess_min_rotation     = 0.000000
[INFO] [1753198462.518975235] [icp_odometry]: Odometry: guess_min_time         = 0.000000
[INFO] [1753198462.518977747] [icp_odometry]: Odometry: expected_update_rate   = 15.000000 Hz
[INFO] [1753198462.518981199] [icp_odometry]: Odometry: max_update_rate        = 0.000000 Hz
[INFO] [1753198462.518983803] [icp_odometry]: Odometry: min_update_rate        = 0.000000 Hz
[INFO] [1753198462.518986357] [icp_odometry]: Odometry: wait_imu_to_init       = false
[INFO] [1753198462.518988661] [icp_odometry]: Odometry: always_check_imu_tf    = true
[INFO] [1753198462.518990805] [icp_odometry]: Odometry: sensor_data_compression_format = .jpg
[INFO] [1753198462.518993052] [icp_odometry]: Odometry: sensor_data_parallel_compression = true
[INFO] [1753198462.518996952] [icp_odometry]: Odometry: stereoParams_=0 visParams_=0 icpParams_=1
[INFO] [1753198462.519329167] [icp_odometry]: Setting odometry parameter "Icp/CorrespondenceRatio"="0.01"
[INFO] [1753198462.519348587] [icp_odometry]: Setting odometry parameter "Icp/Epsilon"="0.001"
[INFO] [1753198462.519367683] [icp_odometry]: Setting odometry parameter "Icp/Iterations"="10"
[INFO] [1753198462.519374988] [icp_odometry]: Setting odometry parameter "Icp/MaxCorrespondenceDistance"="1.0"
[INFO] [1753198462.519393593] [icp_odometry]: Setting odometry parameter "Icp/MaxTranslation"="3"
[INFO] [1753198462.519403988] [icp_odometry]: Setting odometry parameter "Icp/OutlierRatio"="0.7"
[INFO] [1753198462.519446399] [icp_odometry]: Setting odometry parameter "Icp/PointToPlaneK"="20"
[INFO] [1753198462.519464761] [icp_odometry]: Setting odometry parameter "Icp/PointToPlaneRadius"="0"
[INFO] [1753198462.519495289] [icp_odometry]: Setting odometry parameter "Icp/VoxelSize"="0.1"
[INFO] [1753198462.519609618] [icp_odometry]: Setting odometry parameter "Odom/ScanKeyFrameThr"="0.4"
[INFO] [1753198462.519627796] [icp_odometry]: Setting odometry parameter "OdomF2M/BundleAdjustment"="false"
[INFO] [1753198462.519657396] [icp_odometry]: Setting odometry parameter "OdomF2M/ScanMaxSize"="15000"
[INFO] [1753198462.519676643] [icp_odometry]: Setting odometry parameter "OdomF2M/ScanSubtractRadius"="0.1"
[WARN] [1753198462.521695575] [icp_odometry]: IcpOdometry: Transferring value 0.1 of "Icp/VoxelSize" to ros parameter "scan_voxel_size" for convenience. "Icp/VoxelSize" is set to 0.
[WARN] [1753198462.521702638] [icp_odometry]: IcpOdometry: Transferring value 20 of "Icp/PointToPlaneK" to ros parameter "scan_normal_k" for convenience.
[INFO] [1753198462.523697535] [icp_odometry]: IcpOdometry: qos                    = 1
[INFO] [1753198462.523706572] [icp_odometry]: IcpOdometry: scan_cloud_max_points  = -1
[INFO] [1753198462.523708597] [icp_odometry]: IcpOdometry: scan_cloud_is_2d       = false
[INFO] [1753198462.523710326] [icp_odometry]: IcpOdometry: scan_downsampling_step = 1
[INFO] [1753198462.523728965] [icp_odometry]: IcpOdometry: scan_range_min         = 0.000000 m
[INFO] [1753198462.523731789] [icp_odometry]: IcpOdometry: scan_range_max         = 0.000000 m
[INFO] [1753198462.523733471] [icp_odometry]: IcpOdometry: scan_voxel_size        = 0.100000 m
[INFO] [1753198462.523735569] [icp_odometry]: IcpOdometry: scan_normal_k          = 20
[INFO] [1753198462.523737024] [icp_odometry]: IcpOdometry: scan_normal_radius     = 0.000000 m
[INFO] [1753198462.523738577] [icp_odometry]: IcpOdometry: scan_normal_ground_up  = 0.000000
[INFO] [1753198462.523740245] [icp_odometry]: IcpOdometry: deskewing              = true
[INFO] [1753198462.523741605] [icp_odometry]: IcpOdometry: deskewing_slerp        = false

[INFO] [1753198462.524150175] [icp_odometry]: icp_odometry subscribed to /scan and /metrio_data (make sure only one of this topic is published, otherwise remap one to a dummy topic name).
[INFO] [1753198462.586500515] [icp_odometry]: Odom: ratio=0.000000, std dev=0.000000m|0.000000rad, update time=0.000378s delay=0.001995s
[INFO] [1753198462.675639060] [icp_odometry]: Odom: ratio=0.000000, std dev=0.000000m|0.000000rad, update time=0.000311s delay=0.001657s
[INFO] [1753198462.765806919] [icp_odometry]: Odom: ratio=0.000000, std dev=0.000000m|0.000000rad, update time=0.000128s delay=0.001887s
[INFO] [1753198462.855578360] [icp_odometry]: Odom: ratio=0.000000, std dev=0.000000m|0.000000rad, update time=0.000118s delay=0.001976s


--> So for now I send x, y, z and stamps (instead of intensity, in the PC2 message). I put 10 ms interval between each data point, for the per-point stamps. Thanks to that, no more deskewing error (just a workaround for now, and to see what goes next).

However, I would really need to disable deskewing, to keep intensity in my PC2 message. It seems that ROS2 only accepts 4 entries in the PC2 message, as x,y,z + intensity (or something else).

--> I don't understand why deskewing:=false does not work.
______

Also, our system is different from regular LiDAR systems. It has a narrow field of view, does not rotate, and run at high speed (> 1KHz).

Thus it seems that RTAB-Map cannot compute odometry because of one or some of those factors. Indeed, it warns me about high speed:

[rtabmap_viz-3] [INFO] [1753198446.567842431] [rtabmap_viz]: rtabmap_viz started.
[icp_odometry-1] [WARN] [1753198446.570961697] [icp_odometry]: Odometry: Aborting odometry update, higher frame rate detected (33.397863 Hz) than the expected one (15.000000 Hz). (stamps: previous=1753198446.540458s new=1753198446.570400s)
[icp_odometry-1] [WARN] [1753198446.585891568] [icp_odometry]: Odometry: Aborting odometry update, higher frame rate detected (22.317131 Hz) than the expected one (15.000000 Hz). (stamps: previous=1753198446.540458s new=1753198446.585267s)


And after lowering the speed to 120 Hz, no more higher frame rate detected but it warns me about the low complexity preventing it to initialize the first keyframe and about odometry not provided:

[icp_odometry-1] [ WARN] (2025-07-22 08:34:26.170) OdometryF2M.cpp:1349::computeTransform() Scan complexity too low (0.000028) to init first keyframe.
[icp_odometry-1] [ WARN] (2025-07-22 08:34:26.259) OdometryF2M.cpp:1349::computeTransform() Scan complexity too low (0.000028) to init first keyframe.
[rtabmap-2] [ERROR] (2025-07-22 10:37:05.892) Rtabmap.cpp:1406::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 0 is ignored!
[rtabmap-2] [ERROR] (2025-07-22 10:37:06.952) Rtabmap.cpp:1406::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 0 is ignored!


I am not sure why it says this.

Our system (narrow FOV, grid of 435 lasers, flash) targets a wall at 2.5m away and reconstruct that in RViz without issue.

But it seems that the odometry package of RTAB-Map warns because of that particular system.

Is there a way to tweak RTAB-Map_odometry (Odometry: expected_update_rate and/or something else) to take into account those particularities (especially for framerate and the low complexity problem)?
______

Last thing I noticed, the warning:
icp_odometry subscribed to /scan and /metrio_data (make sure only one of this topic is published, otherwise remap one to a dummy topic name).
Should I remap /scan to a dummy topic name when running the command ros2 launch...?

Have a great day,
Pierre
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

matlabbe
Administrator
You are maybe using an older version of that launch file. Based on this commit, it makes sense that deskewing parameter didn't work, but deskewing_slerp did. I released now ros2 binaries 1 week ago, tohugh maybe not all ros2 releases are "officially" out. You can download the latest version of that file from github directly.

Note that the point stamps should be all set to 0 so that deskewing does nothing, though not required anymore if you use the latest launch file linked above.

For the expected lidar rate, you should adjust it to your lidar.

For the "(make sure only one of this topic is published, otherwise remap one to a dummy topic name)" message, you can ignore if the other topic is not published anyway.

For the rtabmap error about no odometry provided, it is caused by icp_odometry not working for the following reason "Scan complexity too low (0.000028) to init first keyframe". icp_odometry cannot work properly if not all 3 planes (X-Y-Z) are observed at the same time, otherwise we have an unconstrained system. Looking at a flat wall, that is the worst situation. Ideally, always keep in FOV enough geometry containing all three planes ("complexity" higher). For example, point the lidar towards the corner of the room, so you will get constraints in more than 2 axes.

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

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
Mathieu,

This works now.

Some details:
* Indeed, it seems that I was using an older version of RTAB-Map, so the deskewing param. was not taken into account.

* I adjusted the Expected LiDAR rate accordingly to my setup.

* Having a more complex geometry to probe definitely did the trick!

--> Now I do have my PC2 data displayed in RTAB-Map.
Results are quite unstable though, and it gets stuck after some times. I guess it will require some tweaking from my side... but that is a huge step forward for sure.

I'm going to get more familiar with RTAB-Map, and let you know if any question arise from my tests.

Thanks again for your time.

Cheers,
Pierre
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
This post was updated on .
Hello Matthieu.

I was wondering if there is a way to run rtabmap in Silent mode (not printing [INFO] and [WARN] in the Terminal, and also not storing them in Log files).

I tried output='none' but it is not accepted (only 'screen' or 'log' is available).

I managed to get rid of the [INFO] messages by setting ROS2 log level in lidar3d.launch.py (arguments=['--ros-args', '--log-level', 'error'])), but all the warnings from UWARN in RegistrationIcp.cpp are still printing in the Terminal.

Thanks in advance for your help,
Pierre
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

matlabbe
Administrator
Hi Pierre,

For RCLCPP logs, you should indeed use the ros2 way to set the minimum log level.

For internal RTAB-Map's logs, try adding "--uerror" as regular argument to the nodes.

EDIT: we can also use "--nolog" to avoid any logs from RTAB-Map.

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

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
Thank you a lot Matthieu.

The --nolog flag is working great.

As you know I am trying to run our system at higher speed.

At 30 FPS, CPU usage is:
* rtabmap_viz: around 12%
* icp_odometry: around 3%

Currently I can achieve 120 FPS. At that rate, CPU usage is:
* rtabmap_viz: around 35%
* icp_odometry: around 12%

My next available speed – above 120 FPS – is 700 FPS.
At that rate, RTAB-Map Viewer starts to be very unresponsive. So I checked CPU usage:
* rtabmap_viz: around 105%, so maxed out I guess.
* icp_odometry: around 60%

When I check the other CPUs (13th Gen 13700F, 24 in total), most of them are running under 25%. Actually only one is cranking up (I suspect that is the one used by rtabmap_viz).

By chance, is there a way to enable some parallel processing for the rtabmap_viz process, in order to get higher speed?

Thanks again for your help,
Pierre
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
This post was updated on .
Or maybe more simply, can we make rtabmap_viz updating at a lower framerate (so skipping the display of some frames), while processing all data at a higher framerate?

[EDIT] Similar to RViz, where I run at full speed (around 1400 FPS) with RViz refresh rate at 120Hz only.

[EDIT 2] I tried with 'Rtabmap/PublishPeriod': '0.017' (60Hz) and also 'Rtabmap/PublishPeriod': '0.0083' (120Hz), rtabmap_viz gets the same issue (when data are coming in at 700 FPS).

If I understand correctly, 'Rtabmap/PublishPeriod' is set in seconds (as a string).
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

matlabbe
Administrator
We would have to see what are the bottlenecks in the UI side. Basically, you would need to look at MainWindow::processStats() function (called when a map update happened) and MainWindow::processOdometry() function (called after each odometry update). Note that Qt's signals/slots mechanism buffers infinite data if the rendering process takes too long, which could increase the latency of data shown. To minimize this issue, on ROS side, we don't forward odometry data if the UI is still processing the previous data or if max odometry rate parameter is set (you can set "max_odom_update_rate" to rtabmap_viz node to limit odometry rendering rate).

On rendering side, you can disable odometry and/or map visualization in Preferences->3D Rendering settings.

You probably want to disable any caching at high frame rate by unchecking these settings:


Not sure what you are referring by "Rtabmap/PublishPeriod", do you mean Rtabmap/DetectionRate? I don't generally recommend to increase it to more that 1-2 Hz.
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
This post was updated on .
Hello Matthieu,

Thanks again for your precious help.

Actually, unchecking the 3 cache options in the settings allows rtabmap_viz to run at the desired speed (1400 FPS).

[EDIT] To be more precise, I can keep all of the cache options checked but not Cache statistics.

So the problem seems to be resolved thanks to that particular advice!

###########

About profiling the 2 functions (processStats() & processOdometry()), here are the results (with and without cache) using perf profiling tool:

_______________
* Without cache:

- atom CPU:
6.12% 0.01% rtabmap_viz librtabmap_gui.so.0.21.10 [.] rtabmap::MainWindow::processOdometry(rtabmap::OdometryEvent const&, bool)
0.01% 0.00% rtabmap_viz librtabmap_gui.so.0.21.10 [.] rtabmap::MainWindow::processStats(rtabmap::Statistics const&)

- core CPU:
0.71% 0.00% rtabmap_viz librtabmap_gui.so.0.21.10 [.] rtabmap::MainWindow::processOdometry(rtabmap::OdometryEvent const&, bool)
0. 04% 0.00% rtabmap_viz librtabmap_gui.so.0.21.10 [.] rtabmap::MainWindow::processStats(rtabmap::Statistics const&)

____________
* With cache:

- atom CPU:
0.02% 0.00% rtabmap_viz librtabmap_gui.so.0.21.10 [.] rtabmap::MainWindow::processOdometry(rtabmap::OdometryEvent const&, bool)
n/a

- core CPU:
16.49% 0.03% rtabmap_viz librtabmap_gui.so.0.21.10 [.] rtabmap::MainWindow::processOdometry(rtabmap::OdometryEvent const&, bool)
0.05% 0.00% rtabmap_viz librtabmap_gui.so.0.21.10 [.] rtabmap::MainWindow::processStats(rtabmap::Statistics const&)

Below are 2 screenshots of the main perf results, in case it's useful, when cache options are checked:





Have a great afternoon,
Pierre
Reply | Threaded
Open this post in threaded view
|

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

matlabbe
Administrator
Hi Pierre,

Indeed, caching statistics is a big one.

I would expect processStats() increasing in CPU usage over time, as the map increases in size. I know there is a slight performance issue with the path rendering in 3D map view. The worst rendering performance issue is if you show the gravity links, but this is not enabled by default.

If you show the GraphView, some processing will be done to assemble/render the occupancy grid map and the map's graph, and similarly, if the occupancy grid is also shown in 3D Map view (not shown by default).

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

Re: PointCloud2 data displayed in RViz but not in RTAB-Map.

pierrec
Matthieu,

Good to know.

Thanks again!
Pierre