3232#include < utility>
3333
3434#include " cuAprilTags.h"
35- #include " isaac_ros_common /vpi_utilities.hpp"
35+ #include " isaac_ros_vpi_utils /vpi_utilities.hpp"
3636
3737namespace nvidia
3838{
@@ -195,12 +195,13 @@ struct AprilTagNode::VPIAprilTagImpl : AprilTagNode::AprilTagImpl
195195 AprilTagNode::AprilTagImpl::Initialize (node, nitros_image_view, camera_info);
196196
197197 try {
198- CHECK_STATUS (vpiStreamCreate (node.backends_ | VPI_BACKEND_CPU | VPI_BACKEND_CUDA, &stream_));
198+ CHECK_VPI_STATUS (vpiStreamCreate (node.backends_ | VPI_BACKEND_CPU | VPI_BACKEND_CUDA,
199+ &stream_));
199200 } catch (std::runtime_error & e) {
200201 RCLCPP_ERROR (node.get_logger (), " Error while initializing: %s" , e.what ());
201202 }
202203
203- CHECK_STATUS (vpiInitAprilTagDecodeParams (¶ms_));
204+ CHECK_VPI_STATUS (vpiInitAprilTagDecodeParams (¶ms_));
204205
205206 params_.family = tag_family_;
206207
@@ -218,7 +219,7 @@ struct AprilTagNode::VPIAprilTagImpl : AprilTagNode::AprilTagImpl
218219 std::memcpy (&cam_intrinsics_, &cam_intrinsics, sizeof (VPICameraIntrinsic));
219220
220221 // Detector
221- CHECK_STATUS (
222+ CHECK_VPI_STATUS (
222223 vpiCreateAprilTagDetector (
223224 node.backends_ , camera_info->width ,
224225 camera_info->height , ¶ms_, &detector_));
@@ -236,7 +237,7 @@ struct AprilTagNode::VPIAprilTagImpl : AprilTagNode::AprilTagImpl
236237 data->buffer .pitch .planes [0 ].pixelType = VPI_PIXEL_TYPE_DEFAULT;
237238 data->buffer .pitch .planes [0 ].pitchBytes = nitros_image_view.GetStride ();
238239 data->buffer .pitch .planes [0 ].offsetBytes = 0 ;
239- CHECK_STATUS (vpiImageCreateWrapper (data, nullptr , VPI_BACKEND_CUDA, &input_image_));
240+ CHECK_VPI_STATUS (vpiImageCreateWrapper (data, nullptr , VPI_BACKEND_CUDA, &input_image_));
240241
241242 RCLCPP_INFO (
242243 node.get_logger (), " Initialized with input image (%dx%d), encoding=%s, pitch=%d" ,
@@ -246,7 +247,7 @@ struct AprilTagNode::VPIAprilTagImpl : AprilTagNode::AprilTagImpl
246247 data->buffer .pitch .planes [0 ].pitchBytes );
247248
248249 // Input monochrome image
249- CHECK_STATUS (
250+ CHECK_VPI_STATUS (
250251 vpiImageCreate (
251252 camera_info->width , camera_info->height ,
252253 VPI_IMAGE_FORMAT_U8, 0 , &input_monochrome_image_));
@@ -260,50 +261,51 @@ struct AprilTagNode::VPIAprilTagImpl : AprilTagNode::AprilTagImpl
260261 // Update input image buffer in wrapper
261262 input_image_data_.buffer .pitch .planes [0 ].pBase =
262263 const_cast <unsigned char *>(nitros_image_view.GetGpuData ());
263- CHECK_STATUS (vpiImageSetWrapper (input_image_, &input_image_data_))
264+ CHECK_VPI_STATUS (vpiImageSetWrapper (input_image_, &input_image_data_))
264265
265266 // Submit image conversion to U8
266267 VPIConvertImageFormatParams convert_params;
267- CHECK_STATUS (vpiInitConvertImageFormatParams (&convert_params));
268+ CHECK_VPI_STATUS (vpiInitConvertImageFormatParams (&convert_params));
268269
269- CHECK_STATUS (
270+ CHECK_VPI_STATUS (
270271 vpiSubmitConvertImageFormat (
271272 stream_, VPI_BACKEND_CUDA, input_image_,
272273 input_monochrome_image_, &convert_params));
273274
274275 // Perform AprilTag detection
275276 VPIArray detections_array;
276- CHECK_STATUS (
277+ CHECK_VPI_STATUS (
277278 vpiArrayCreate (
278279 node.max_tags_ , VPI_ARRAY_TYPE_APRILTAG_DETECTION, 0 ,
279280 &detections_array));
280- CHECK_STATUS (
281+ CHECK_VPI_STATUS (
281282 vpiSubmitAprilTagDetector (
282283 stream_, node.backends_ , detector_, node.max_tags_ ,
283284 input_monochrome_image_, detections_array));
284285
285286 VPIArray detections_pose_array;
286- CHECK_STATUS (vpiArrayCreate (node.max_tags_ , VPI_ARRAY_TYPE_POSE, 0 , &detections_pose_array));
287- CHECK_STATUS (
287+ CHECK_VPI_STATUS (vpiArrayCreate (node.max_tags_ , VPI_ARRAY_TYPE_POSE, 0 ,
288+ &detections_pose_array));
289+ CHECK_VPI_STATUS (
288290 vpiSubmitAprilTagPoseEstimation (
289291 stream_, VPI_BACKEND_CPU, detections_array,
290292 cam_intrinsics_, node.size_ , detections_pose_array));
291293
292- CHECK_STATUS (vpiStreamSync (stream_));
294+ CHECK_VPI_STATUS (vpiStreamSync (stream_));
293295
294296 int32_t num_detections = 0 ;
295- CHECK_STATUS (vpiArrayGetSize (detections_array, &num_detections));
297+ CHECK_VPI_STATUS (vpiArrayGetSize (detections_array, &num_detections));
296298
297299 VPIArrayData detections_data;
298- CHECK_STATUS (
300+ CHECK_VPI_STATUS (
299301 vpiArrayLockData (
300302 detections_array, VPI_LOCK_READ, VPI_ARRAY_BUFFER_HOST_AOS,
301303 &detections_data));
302304 VPIAprilTagDetection * detections =
303305 reinterpret_cast <VPIAprilTagDetection *>(detections_data.buffer .aos .data );
304306
305307 VPIArrayData detections_pose_data;
306- CHECK_STATUS (
308+ CHECK_VPI_STATUS (
307309 vpiArrayLockData (
308310 detections_pose_array, VPI_LOCK_READ, VPI_ARRAY_BUFFER_HOST_AOS,
309311 &detections_pose_data));
@@ -356,10 +358,10 @@ struct AprilTagNode::VPIAprilTagImpl : AprilTagNode::AprilTagImpl
356358 node.tf_broadcaster_ ->sendTransform (tfs.transforms );
357359
358360 // Cleanup
359- CHECK_STATUS (vpiArrayUnlock (detections_pose_array));
361+ CHECK_VPI_STATUS (vpiArrayUnlock (detections_pose_array));
360362 vpiArrayDestroy (detections_pose_array);
361363
362- CHECK_STATUS (vpiArrayUnlock (detections_array));
364+ CHECK_VPI_STATUS (vpiArrayUnlock (detections_array));
363365 vpiArrayDestroy (detections_array);
364366 }
365367
@@ -551,7 +553,7 @@ AprilTagNode::AprilTagNode(const rclcpp::NodeOptions & options)
551553 size_(declare_parameter<double >(" size" , 0.22 )),
552554 tile_size_(declare_parameter<uint16_t >(" tile_size" , 4 )),
553555 tag_family_(declare_parameter<std::string>(" tag_family" , " tag36h11" )),
554- backends_{::isaac_ros::common ::DeclareVPIBackendParameter (this , VPI_BACKEND_CUDA)},
556+ backends_{nvidia ::isaac_ros::vpi_utils ::DeclareVPIBackendParameter (this , VPI_BACKEND_CUDA)},
555557 image_sub_{},
556558 camera_info_sub_{},
557559 camera_image_sync_{ExactPolicy{3 }, image_sub_, camera_info_sub_},
0 commit comments