|
| 1 | +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES |
| 2 | +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. |
| 3 | +// |
| 4 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 5 | +// you may not use this file except in compliance with the License. |
| 6 | +// You may obtain a copy of the License at |
| 7 | +// |
| 8 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 9 | +// |
| 10 | +// Unless required by applicable law or agreed to in writing, software |
| 11 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 12 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 13 | +// See the License for the specific language governing permissions and |
| 14 | +// limitations under the License. |
| 15 | +// |
| 16 | +// SPDX-License-Identifier: Apache-2.0 |
| 17 | + |
| 18 | +#include "extensions/camera_utils/stereo_camera_synchronizer.hpp" |
| 19 | +#include "gems/gxf_helpers/expected_macro_gxf.hpp" |
| 20 | +#include "gxf/std/timestamp.hpp" |
| 21 | + |
| 22 | +namespace nvidia { |
| 23 | +namespace isaac { |
| 24 | + |
| 25 | +gxf_result_t StereoCameraSynchronizer::registerInterface(gxf::Registrar* registrar) { |
| 26 | + gxf::Expected<void> result; |
| 27 | + result &= registrar->parameter( |
| 28 | + rx_right_camera_, "rx_right_camera", "RX Right Camera Message", |
| 29 | + "Input for Right CameraMessage entities"); |
| 30 | + result &= registrar->parameter( |
| 31 | + rx_left_camera_, "rx_left_camera", "RX Left Camera Message", |
| 32 | + "Input for Left CameraMessage entities"); |
| 33 | + result &= registrar->parameter( |
| 34 | + tx_right_camera_, "tx_right_camera", "TX Right Camera Message", |
| 35 | + "Input for Right CameraMessage entities"); |
| 36 | + result &= registrar->parameter( |
| 37 | + tx_left_camera_, "tx_left_camera", "TX Left Camera Message", |
| 38 | + "Input for Left CameraMessage entities"); |
| 39 | + result &= registrar->parameter( |
| 40 | + max_timestamp_diff_, "max_timestamp_diff", "Max difference timestamps nanoseconds", |
| 41 | + "Max difference between timestamps in nanoseconds", |
| 42 | + static_cast<int64_t>(200000)); // 200 micro seconds |
| 43 | + return gxf::ToResultCode(result); |
| 44 | +} |
| 45 | + |
| 46 | +gxf_result_t StereoCameraSynchronizer::start() { |
| 47 | + // Set all previous timestamps to minimum value of int64_t |
| 48 | + // This ensures that the first message received does NOT trigger the |
| 49 | + // "not monotonically increasing" error |
| 50 | + prev_left_unnamed_timestamp_ = std::numeric_limits<int64_t>::min(); |
| 51 | + prev_right_unnamed_timestamp_ = std::numeric_limits<int64_t>::min(); |
| 52 | + prev_left_named_timestamp_ = std::numeric_limits<int64_t>::min(); |
| 53 | + prev_right_named_timestamp_ = std::numeric_limits<int64_t>::min(); |
| 54 | + return GXF_SUCCESS; |
| 55 | +} |
| 56 | + |
| 57 | +gxf_result_t StereoCameraSynchronizer::tick() { |
| 58 | + auto left_camera_entity = UNWRAP_OR_RETURN(rx_left_camera_->receive()); |
| 59 | + auto right_camera_entity = UNWRAP_OR_RETURN(rx_right_camera_->receive()); |
| 60 | + auto left_unnamed_timestamp = UNWRAP_OR_RETURN(left_camera_entity.get<gxf::Timestamp>()); |
| 61 | + auto right_unnamed_timestamp = UNWRAP_OR_RETURN(right_camera_entity.get<gxf::Timestamp>()); |
| 62 | + auto left_named_timestamp = UNWRAP_OR_RETURN(left_camera_entity.get<gxf::Timestamp>("timestamp")); |
| 63 | + auto right_named_timestamp = UNWRAP_OR_RETURN(right_camera_entity.get<gxf::Timestamp>("timestamp")); |
| 64 | + |
| 65 | + const int64_t unnamed_diff = std::abs(left_unnamed_timestamp->acqtime - right_unnamed_timestamp->acqtime); |
| 66 | + if (unnamed_diff > max_timestamp_diff_) { |
| 67 | + GXF_LOG_ERROR("L/R frames are not synchronized, unnamed timestamp diff = %ld ns", unnamed_diff); |
| 68 | + return GXF_FAILURE; |
| 69 | + } |
| 70 | + |
| 71 | + const int64_t named_diff = std::abs(left_named_timestamp->acqtime - right_named_timestamp->acqtime); |
| 72 | + if (named_diff > max_timestamp_diff_) { |
| 73 | + GXF_LOG_ERROR("L/R frames are not synchronized, named timestamp diff = %ld ns", named_diff); |
| 74 | + return GXF_FAILURE; |
| 75 | + } |
| 76 | + // Set right input timestamp to left input timestamp |
| 77 | + right_unnamed_timestamp->acqtime = left_unnamed_timestamp->acqtime; |
| 78 | + right_named_timestamp->acqtime = left_named_timestamp->acqtime; |
| 79 | + |
| 80 | + |
| 81 | + // Check if previous timestamp is lower than current timestamp |
| 82 | + if (prev_left_unnamed_timestamp_ > left_unnamed_timestamp->acqtime) { |
| 83 | + GXF_LOG_ERROR("Left unnamed timestamp is not monotonically increasing"); |
| 84 | + return GXF_FAILURE; |
| 85 | + } |
| 86 | + if (prev_right_unnamed_timestamp_ > right_unnamed_timestamp->acqtime) { |
| 87 | + GXF_LOG_ERROR("Right unnamed timestamp is not monotonically increasing"); |
| 88 | + return GXF_FAILURE; |
| 89 | + } |
| 90 | + if (prev_left_named_timestamp_ > left_named_timestamp->acqtime) { |
| 91 | + GXF_LOG_ERROR("Left named timestamp is not monotonically increasing"); |
| 92 | + return GXF_FAILURE; |
| 93 | + } |
| 94 | + if (prev_right_named_timestamp_ > right_named_timestamp->acqtime) { |
| 95 | + GXF_LOG_ERROR("Right named timestamp is not monotonically increasing"); |
| 96 | + return GXF_FAILURE; |
| 97 | + } |
| 98 | + |
| 99 | + prev_left_unnamed_timestamp_ = left_unnamed_timestamp->acqtime; |
| 100 | + prev_right_unnamed_timestamp_ = right_unnamed_timestamp->acqtime; |
| 101 | + prev_left_named_timestamp_ = left_named_timestamp->acqtime; |
| 102 | + prev_right_named_timestamp_ = right_named_timestamp->acqtime; |
| 103 | + |
| 104 | + RETURN_IF_ERROR(tx_left_camera_->publish(left_camera_entity)); |
| 105 | + RETURN_IF_ERROR(tx_right_camera_->publish(right_camera_entity)); |
| 106 | + |
| 107 | + return GXF_SUCCESS; |
| 108 | +} |
| 109 | + |
| 110 | +} // namespace isaac |
| 111 | +} // namespace nvidia |
0 commit comments