Odometry from Isaac Ros Slam not updating

I’ve setup the isaac ros slam and it is subscribing to my images from gazebo simulation and publishing all the topics. However, the visual_slam/vis/observations_cloud topic is empty resulting the /visual_slam/vis/slam_odometry to be not moving even though my drone is moving as shown in the videos. My environment have enough objects, hence I assume finding features is not an issue

This is my launch file

# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
# Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# SPDX-License-Identifier: Apache-2.0

import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def generate_launch_description():
    """Launch file which brings up visual slam node configured for Isaac Sim."""
    visual_slam_node = ComposableNode(
        name='visual_slam_node',
        package='isaac_ros_visual_slam',
        plugin='nvidia::isaac_ros::visual_slam::VisualSlamNode',
        remappings=[('visual_slam/image_0', '/camera_left/image'),
                    ('visual_slam/camera_info_0', '/camera_left/info'),
                    ('visual_slam/image_1', '/camera_right/image'),
                    ('visual_slam/camera_info_1', '/camera_right/info'),
                    ('visual_slam/imu', '/imu')],
        parameters=[{
                    'use_sim_time': True,
                    'denoise_input_images': False,
                    'rectified_images': False,
                    'enable_slam_visualization': True,
                    'enable_observations_view': True,
                    'enable_landmarks_view': True,
                    'enable_imu_fusion': True, 
                    'enable_debug_mode': True,
                    'enable_verbosity': True,
                    'debug_dump_path': '/tmp/cuvslam',
                    'base_frame': 'base_link',
                    'map_frame': 'map',
                    'odom_frame': 'odom',
                    'verbosity': 1,
                    'input_imu_frame': 'base_link',
                    'image_jitter_threshold_ms': 50.0
                    }]
    )

    visual_slam_launch_container = ComposableNodeContainer(
        name='visual_slam_launch_container',
        namespace='',
        package='rclcpp_components',
        executable='component_container',
        composable_node_descriptions=[
            visual_slam_node,
        ],
        output='screen',
    )

    return launch.LaunchDescription([visual_slam_launch_container])

Guess that the IMU’s coordinate system name is not set, and there is no further problem from the launch file, you can check from the log file to see if there is an error or if the initialization is complete.

This is what printed out in my console. After that it doesn’t print anything else

[INFO] [launch]: All log files can be found below /home/admin/.ros/log/2025-08-21-19-30-44-897302-tingsheng-1152
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container-1]: process started with pid [1164]
[component_container-1] [INFO] [1755797445.234307410] [visual_slam_launch_container]: Load Library: /workspaces/isaac_ros-dev/install/isaac_ros_visual_slam/lib/libvisual_slam_node.so
[component_container-1] [INFO] [1755797445.287335163] [visual_slam_launch_container]: Found class: rclcpp_components::NodeFactoryTemplate<nvidia::isaac_ros::visual_slam::VisualSlamNode>
[component_container-1] [INFO] [1755797445.287398173] [visual_slam_launch_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nvidia::isaac_ros::visual_slam::VisualSlamNode>
[component_container-1] [INFO] [1755797445.378152811] [NitrosContext]: [NitrosContext] Loading extension: gxf/lib/std/libgxf_std.so
[component_container-1] [INFO] [1755797445.379104308] [NitrosContext]: [NitrosContext] Loading extension: gxf/lib/libgxf_isaac_gxf_helpers.so
[component_container-1] [INFO] [1755797445.381104964] [NitrosContext]: [NitrosContext] Loading extension: gxf/lib/libgxf_isaac_sight.so
[component_container-1] [INFO] [1755797445.383275572] [NitrosContext]: [NitrosContext] Loading extension: gxf/lib/libgxf_isaac_atlas.so
[component_container-1] 2025-08-21 19:30:45.389 WARN  external/com_nvidia_gxf/gxf/std/program.cpp@538: No GXF scheduler specified.
[component_container-1] [INFO] [1755797445.389359681] [NitrosContext]: [NitrosContext] Loading extension: gxf/lib/multimedia/libgxf_multimedia.so
[component_container-1] [INFO] [1755797445.393039858] [visual_slam_node.ManagedNitrosSubscriber]: Starting Managed Nitros Subscriber
[component_container-1] [INFO] [1755797445.393721618] [visual_slam_node.ManagedNitrosSubscriber]: Starting Managed Nitros Subscriber
[component_container-1] [INFO] [1755797445.405682528] [visual_slam_node]: cuVSLAM version: 12.6
[component_container-1] [INFO] [1755797445.550328313] [visual_slam_node]: Time taken by CUVSLAM_WarmUpGPU(): 0.144613
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/visual_slam_node' in container '/visual_slam_launch_container'
[component_container-1] [INFO] [1755797445.552655800] [visual_slam_node]: Initializing cuVSLAM.
[component_container-1] [INFO] [1755797445.552794736] [visual_slam_node]: Use use_gpu: true
[component_container-1] [INFO] [1755797445.552804563] [visual_slam_node]: Enable IMU Fusion: true
[component_container-1] [INFO] [1755797445.552810892] [visual_slam_node]: gyroscope_noise_density: 0.000244
[component_container-1] [INFO] [1755797445.552818662] [visual_slam_node]: gyroscope_random_walk: 0.000019
[component_container-1] [INFO] [1755797445.552825134] [visual_slam_node]: accelerometer_noise_density: 0.001862
[component_container-1] [INFO] [1755797445.552831943] [visual_slam_node]: accelerometer_random_walk: 0.003000
[component_container-1] [INFO] [1755797445.552839113] [visual_slam_node]: frequency: 200.000000
[component_container-1] [INFO] [1755797447.499601740] [visual_slam_node]: Time taken by CUVSLAM_CreateTracker(): 1.946754
[component_container-1] [INFO] [1755797447.499881894] [visual_slam_node]: cuVSLAM tracker was successfully initialized.
[component_container-1] [WARN] [1755797447.663480780] [visual_slam_node]: Delta between current and previous frame [131.000000 ms] is above threshold [50.000000 ms]

This is what written on my log files

1755797444.8980365 [INFO] [launch]: All log files can be found below /home/admin/.ros/log/2025-08-21-19->
1755797444.8981378 [INFO] [launch]: Default logging verbosity is set to INFO
1755797444.9840829 [INFO] [component_container-1]: process started with pid [1164]
1755797445.5518517 [INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/visual_slam_node' in>
1755797532.7106118 [WARNING] [launch]: user interrupted with ctrl-c (SIGINT)
1755797533.5795510 [INFO] [component_container-1]: process has finished cleanly [pid 1164]

The logs indicate initialization is complete. If cuvslam doesn’t respond, there might be a problem with the input topic. You can check the node input topic to see if it’s correct. Additionally, the official launch file uses packages such as isaac_ros_image_proc to correct input image data. You can check to see if these packages are running correctly. Also, if your launch file has the rectified_images option disabled, you need to ensure that the camera_info for the corresponding image provides correct internal and external parameter information. You can try enabling it.

My cameras are 0.1 meter apart and here are the camera infos

header:
  stamp:
    sec: 802
    nanosec: 950000000
  frame_id: camera_left
height: 240
width: 320
distortion_model: plumb_bob
d:
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
k:
- 277.1
- 0.0
- 160.5
- 0.0
- 277.1
- 120.5
- 0.0
- 0.0
- 1.0
r:
- 1.0
- 0.0
- 0.0
- 0.0
- 1.0
- 0.0
- 0.0
- 0.0
- 1.0
p:
- 277.09999084472656
- 0.0
- 160.50000000745058
- 0.0
- 0.0
- 277.1000003814697
- 120.50000002607703
- 0.0
- 0.0
- 0.0
- 1.0
- 0.0
binning_x: 0
binning_y: 0
roi:
  x_offset: 0
  y_offset: 0
  height: 0
  width: 0
  do_rectify: false
---
header:
  stamp:
    sec: 6
    nanosec: 750000000
  frame_id: camera_right
height: 240
width: 320
distortion_model: plumb_bob
d:
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
k:
- 277.1
- 0.0
- 160.5
- 0.0
- 277.1
- 120.5
- 0.0
- 0.0
- 1.0
r:
- 1.0
- 0.0
- 0.0
- 0.0
- 1.0
- 0.0
- 0.0
- 0.0
- 1.0
p:
- 277.09999084472656
- 0.0
- 160.50000000745058
- -27.710000000000004
- 0.0
- 277.1000003814697
- 120.50000002607703
- 0.0
- 0.0
- 0.0
- 1.0
- 0.0
binning_x: 0
binning_y: 0
roi:
  x_offset: 0
  y_offset: 0
  height: 0
  width: 0
  do_rectify: false
---

I tried setting the rectied_images parameter to both True and False but it still exhibits the same behavior.

Below is my rosgraph, all the input topics are publishing

From the information you provided, it seems that there is no problem. You may need more information to judge and wait for the official answer.