Skip to content

Commit 55f94ff

Browse files
Isaac ROS 4.0 (#39)
1 parent bd78020 commit 55f94ff

File tree

57 files changed

+5193
-1570
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

57 files changed

+5193
-1570
lines changed

README.md

Lines changed: 21 additions & 15 deletions
Large diffs are not rendered by default.

SECURITY.md

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
## Security
2+
3+
NVIDIA is dedicated to the security and trust of our software products and services, including all source code repositories managed through our organization.
4+
5+
If you need to report a security issue, please use the appropriate contact points outlined below. **Please do not report security vulnerabilities through GitHub.**
6+
7+
## Reporting Potential Security Vulnerability in an NVIDIA Product
8+
9+
To report a potential security vulnerability in any NVIDIA product:
10+
- Web: [Security Vulnerability Submission Form](https://www.nvidia.com/object/submit-security-vulnerability.html)
11+
12+
- We encourage you to use the following PGP key for secure email communication: [NVIDIA public PGP Key for communication](https://www.nvidia.com/en-us/security/pgp-key)
13+
- Please include the following information:
14+
- Product/Driver name and version/branch that contains the vulnerability
15+
- Type of vulnerability (code execution, denial of service, buffer overflow, etc.)
16+
- Instructions to reproduce the vulnerability
17+
- Proof-of-concept or exploit code
18+
- Potential impact of the vulnerability, including how an attacker could exploit the vulnerability
19+
20+
While NVIDIA currently does not have a bug bounty program, we do offer acknowledgement when an externally reported security issue is addressed under our coordinated vulnerability disclosure policy. Please visit our [Product Security Incident Response Team (PSIRT)](https://www.nvidia.com/en-us/security/psirt-policies/) policies page for more information.
21+
22+
## NVIDIA Product Security
23+
24+
For all security-related concerns, please visit NVIDIA's Product Security portal at https://www.nvidia.com/en-us/security

isaac_ros_gxf_extensions/gxf_isaac_ros_segment_anything/gxf/segment_anything/segment_anything_postprocessor.cpp

Lines changed: 16 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -45,19 +45,19 @@ gxf::Expected<gxf::Handle<gxf::Tensor>> GetTensor(gxf::Entity entity, const char
4545

4646
gxf::Expected<Shape> GetShape(gxf::Handle<gxf::Tensor> in_tensor) {
4747
Shape shape{};
48-
48+
4949
shape.batch_size = in_tensor->shape().dimension(0);
5050
shape.channels = in_tensor->shape().dimension(1);
5151
shape.height = in_tensor->shape().dimension(2);
5252
shape.width = in_tensor->shape().dimension(3);
53-
54-
// Only single channel
53+
54+
// Only single channel
5555
if (shape.channels != kExpectedChannelCount) {
5656
GXF_LOG_ERROR("Received %d input channels, which is larger than the maximum allowable %d",
5757
shape.channels, kExpectedChannelCount);
5858
return gxf::Unexpected{GXF_FAILURE};
5959
}
60-
60+
6161
return shape;
6262
}
6363

@@ -160,7 +160,7 @@ gxf_result_t SegmentAnythingPostprocessor::tick() {
160160
Shape shape = maybe_shape.value();
161161

162162
auto out_message = gxf::Entity::New(context());
163-
163+
164164
if (!out_message) {
165165
GXF_LOG_ERROR("Failed to allocate message");
166166
return gxf::ToResultCode(out_message);
@@ -180,8 +180,7 @@ gxf_result_t SegmentAnythingPostprocessor::tick() {
180180
cudaStream_t cuda_stream = maybe_cuda_stream.value();
181181

182182
gxf::Expected<void> maybe_kernel_result;
183-
184-
183+
185184
auto raw_tensor = out_message.value().add<gxf::Tensor>();
186185

187186
if (!raw_tensor) {
@@ -202,14 +201,23 @@ gxf_result_t SegmentAnythingPostprocessor::tick() {
202201

203202
maybe_kernel_result =
204203
GenerateSegmentationMask(shape, in_tensor, output_video_buffer_data, cuda_stream);
205-
204+
206205
auto maybe_added_timestamp = AddInputTimestampToOutput(out_message.value(), in_message.value());
207206
if (!maybe_added_timestamp) { return gxf::ToResultCode(maybe_added_timestamp); }
208207

209208

210209
auto maybe_added_stream = AddStreamToOutput(out_message.value(), stream_);
211210
if (!maybe_added_stream) { return gxf::ToResultCode(maybe_added_stream); }
212211

212+
// Sync the stream, before sending it across the framework.
213+
// This is important to do since Isaac does not support non synced work across
214+
// codelets and multiple nodes.
215+
cudaError_t sync_result = cudaStreamSynchronize(cuda_stream);
216+
if (sync_result != cudaSuccess) {
217+
GXF_LOG_ERROR("Error while synchronizing CUDA stream: %s", cudaGetErrorString(sync_result));
218+
return GXF_FAILURE;
219+
}
220+
213221
return gxf::ToResultCode(out_->publish(std::move(out_message.value())));
214222
}
215223

isaac_ros_gxf_extensions/gxf_isaac_ros_segment_anything/gxf/segment_anything/segment_anything_prompt_processor.cpp

Lines changed: 44 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2-
// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
2+
// Copyright (c) 2024-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
33
//
44
// Licensed under the Apache License, Version 2.0 (the "License");
55
// you may not use this file except in compliance with the License.
@@ -66,18 +66,33 @@ gxf_result_t SegmentAnythingPromptProcessor::registerInterface(gxf::Registrar* r
6666
result &= registrar->parameter(max_batch_size_, "max_batch_size");
6767
result &= registrar->parameter(prompt_type_name_, "prompt_type_name");
6868
result &= registrar->parameter(has_input_mask_, "has_input_mask");
69+
result &= registrar->parameter(cuda_stream_pool_, "stream_pool", "Cuda Stream Pool",
70+
"Instance of gxf::CudaStreamPool to allocate CUDA stream.");
6971
return gxf::ToResultCode(result);
7072
}
7173

7274
gxf_result_t SegmentAnythingPromptProcessor::start() {
7375

76+
// Get cuda stream from stream pool
77+
auto maybe_stream = cuda_stream_pool_.get()->allocateStream();
78+
if (!maybe_stream) { return gxf::ToResultCode(maybe_stream); }
79+
80+
cuda_stream_handle_ = std::move(maybe_stream.value());
81+
if (!cuda_stream_handle_->stream()) {
82+
GXF_LOG_ERROR("Allocated stream is not initialized!");
83+
return GXF_FAILURE;
84+
}
85+
if (!cuda_stream_handle_.is_null()) {
86+
cuda_stream_ = cuda_stream_handle_->stream().value();
87+
}
88+
7489
uint32_t orig_width = orig_img_dim_.get()[1];
7590
uint32_t orig_height = orig_img_dim_.get()[0];
7691

7792
if (orig_width > orig_height) {
7893
resized_width_ = IMAGE_WIDTH_;
7994
resized_height_ = int((float(resized_width_) / orig_width) * orig_height);
80-
} else {
95+
} else {
8196
resized_height_ = IMAGE_HEIGHT_;
8297
resized_width_ = int((float(resized_height_) / orig_height) * orig_width);
8398
}
@@ -96,21 +111,21 @@ gxf_result_t SegmentAnythingPromptProcessor::tick() {
96111
Detection2DParts parts;
97112
auto detection2_d_parts_expected = nvidia::isaac_ros::GetDetection2DList(
98113
in_message.value());
99-
114+
100115
if (!detection2_d_parts_expected) { return gxf::ToResultCode(detection2_d_parts_expected); }
101-
116+
102117
auto detection2_d_parts = detection2_d_parts_expected.value();
103118

104119
// Extract detection2_d array to a struct type defined in detection2_d.hpp
105120
std::vector<nvidia::isaac_ros::Detection2D> detections =
106121
*(detection2_d_parts.detection2_d_array);
107-
122+
108123
auto maybe_added_timestamp = AddInputTimestampToOutput(out_message.value(), in_message.value());
109124
if (!maybe_added_timestamp) {
110125
GXF_LOG_ERROR("Failed to add timestamp to output msg");
111126
return gxf::ToResultCode(maybe_added_timestamp);
112127
}
113-
128+
114129
// Add invalid_frame tensor and publish it.
115130
// invalid_frame tensor is used by msg compositor to disqualify this input.
116131
if(detections.size() == 0){
@@ -126,7 +141,7 @@ gxf_result_t SegmentAnythingPromptProcessor::tick() {
126141

127142
uint32_t batch_size = 1;
128143
uint32_t num_points = num_points_;
129-
if (prompt_type_value_ == PromptType::kBbox) {
144+
if (prompt_type_value_ == PromptType::kBbox) {
130145
batch_size = max_batch_size_ < detections.size() ? max_batch_size_ : detections.size();
131146
}
132147

@@ -139,7 +154,7 @@ gxf_result_t SegmentAnythingPromptProcessor::tick() {
139154
std::vector<float> label_vec;
140155

141156
detectionToSAMPrompt(detections, prompt_vec, label_vec);
142-
157+
143158
if (!out_message) {
144159
GXF_LOG_ERROR("Failed to allocate message");
145160
return gxf::ToResultCode(out_message);
@@ -175,13 +190,15 @@ gxf_result_t SegmentAnythingPromptProcessor::tick() {
175190
auto result = bbox_tensor.value()->reshapeCustom(
176191
prompt_tensor_shape, gxf::PrimitiveType::kFloat32,
177192
gxf::PrimitiveTypeSize(gxf::PrimitiveType::kFloat32),
178-
gxf::Unexpected{GXF_UNINITIALIZED_VALUE}, gxf::MemoryStorageType::kDevice, allocator_.get());
193+
gxf::Unexpected{GXF_UNINITIALIZED_VALUE}, gxf::MemoryStorageType::kDevice, allocator_.get());
179194
if(!result){
180195
GXF_LOG_ERROR("Error allocating tensor for points tensor.");
181196
return gxf::ToResultCode(result);
182197
}
183-
cudaMemcpy(bbox_tensor.value()->pointer(), prompt_vec.data(), buffer_size,cudaMemcpyHostToDevice);
184-
198+
cudaMemcpyAsync(
199+
bbox_tensor.value()->pointer(), prompt_vec.data(), buffer_size,cudaMemcpyHostToDevice,
200+
cuda_stream_);
201+
185202
// Create Tensor for labels corresponding to each point
186203
gxf::Shape label_tensor_shape({batch_size,num_points});
187204
uint32_t buffer_size_label{batch_size*num_points*sizeof(float)};
@@ -193,7 +210,9 @@ gxf_result_t SegmentAnythingPromptProcessor::tick() {
193210
GXF_LOG_ERROR("Error allocating tensor for label tensor.");
194211
return gxf::ToResultCode(label_tensor_result);
195212
}
196-
cudaMemcpy(labels_tensor.value()->pointer(), label_vec.data(), buffer_size_label,cudaMemcpyHostToDevice);
213+
cudaMemcpyAsync(
214+
labels_tensor.value()->pointer(), label_vec.data(), buffer_size_label,cudaMemcpyHostToDevice,
215+
cuda_stream_);
197216

198217
// Create Tensor to put has_input_mask data
199218
gxf::Shape has_in_mask({1});
@@ -207,8 +226,10 @@ gxf_result_t SegmentAnythingPromptProcessor::tick() {
207226
GXF_LOG_ERROR("Error allocating tensor for has input mask tensor.");
208227
return gxf::ToResultCode(has_input_mask_result);
209228
}
210-
cudaMemcpy(has_input_mask_tensor.value()->pointer(), has_input_mask.data(), sizeof(float), cudaMemcpyHostToDevice);
211-
229+
cudaMemcpyAsync(
230+
has_input_mask_tensor.value()->pointer(), has_input_mask.data(), sizeof(float),
231+
cudaMemcpyHostToDevice, cuda_stream_);
232+
212233
// Create Tensor to put original image shape data
213234
gxf::Shape img_size_tensor_shape({2});
214235
std::vector<float> img_size(2);
@@ -217,12 +238,19 @@ gxf_result_t SegmentAnythingPromptProcessor::tick() {
217238
auto img_size_tensor_result = img_size_tensor.value()->reshapeCustom(
218239
img_size_tensor_shape, gxf::PrimitiveType::kFloat32,
219240
gxf::PrimitiveTypeSize(gxf::PrimitiveType::kFloat32),
220-
gxf::Unexpected{GXF_UNINITIALIZED_VALUE}, gxf::MemoryStorageType::kDevice, allocator_.get());
241+
gxf::Unexpected{GXF_UNINITIALIZED_VALUE}, gxf::MemoryStorageType::kDevice, allocator_.get());
221242
if(!img_size_tensor_result){
222243
GXF_LOG_ERROR("Error allocating tensor for image size tensor.");
223244
return gxf::ToResultCode(img_size_tensor_result);
224245
}
225-
cudaMemcpy(img_size_tensor.value()->pointer(),img_size.data(), 2*sizeof(float),cudaMemcpyHostToDevice);
246+
cudaMemcpyAsync(
247+
img_size_tensor.value()->pointer(),img_size.data(), 2*sizeof(float),
248+
cudaMemcpyHostToDevice, cuda_stream_);
249+
250+
if (cudaStreamSynchronize(cuda_stream_) != cudaSuccess) {
251+
GXF_LOG_ERROR("Failed to synchronize stream");
252+
return GXF_FAILURE;
253+
}
226254

227255
out_points_->publish(std::move(out_message.value()));
228256
return GXF_SUCCESS;

isaac_ros_gxf_extensions/gxf_isaac_ros_segment_anything/gxf/segment_anything/segment_anything_prompt_processor.hpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2-
// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
2+
// Copyright (c) 2024-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
33
//
44
// Licensed under the Apache License, Version 2.0 (the "License");
55
// you may not use this file except in compliance with the License.
@@ -27,6 +27,9 @@
2727
#include "detection2_d_array_message.hpp"
2828
#include "isaac_ros_nitros_detection2_d_array_type/nitros_detection2_d_array.hpp"
2929

30+
#include "gxf/cuda/cuda_stream.hpp"
31+
#include "gxf/cuda/cuda_stream_pool.hpp"
32+
3033
namespace nvidia {
3134
namespace isaac_ros {
3235

@@ -47,15 +50,18 @@ class SegmentAnythingPromptProcessor : public gxf::Codelet {
4750
std::vector<float>& label_vec
4851
);
4952
private:
50-
5153
gxf::Parameter<gxf::Handle<gxf::Receiver>> in_;
5254
gxf::Parameter<gxf::Handle<gxf::Transmitter>> out_points_;
5355
gxf::Parameter<gxf::Handle<gxf::Allocator>> allocator_;
5456
gxf::Parameter<std::vector<int32_t>> orig_img_dim_;
5557
gxf::Parameter<int32_t> max_batch_size_;
5658
gxf::Parameter<std::string> prompt_type_name_;
5759
gxf::Parameter<bool> has_input_mask_;
58-
60+
gxf::Parameter<gxf::Handle<gxf::CudaStreamPool>> cuda_stream_pool_;
61+
// CUDA stream variables
62+
gxf::Handle<gxf::CudaStream> cuda_stream_handle_;
63+
cudaStream_t cuda_stream_ = 0;
64+
5965
const uint16_t IMAGE_WIDTH_ = 1024;
6066
const uint16_t IMAGE_HEIGHT_ = 1024;
6167
uint16_t resized_width_;

isaac_ros_gxf_extensions/gxf_isaac_ros_segment_anything/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0
2121
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
2222
<package format="3">
2323
<name>gxf_isaac_ros_segment_anything</name>
24-
<version>3.2.5</version>
24+
<version>4.0.0</version>
2525
<description>Segmentation Anything extension.</description>
2626

2727
<maintainer email="[email protected]">Isaac ROS Maintainers</maintainer>

isaac_ros_gxf_extensions/gxf_isaac_ros_unet/gxf/image_segmentation/segmentation_mask_colorizer.cpp

Lines changed: 24 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2-
// Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
2+
// Copyright (c) 2022-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
33
//
44
// Licensed under the Apache License, Version 2.0 (the "License");
55
// you may not use this file except in compliance with the License.
@@ -114,27 +114,46 @@ gxf_result_t SegmentationMaskColorizer::registerInterface(gxf::Registrar * regis
114114
color_segmentation_mask_encoding_str_, "color_segmentation_mask_encoding",
115115
"Color Segmentation Mask Encoding",
116116
"The encoding of the colored segmentation mask. This should be either rgb8 or bgr8");
117+
result &= registrar->parameter(cuda_stream_pool_, "stream_pool", "Cuda Stream Pool",
118+
"Instance of gxf::CudaStreamPool to allocate CUDA stream.");
117119
return gxf::ToResultCode(result);
118120
}
119121

120122
gxf_result_t SegmentationMaskColorizer::start()
121123
{
124+
// Get cuda stream from stream pool
125+
auto maybe_stream = cuda_stream_pool_.get()->allocateStream();
126+
if (!maybe_stream) { return gxf::ToResultCode(maybe_stream); }
127+
128+
cuda_stream_handle_ = std::move(maybe_stream.value());
129+
if (!cuda_stream_handle_->stream()) {
130+
GXF_LOG_ERROR("Allocated stream is not initialized!");
131+
return GXF_FAILURE;
132+
}
133+
if (!cuda_stream_handle_.is_null()) {
134+
cuda_stream_ = cuda_stream_handle_->stream().value();
135+
}
136+
122137
if (color_palette_vec_.get().empty()) {
123138
GXF_LOG_ERROR("Error: received empty color palette!");
124139
return GXF_FAILURE;
125140
}
126141

127142
int64_t * data{nullptr};
128143
cudaError_t result =
129-
cudaMalloc(&data, sizeof(int64_t) * color_palette_vec_.get().size());
144+
cudaMallocAsync(&data, sizeof(int64_t) * color_palette_vec_.get().size(), cuda_stream_);
130145
if (result != cudaSuccess) {return GXF_FAILURE;}
131146
color_palette_.data.reset(data);
132-
133-
result = cudaMemcpy(
147+
result = cudaMemcpyAsync(
134148
color_palette_.data.get(), color_palette_vec_.get().data(),
135-
color_palette_vec_.get().size() * sizeof(int64_t), cudaMemcpyHostToDevice);
149+
color_palette_vec_.get().size() * sizeof(int64_t), cudaMemcpyHostToDevice, cuda_stream_);
136150
if (result != cudaSuccess) {return GXF_FAILURE;}
137151

152+
if (cudaStreamSynchronize(cuda_stream_) != cudaSuccess) {
153+
GXF_LOG_ERROR("Failed to synchronize stream");
154+
return GXF_FAILURE;
155+
}
156+
138157
if (color_segmentation_mask_encoding_str_.get() == std::string{"rgb8"}) {
139158
color_segmentation_mask_encoding_ = ColorImageEncodings::kRGB8;
140159
} else if (color_segmentation_mask_encoding_str_.get() == std::string{"bgr8"}) {

isaac_ros_gxf_extensions/gxf_isaac_ros_unet/gxf/image_segmentation/segmentation_mask_colorizer.hpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
2-
// Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
2+
// Copyright (c) 2022-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
33
//
44
// Licensed under the Apache License, Version 2.0 (the "License");
55
// you may not use this file except in compliance with the License.
@@ -27,6 +27,8 @@
2727
#include "gxf/std/receiver.hpp"
2828
#include "gxf/std/transmitter.hpp"
2929
#include "segmentation_mask_colorizer.cu.hpp"
30+
#include "gxf/cuda/cuda_stream.hpp"
31+
#include "gxf/cuda/cuda_stream_pool.hpp"
3032

3133
namespace nvidia {
3234
namespace isaac_ros {
@@ -45,6 +47,10 @@ class SegmentationMaskColorizer : public gxf::Codelet {
4547
gxf::Parameter<gxf::Handle<gxf::Allocator>> allocator_;
4648
gxf::Parameter<std::vector<int64_t>> color_palette_vec_;
4749
gxf::Parameter<std::string> color_segmentation_mask_encoding_str_;
50+
gxf::Parameter<gxf::Handle<gxf::CudaStreamPool>> cuda_stream_pool_;
51+
// CUDA stream variables
52+
gxf::Handle<gxf::CudaStream> cuda_stream_handle_;
53+
cudaStream_t cuda_stream_ = 0;
4854

4955
ArrayView<int64_t> color_palette_;
5056
ColorImageEncodings color_segmentation_mask_encoding_;

isaac_ros_gxf_extensions/gxf_isaac_ros_unet/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0
2121
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
2222
<package format="3">
2323
<name>gxf_isaac_ros_unet</name>
24-
<version>3.2.5</version>
24+
<version>4.0.0</version>
2525
<description>Segmentation post-processor extension.</description>
2626

2727
<maintainer email="[email protected]">Isaac ROS Maintainers</maintainer>

isaac_ros_peoplesemseg_models_install/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0
2121
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
2222
<package format="3">
2323
<name>isaac_ros_peoplesemseg_models_install</name>
24-
<version>3.2.5</version>
24+
<version>4.0.0</version>
2525
<description>Scripts for installing people segmentation models</description>
2626

2727
<maintainer email="[email protected]">Isaac ROS Maintainers</maintainer>

0 commit comments

Comments
 (0)