Hi there,
I would like to modify the timestamp on an existing NitrosImage (or NitrosImageView) but am running into cuda issues.
I have two independent ArgusMonoNode’s running, and am trying to use the nitros::message_filters to synchronize (via message_filters::Synchronizer<ApproxSyncPolicy>) the two images (and their CameraInfos). Following the NitrosCameraDropNode example, I was able to get a callback with all topics triggered, but I am not sure how I can re-timestamp the NitrosImages without copying the underlying data.
In the callback, if I wrap the incoming NitrosImage::ConstSharedPtr with a NitrosImageView, then create a new NitrosImage with NitrosImageBuilder (accessing data with .GetGpuData()), I get the following error:
2025-08-25 10:30:03.552 ERROR gxf/std/unbounded_allocator.cpp@99: Failure in cudaFree. cuda_error: cudaErrorInvalidValue, error_str: invalid argument
This method seems problematic, likely some issue with memory ownership.
How else can I modify the timestamp of the incoming NitrosImage, without copying the underlying GPU data?
Is it possible to add a NitrosImageView.SetTimestampSeconds() & NitrosImageView.SetTimestampNanoseconds() functionality?
Longer code snippet:
void sync_callback(const nvidia::isaac_ros::nitros::NitrosImage::ConstSharedPtr &left_img_ptr,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr &left_cam_info_ptr,
const nvidia::isaac_ros::nitros::NitrosImage::ConstSharedPtr &right_img_ptr,
const sensor_msgs::msg::CameraInfo::ConstSharedPtr &right_cam_info_ptr) {
auto left_image_view = nvidia::isaac_ros::nitros::NitrosImageView(*left_img_ptr);
auto right_image_view = nvidia::isaac_ros::nitros::NitrosImageView(*right_img_ptr);
// Get "now" timestamp
rclcpp::Time now = this->now();
// Left header data
std_msgs::msg::Header left_header;
left_header.stamp = now;
left_header.frame_id = left_image_view.GetFrameId(); // todo update
// TODO: Below causes a cudaFree error. How to resolve this??
// Create NitrosImage wrapping CUDA buffer of left nitros image
nvidia::isaac_ros::nitros::NitrosImage left_nitros_image =
nvidia::isaac_ros::nitros::NitrosImageBuilder()
.WithHeader(left_header)
.WithEncoding(img_encodings::RGB8)
.WithDimensions(left_image_view.GetHeight(), left_image_view.GetWidth())
.WithGpuData(const_cast<void *>(static_cast<const void *>(left_image_view.GetGpuData())))
.Build();
// ... etc ...
// Republish images and Camera Info with all matching timestamps
left_img_syncd_pub_->publish(left_nitros_image);
// ... etc ...
}