When I use GNSS for fusion and call the ingestGNSSData
function, it returns an error with the value INVALID_TIMESTAMP
. Below is my code snippet and error log. What went wrong?
SDK Version: 5.0.2
Device: ZED-X
[2025-06-25 15:07:24.047806] [error] [4117] [zed_camera.cpp:148] : Failed to ingest GNSS data: INVALID TIMESTAMP
[2025-06-25 15:07:24.047806] [error] [4117] [zed_camera.cpp:148] : Failed to ingest GNSS data: INVALID TIMESTAMP
[2025-06-25 07:07:24 UTC][FUSION][WARNING] The GNSS data you are trying to ingest appears to be out of sync with the current frame. Please ensure that the GNSS data is synchronized with the camera frame.
[2025-06-25 07:07:24 UTC][FUSION][WARNING] Hint: The GNSS data timestamp is 1750835244045000000 ns, the current frame timestamp is 0 ns, and the maximum allowed difference is 4000000000 ns.
[2025-06-25 07:07:24 UTC][FUSION][WARNING] Hint: The GNSS data timestamp is 1750835244045000000 ns, the current frame timestamp is 0 ns, and the maximum allowed difference is 4000000000 ns.
[2025-06-25 15:07:24.047808] [error] [4117] [zed_camera.cpp:153] : ERROR: gnss_timestamp:1750835244045, camera_frame_timestamp:1750835243993,cur_timestamp:1750835244047, fusion_timestamp:0
[2025-06-25 07:07:24 UTC][FUSION][WARNING] Hint: It seems that the GNSS data is ahead by 1750835244.0449998 seconds. Please check the GNSS data and ensure that it is synchronized with the camera frame.
sl::InitParameters init_params{};
init_params.depth_mode = sl::DEPTH_MODE::NEURAL;
init_params.camera_fps = 60;
init_params.camera_resolution = sl::RESOLUTION::HD1200;
init_params.coordinate_units = sl::UNIT::METER;
init_params.coordinate_system = sl::COORDINATE_SYSTEM::RIGHT_HANDED_Z_UP;
init_params.sdk_verbose = 1;
_runtime_params.confidence_threshold = 30;
_runtime_params.texture_confidence_threshold = 100;
_positional_tracking_params.mode = sl::POSITIONAL_TRACKING_MODE::GEN_3;
bool ZedCamera::open(sl::InitParameters params)
{
auto ec = _zed.open(std::move(params));
if (ec != sl::ERROR_CODE::SUCCESS)
{
LOG_ERROR("Failed to open ZED camera: {}", sl::toString(ec).c_str());
return false;
}
_zed.updateSelfCalibration();
loadDefaultSettings();
_is_running = true;
const auto info = _zed.getCameraInformation();
LOG_INFO("ZED Camera Information:\n\tserial_number: {}\n\tinput_type: {}\n\tcamera_model: {}\n\tfirmware_version: {}\n\tresolution: {}x{} @ fps: {}",
info.serial_number, sl::toString(info.input_type).c_str(), sl::toString(info.camera_model).c_str(),
info.camera_configuration.firmware_version,
info.camera_configuration.resolution.height,
info.camera_configuration.resolution.width,
info.camera_configuration.fps);
ec = _zed.enablePositionalTracking(_positional_tracking_params);
if (ec != sl::ERROR_CODE::SUCCESS)
{
LOG_ERROR("Failed to enable positional tracking: {}", sl::toString(ec).c_str());
return false;
}
else
{
LOG_INFO("Positional tracking enabled successfully.");
}
// Fusion
_zed.startPublishing();
_init_fusion_params.coordinate_system = sl::COORDINATE_SYSTEM::LEFT_HANDED_Z_UP;
_init_fusion_params.coordinate_units = sl::UNIT::METER;
_init_fusion_params.verbose = 1;
if (auto fec = _fusion.init(_init_fusion_params); fec != sl::FUSION_ERROR_CODE::SUCCESS)
{
LOG_ERROR("[Fusion][ERROR] Failed to initialize fusion, error: {}", sl::toString(fec).c_str());
return false;
}
const sl::CameraIdentifier uuid(_zed.getCameraInformation().serial_number);
if (auto fec = _fusion.subscribe(uuid); fec != sl::FUSION_ERROR_CODE::SUCCESS)
{
LOG_ERROR("[Fusion] subcribe failed. {}", sl::toString(fec).c_str());
return false;
}
sl::GNSSCalibrationParameters gnss_calibration_params{};
// TODO : To be set
sl::float3 gnss_antenna_position{1, 2, 3};
gnss_calibration_params.gnss_antenna_position = gnss_antenna_position;
_positional_tracking_fusion_params.enable_GNSS_fusion = true;
//_positional_tracking_fusion_params.gnss_calibration_parameters = gnss_calibration_params;
if (const auto fec = _fusion.enablePositionalTracking(_positional_tracking_fusion_params);
fec != sl::FUSION_ERROR_CODE::SUCCESS)
{
LOG_ERROR("Failed to enable positional tracking fusion: {}", sl::toString(fec).c_str());
return false;
}
/// Start work thread
_work_thread = std::thread([this, uuid]()
{
LOG_INFO("ZED Camera work thread started.");
sl::Pose pose{};
sl::POSITIONAL_TRACKING_STATE tracking_state = sl::POSITIONAL_TRACKING_STATE::OFF;
while (_is_running)
{
sl::Mat image;
if (_zed.grab(_runtime_params) == sl::ERROR_CODE::SUCCESS)
{
tracking_state = _zed.getPosition(pose);
auto trans = pose.pose_data.getTranslation();
auto euler = pose.getEulerAngles(false);
auto quaternion = pose.getOrientation();
}
sl::GNSSData gnss_data{};
if (grapGnssInfo(gnss_data) != sl::ERROR_CODE::SUCCESS || gnss_data.gnss_status == sl::GNSS_STATUS::UNKNOWN)
{
LOG_WARN("Failed to get GNSS data");
continue;
}
auto fusion_sender_status = _fusion.getSenderState();
if (fusion_sender_status.count(uuid) != 0)
{
LOG_INFO("fusion sender status is {}", sl::toString(fusion_sender_status.at(uuid)).c_str());
}
else
{
LOG_ERROR("[Fusion] There is now fusion sender");
}
if (auto ingest_ec = _fusion.ingestGNSSData(gnss_data); ingest_ec != sl::FUSION_ERROR_CODE::SUCCESS)
{
LOG_ERROR("Failed to ingest GNSS data: {}", sl::toString(ingest_ec).c_str());
auto gnss_timestamp = gnss_data.ts.getMilliseconds();
auto camera_frame_timestamp = pose.timestamp.getMilliseconds();
auto cur_timestamp = _zed.getTimestamp(sl::TIME_REFERENCE::CURRENT).getMilliseconds();
auto fusion_timestapm = _fusion.getCurrentTimeStamp().getMilliseconds();
LOG_ERROR("ERROR: gnss_timestamp:{}, camera_frame_timestamp:{},cur_timestamp:{}, fusion_timestamp:{}",
gnss_timestamp, camera_frame_timestamp, cur_timestamp, fusion_timestapm);
continue;
}
if (_fusion.process() != sl::FUSION_ERROR_CODE::SUCCESS)
{
LOG_ERROR("Fusion process failed.");
continue;
}
// Get position into the ZED CAMERA coordinate system:
sl::Pose fused_pose{};
sl::POSITIONAL_TRACKING_STATE current_state = _fusion.getPosition(fused_pose);
sl::FusedPositionalTrackingStatus fused_status = _fusion.getFusedPositionalTrackingStatus();
LOG_INFO("POSITIONAL_TRACKING_STATE:{}, FusedPositionalTrackingStatus:{}", sl::toString(current_state).c_str(),
toString(fused_status));
LOG_INFO("{}", getPoseInfoString(fused_pose));
// Get position into the GNSS coordinate system
sl::GeoPose current_geo_pose;
if (auto current_geo_pose_satus = _fusion.getGeoPose(current_geo_pose);
current_geo_pose_satus == sl::GNSS_FUSION_STATUS::OK)
{
LOG_INFO("{}", getGeoPoseInfoString(current_geo_pose));
}
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
LOG_INFO("ZED Camera work thread stopped.");
});
return true;
}