ZED GNSS fusion /zed/zed_node/pose/filtered not published when having the ERROR(warning in reallity) of Ingest error occurred when ingesting GNSSData: GNSS DATA COVARIANCE MUST VARY

Hello,

I’m attempting to use ZED Global Sensor Fusion and running into a couple of issues . My setup:

Camera: ZED2i

SDK: 5.1

Platform: NVIDIA Jetson Orin AGX

Middleware: ROS 2 Humble

GNSS: u-blox ZED-F9P with RTK module

Even though the cov matrix of the my gps topic is varying I get this error(I know its a warning but it seems like i cannot get the calibration finished most of the times with RTK and when i finished the calibration the pose/filtered message is not visible on rviz)

[component_container_isolated-5] [ERROR] [1778175497.079648915] [zed.zed_node]: Ingest error occurred when ingesting GNSSData: GNSS DATA COVARIANCE MUST VARY

Issue 1 — Stuck at CALIBRATION IN PROGRESS

When running GNSS fusion with low GPS covariance (still within normal RTK range), the pipeline stalls at CALIBRATION IN PROGRESS and never publishes pose/filtered, even with rolling_calibration set to true. Applying a covariance multiplier silenced the warning but did not resolve the underlying problem — calibration still never completes.

Issue 2 — Linear drift between map and odom

In cases where fusion does succeed (with higher GPS covariance), we observe linear drift between the map and odom frames that seems significantly larger than what would be expected under normal conditions.

I’ve attached SVO files’ drive links reproducing the no-pose-published case to this thread.

Any guidance on recommended troubleshooting steps would be greatly appreciated. Thank you.

Here is the following .svo2 files stored in GoogleDrive link : SVOs - Google Drive

Desktop.svo2

pose_try.svo2

pose_mulpt_10000try.svo2 : we tried with 10000 multiplier of covarince to get rid of the warning lower amounts didnt’t eliminated the error

to_toolboxrecording.svo2 : We tried calibration for several minutes here driving around the park still didn’t finished

Hi @betelgeuse
I recommend you upgrade the ZED SDK to the latest v5.3 and you use the latest version of the ZED ROS2 Wrapper in the master branch of the GitHub repository with it.

I also invite you to explore the Global Localization documentation with details concerning the calibration process and how to perform it.

Thanks @Myzhar the now the /zed/zed_node/pose/filtered is publishing and the calibration is completed in 10-15 seconds when the following part of my common stereo config, without gnss_fusion.enable_translation_uncertainty_target false

it doesnt finish the calibration though


        pos_tracking:
            pos_tracking_enabled: true # True to enable positional tracking from start
            pos_tracking_mode: 'GEN_3' # Matches the ZED SDK setting: 'GEN_1', 'GEN_2', 'GEN_3'
            imu_fusion: true # enable/disable IMU fusion. When set to false, only the optical odometry will be used.
            publish_tf: true # [overwritten by launch file options] publish `odom -> camera_link` TF
            publish_map_tf: true # [overwritten by launch file options] publish `map -> odom` TF
            map_frame: 'map'
            odometry_frame: 'odom'
            base_frame: 'base_link' # Leave empty to use `<camera_name>_camera_link`, or set to your robot base frame (e.g. 'base_link')
            area_memory: false # Enable to detect loop closure
            area_file_path: '' # Path to the area memory file for relocalization and loop closure in a previously explored environment. 
            enable_localization_only: false # If true, the camera will only localize in the loaded area memory without updating the map with new information.
            save_area_memory_on_closing: false # Save Area memory before closing the camera if `area_file_path` is not empty. You can also use the `save_area_memory` service to save the area memory at any time.
            reset_odom_with_loop_closure: false # Re-initialize odometry to the last valid pose when loop closure happens (reset camera odometry drift)
            publish_3d_landmarks: false # Publish 3D landmarks used by the positional tracking algorithm
            publish_lm_skip_frame: 5 # Publish the landmarks every X frames to reduce bandwidth. Set to 0 to publish all landmarks
            depth_min_range: 0.0 # Set this value for removing fixed zones of the robot in the FoV of the camerafrom the visual odometry evaluation
            set_as_static: false # If 'true' the camera will be static and not move in the environment
            set_gravity_as_origin: true # If 'true' align the positional tracking world to imu gravity measurement. Keep the yaw from the user initial pose.
            floor_alignment: true # Enable to automatically calculate camera/floor offset
            initial_base_pose: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # Initial position of the `camera_link` frame in the map -> [X, Y, Z, R, P, Y]
            path_pub_rate: 2.0 # [DYNAMIC] - Camera trajectory publishing frequency. Set to 0 for no limit (= grab_frame_rate).
            path_max_count: -1 # use '-1' for unlimited path size
            two_d_mode: true # Force navigation on a plane. If true the Z value will be fixed to 'fixed_z_value', roll and pitch to zero
            fixed_z_value: 0.0 # Value to be used for Z coordinate if `two_d_mode` is true
            transform_time_offset: 0.0 # The value added to the timestamp of `map->odom` and `odom->camera_link` transform being generated
            reset_pose_with_svo_loop: true # Reset the camera pose the `initial_base_pose` when the SVO loop is enabled and the SVO playback reaches the end of the file.
            publish_odom_pose: true # Advertise the odometry and pose topics that are published only if a node subscribes to them
            publish_pose_cov: false # Advertise the pose with covariance topic that is published only if a node subscribes to it
            publish_cam_path: false # Advertise the camera odometry and pose path topics that are published only if a node subscribes to them

        gnss_fusion:
            gnss_fusion_enabled: true # fuse 'sensor_msg/NavSatFix' message information into pose data
            gnss_fix_topic: '/ublox_gps_node/fix' # Name of the GNSS topic of type NavSatFix to subscribe [Default: '/gps/fix']
            gnss_zero_altitude: true # Set to `true` to ignore GNSS altitude information
            h_covariance_mul: 1.0 # Multiplier factor to be applied to horizontal covariance of the received fix (plane X/Y)
            v_covariance_mul: 1.0 # Multiplier factor to be applied to vertical covariance of the received fix (Z axis)
            publish_utm_tf: true # Publish `utm` -> `map` TF
            broadcast_utm_transform_as_parent_frame: false # if 'true' publish `utm` -> `map` TF, otherwise `map` -> `utm`
            enable_reinitialization: false # determines whether reinitialization should be performed between GNSS and VIO fusion when a significant disparity is detected between GNSS data and the current fusion data. It becomes particularly crucial during prolonged GNSS signal loss scenarios.
            enable_rolling_calibration: true # If this parameter is set to true, the fusion algorithm will used a rough VIO / GNSS calibration at first and then refine it. This allow you to quickly get a fused position.
            enable_translation_uncertainty_target: false # When this parameter is enabled (set to true), the calibration process between GNSS and VIO accounts for the uncertainty in the determined translation, thereby facilitating the calibration termination. The maximum allowable uncertainty is controlled by the 'target_translation_uncertainty' parameter.
            gnss_vio_reinit_threshold: 5.0 # determines the threshold for GNSS/VIO reinitialization. If the fused position deviates beyond out of the region defined by the product of the GNSS covariance and the gnss_vio_reinit_threshold, a reinitialization will be triggered.
            target_translation_uncertainty: 0.1 # defines the target translation uncertainty at which the calibration process between GNSS and VIO concludes. By default, the threshold is set at 10 centimeters.
            target_yaw_uncertainty: 0.1 # defines the target yaw uncertainty at which the calibration process between GNSS and VIO concludes. The unit of this parameter is in radian. By default, the threshold is set at 0.1 radians.


and this brings to my current problem in which I have a drift, as I move my pose is good but when I stop the vehicle seems to drift. Right now I consider calibrating the Gyroscope , accelometer I am open to your suggestions. Thanks again

Hi @betelgeuse
Thank you for the feedback.

You are using an old version of the ZED SDK.
I recommend you upgrade to ZED SDK v5.3 and to the latest version of the ZED ROS2 Wrapper in the master branch of the GitHub repository.

Please let me know if this solves the drift issues.

Thanks for the quick resonse @Myzhar but I updated the sdk to 5.3 and wrapper to the master that solved the initial problem with calibration but not the drift. If you have any suggestions on params I would be glad. Also I will upload a svo file tomorrow using the Global Localization example from SDK examples, if still the wrapper ROS2 startSvoRecord service does not include the gnss values.

All the best

Hi @betelgeuse
We quickly reviewed the SVOs. None of them contains GNSS data, so we weren’t able to test the fusion.

From what we saw, the pose is indeed slightly modified when the robot stops. That said, there are small movements visible in the image that could explain this.

Could you clarify whether the drift you are experiencing is small or significantly larger?

Hi @Myzhar ,Yes sorry for the late reply but the drift is large. For the reason for GNSS data not existing is that we took the svo using the ROS2 service of startSVOrecording of ROS wrapper of ZED SDK, I believe it still does not support to include GNSS data. I tried to take a recording of svo2 with the global localization example of the zed_sdk repo but didn’t worked with the same GNSS data error. But I have a ros2bag recording of me trying to calibrate. Consider that I launched ros2 bag record some time later after launching zed_localization: And there is the problem of depth perception it sees ghost obstacles in the air you can see it yourself in the rosbag. And that effect our point cloud and therefore the obstacle map, Do you think it is because of the sun being too shiny?

# map->odom: provided by global EKF (GPS-fused)
# odom->zed_camera_link: provided by local EKF
# rtabmap: costmap/grid generation only (publish_tf disabled)
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from launch.actions import GroupAction
from launch_ros.actions import PushRosNamespace, SetRemap
from launch_ros.actions import Node
from launch.substitutions import Command
from launch_ros.parameter_descriptions import ParameterValue
import os
from ament_index_python.packages import get_package_share_directory

# TF chain: map->odom->zed_camera_link (REP 105)
def generate_launch_description() -> LaunchDescription:

    juno_bringup_dir = get_package_share_directory('juno_bringup')
    config_dir = os.path.join(
        juno_bringup_dir,
        'launch',
        'gps_rl_config'
    )
    navsat_params_file = os.path.join(config_dir, 'navsat_transform_node.yaml')

    rviz_cfg = PathJoinSubstitution(
        [
            FindPackageShare("juno_bringup"),
            "launch",
            "rviz_config",
            "ekf_check_config.rviz",
        ]
    )
    urdf_path = PathJoinSubstitution(
        [
            FindPackageShare("juno_bringup"), # Change to your actual package
            "launch",
            "urdf_config",                           # Change to your urdf folder
            "zed_base_link.urdf.xacro",               # Change to your actual file name
        ]
    )

    robot_state_publisher_node = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        name="robot_state_publisher",
        parameters=[{
            "robot_description": ParameterValue(
                Command(['xacro ', urdf_path, ' use_zed_localization:=true']),
                value_type=str
            )
        }],
    )
    # Disable VIO’s publication of odom->camera and instead publish nav_msgs/Odometry of the VIO’s pose solution for fusion. 
    # By default the zed_wrapper publishes this under the odom topic, but it is recommended to remap this to a non-reserved topic name (for example, camera_odom).
    # remappings=[('odom', 'camera_odom')]
    zed_camera_launch = GroupAction(
        actions=[
            SetRemap(src='odom', dst='camera_odom'),
            IncludeLaunchDescription(
                PythonLaunchDescriptionSource(
                    PathJoinSubstitution(
                        [
                            FindPackageShare("zed_wrapper"),
                            "launch",
                            "zed_camera.launch.py",
                        ]
                    )
                ),
                launch_arguments={
                    "camera_model": "zed2i",
                    "publish_map_tf": "true",
                    "publish_imu_tf": "true",
                    "publish_tf": "true",
                    "enable_gnss": "true",
                    "gnss_antenna_offset": "[-0.73,0,0]"
                }.items(),
            )
        ]
    )
    gps_launch = IncludeLaunchDescription(
                PythonLaunchDescriptionSource(
                PathJoinSubstitution([
                    FindPackageShare("ublox_gps"), "launch", "rover-launch.py",
                ])
            )
    )

    return LaunchDescription(
        [
            robot_state_publisher_node,
            gps_launch,
            #imu_mag_fuse,
            zed_camera_launch,
        ]
    )


    # Disable VIO’s publication of odom->camera and instead publish nav_msgs/Odometry of the VIO’s pose solution for fusion. 
    # By default the zed_wrapper publishes this under the odom topic, but it is recommended to remap this to a non-reserved topic name (for example, camera_odom).
    # remappings=[('odom', 'camera_odom')]
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from launch.actions import GroupAction
from launch_ros.actions import PushRosNamespace, SetRemap
from launch_ros.actions import Node
from launch.substitutions import Command
from launch_ros.parameter_descriptions import ParameterValue
import os
from ament_index_python.packages import get_package_share_directory

# TF chain: map->odom->zed_camera_link (REP 105)
def generate_launch_description() -> LaunchDescription:

    juno_bringup_dir = get_package_share_directory('juno_bringup')
    config_dir = os.path.join(
        juno_bringup_dir,
        'launch',
        'gps_rl_config'
    )
    navsat_params_file = os.path.join(config_dir, 'navsat_transform_node.yaml')

    rviz_cfg = PathJoinSubstitution(
        [
            FindPackageShare("juno_bringup"),
            "launch",
            "rviz_config",
            "ekf_check_config.rviz",
        ]
    )
    urdf_path = PathJoinSubstitution(
        [
            FindPackageShare("juno_bringup"), # Change to your actual package
            "launch",
            "urdf_config",                           # Change to your urdf folder
            "zed_base_link.urdf.xacro",               # Change to your actual file name
        ]
    )

    robot_state_publisher_node = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        name="robot_state_publisher",
        parameters=[{
            "robot_description": ParameterValue(
                Command(['xacro ', urdf_path, ' use_zed_localization:=true']),
                value_type=str
            )
        }],
    )
    zed_camera_launch = GroupAction(
        actions=[
            SetRemap(src='odom', dst='camera_odom'),
            IncludeLaunchDescription(
                PythonLaunchDescriptionSource(
                    PathJoinSubstitution(
                        [
                            FindPackageShare("zed_wrapper"),
                            "launch",
                            "zed_camera.launch.py",
                        ]
                    )
                ),
                launch_arguments={
                    "camera_model": "zed2i",
                    "publish_map_tf": "true",
                    "publish_imu_tf": "true",
                    "publish_tf": "true",
                    "enable_gnss": "true",
                    "gnss_antenna_offset": "[-0.73,0,0]"
                }.items(),
            )
        ]
    )
    gps_launch = IncludeLaunchDescription(
                PythonLaunchDescriptionSource(
                PathJoinSubstitution([
                    FindPackageShare("ublox_gps"), "launch", "rover-launch.py",
                ])
            )
    )

    return LaunchDescription(
        [
            robot_state_publisher_node,
            gps_launch,
            #imu_mag_fuse,
            zed_camera_launch,
        ]
    )



The calibration didn’t finished even though we were having 2cm accuracy with gps. The following is the rosbag recording: https://drive.google.com/drive/folders/1zU8ogGQUADjxfhZkSPicwUrfR4xbNQY8?usp=drive_link

Would appreciate if this calibration in progress is just a needing of more time to calibrate issue or something deeper. Best

Hi @betelgeuse
Sorry for the long delay.

The ZED SDK team is analyzing the issue and trying to replicate the behavior to fix it in one of the next releases.