Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Wrong acquisition timestamp carried in the ArgusCamera output entity message #39

Open
developer-mayuan opened this issue Mar 6, 2024 · 0 comments

Comments

@developer-mayuan
Copy link

We are running the latest isaac_ros_argus_camera (Isaac ros 2.1) with Hawk cameras on Jetson AGX Orin 64G Dev kit using Jetpack 5.1.2. We can have setup the isaac ros framework successfully using the dev container created from isaac_ros_common package. However, we found that wrong acquisition timestamp was carried in the ArgusCamera output entity message, which is always about 18 seconds later than the system steady clock.

How we observed this issue is by doing the following:

  1. Clone the source code of isaac_ros_argus_camera and isaac_ros_image_pipeline package.
  2. apply the following patch to isaac_ros_image_proc:
diff --git a/isaac_ros_image_proc/gxf/tensorops/extensions/tensorops/components/TensorOperator.cpp b/isaac_ros_image_proc/gxf/tensorops/extensions/tensorops/components/TensorOperator.cpp
index 572751d..8de17d7 100644
--- a/isaac_ros_image_proc/gxf/tensorops/extensions/tensorops/components/TensorOperator.cpp
+++ b/isaac_ros_image_proc/gxf/tensorops/extensions/tensorops/components/TensorOperator.cpp
@@ -166,6 +166,10 @@ gxf_result_t TensorOperator::tick() {
   error =
     detail::RerouteMessage<gxf::Timestamp>(output_message.value(), input_message.value(),
         [](gxf::Handle<gxf::Timestamp> output, gxf::Handle<gxf::Timestamp> input) {
+      auto steady_clock_now = std::chrono::steady_clock::now().time_since_epoch().count();
+      GXF_LOG_WARNING("frame acq time: %ld, frame pub time: %ld", input.get()->acqtime, input.get()->pubtime);
+      GXF_LOG_WARNING("system steady_clock now: %ld", steady_clock_now);
+      GXF_LOG_ERROR("Diff between current steady_clock and frame acq time: %ld", steady_clock_now - input.get()->acqtime);
           *output = *input;
           return GXF_SUCCESS;
         });

The purpose for this patch is comparing the current steady_clock timestamp with the acquisition time stamp carried in the camera message. And the reason why we put it here is because nvidia::isaac::tensor_ops::StreamConvertColorFormat is the direct down stream consumer of the ArgusCamera message entity, and TensorOperator class is the base class of the ConvertolorFormat and handles the ingress and egress messages.

  1. Build isaac_ros_argus_camera and isaac_ros_image_pipeline package from source:
cd $ISAAC_ROS_WS \
 && colcon build \
   --packages-up-to isaac_ros_argus_camera \
   --parallel-workers 8 \
   --symlink-install \
   --install-base /workspaces/isaac_ros-dev/install \
   --merge-install \
 && source install/setup.bash
  1. launch mono_camera or stereo_camera launch file and check the output:
ros2 launch isaac_ros_argus_camera isaac_ros_argus_camera_mono.launch.py

image
Here we can fount there is always an offset about 18 seconds between the frame acquisition time and the current system steady clock, which is huge. And also the acquisition time is 18 seconds later than the system clock, which doesn't make any sense. I'm wondering if anyone has any thoughts how to address this issue? Thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

1 participant