Skip to content

Commit dd1600f

Browse files
committed
Isaac ROS 0.9.2 (EA2.1)
release-ea2.1: aa1178dd2dccb9ce28807f750af87bdfc344856b
1 parent 12c5686 commit dd1600f

39 files changed

+437
-2235
lines changed

LICENSE

Lines changed: 43 additions & 107 deletions
Large diffs are not rendered by default.

README.md

Lines changed: 35 additions & 127 deletions
Large diffs are not rendered by default.

giistr-cla.md

Lines changed: 0 additions & 58 deletions
This file was deleted.

isaac_ros_dnn_encoders/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ install(TARGETS dnn_image_encoder_node
4040
if(BUILD_TESTING)
4141
find_package(ament_lint_auto REQUIRED)
4242

43-
# Ignore copyright notices since we use custom JetPack EULA
43+
# Ignore copyright notices since we use custom NVIDIA Isaac ROS Software License
4444
set(ament_cmake_copyright_FOUND TRUE)
4545

4646
ament_lint_auto_find_test_dependencies()

isaac_ros_dnn_encoders/include/isaac_ros_dnn_encoders/dnn_image_encoder_node.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313

1414
#include <memory>
1515
#include <string>
16+
#include <vector>
1617

1718
#include "image_transport/image_transport.hpp"
1819
#include "isaac_ros_nvengine_interfaces/msg/tensor_list.hpp"
@@ -44,6 +45,10 @@ class DnnImageEncoderNode : public rclcpp::Node
4445
const int network_image_width_;
4546
const int network_image_height_;
4647
const std::string network_image_encoding_;
48+
const bool maintain_aspect_ratio_;
49+
const bool center_crop_;
50+
const std::vector<double> image_mean_;
51+
const std::vector<double> image_stddev_;
4752

4853
// Name of the published Tensor message
4954
const std::string tensor_name_;

isaac_ros_dnn_encoders/package.xml

Lines changed: 14 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,23 @@
11
<?xml version="1.0"?>
2+
3+
<!--
4+
Copyright (c) 2021, NVIDIA CORPORATION. All rights reserved.
5+
6+
NVIDIA CORPORATION and its licensors retain all intellectual property
7+
and proprietary rights in and to this software, related documentation
8+
and any modifications thereto. Any use, reproduction, disclosure or
9+
distribution of this software and related documentation without an express
10+
license agreement from NVIDIA CORPORATION is strictly prohibited.
11+
-->
12+
213
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
314
<package format="3">
415
<name>isaac_ros_dnn_encoders</name>
516
<version>0.9.0</version>
617
<description>Encoders for preprocessing before running deep learning inference</description>
718
<maintainer email="[email protected]">Hemal Shah</maintainer>
8-
<license>Jetpack EULA</license>
9-
<url type="website">https://developer.nvidia.com/blog/accelerating-ai-modules-for-ros-and-ros-2-on-jetson/</url>
19+
<license>NVIDIA Isaac ROS Software License</license>
20+
<url type="website">https://developer.nvidia.com/isaac-ros-gems/</url>
1021
<author>Ethan Yu</author>
1122
<author>Kajanan Chinniah</author>
1223

@@ -22,4 +33,4 @@
2233
<export>
2334
<build_type>ament_cmake</build_type>
2435
</export>
25-
</package>
36+
</package>

isaac_ros_dnn_encoders/src/dnn_image_encoder_node.cpp

Lines changed: 68 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
#include <memory>
1414
#include <string>
1515
#include <unordered_map>
16+
#include <vector>
1617

1718
#include "cv_bridge/cv_bridge.h"
1819
#include "opencv2/dnn.hpp"
@@ -24,13 +25,16 @@ enum NormalizationTypes
2425
{
2526
kNone,
2627
kUnitScaling,
27-
kPositiveNegative
28+
kPositiveNegative,
29+
kImageNormalization
2830
};
2931

3032
const std::unordered_map<std::string, int32_t> g_str_to_normalization_type({
3133
{"none", NormalizationTypes::kNone},
3234
{"unit_scaling", NormalizationTypes::kUnitScaling},
33-
{"positive_negative", NormalizationTypes::kPositiveNegative}});
35+
{"positive_negative", NormalizationTypes::kPositiveNegative},
36+
{"image_normalization", NormalizationTypes::kImageNormalization}}
37+
);
3438

3539
const std::unordered_map<std::string, std::string> g_str_to_image_encoding({
3640
{"rgb8", sensor_msgs::image_encodings::RGB8},
@@ -53,6 +57,10 @@ struct DnnImageEncoderNode::DnnImageEncoderImpl
5357
std::string image_encoding_;
5458
std::string normalization_type_;
5559
std::string tensor_name_;
60+
bool maintain_aspect_ratio_;
61+
bool center_crop_;
62+
std::vector<double> image_mean_;
63+
std::vector<double> image_stddev_;
5664

5765
void Initialize(DnnImageEncoderNode * encoder_node)
5866
{
@@ -62,6 +70,10 @@ struct DnnImageEncoderNode::DnnImageEncoderImpl
6270
image_encoding_ = node->network_image_encoding_;
6371
normalization_type_ = node->network_normalization_type_;
6472
tensor_name_ = node->tensor_name_;
73+
maintain_aspect_ratio_ = node->maintain_aspect_ratio_;
74+
center_crop_ = node->center_crop_;
75+
image_mean_ = node->image_mean_;
76+
image_stddev_ = node->image_stddev_;
6577
}
6678

6779
isaac_ros_nvengine_interfaces::msg::TensorList OnCallback(
@@ -73,6 +85,39 @@ struct DnnImageEncoderNode::DnnImageEncoderImpl
7385

7486
// Resize the image to the user specified dimensions
7587
cv::Mat image_resized;
88+
89+
if (maintain_aspect_ratio_) {
90+
const double width_ratio = static_cast<double>(image_msg->width) /
91+
static_cast<double>(image_width_);
92+
const double height_ratio = static_cast<double>(image_msg->height) /
93+
static_cast<double>(image_height_);
94+
cv::Size size;
95+
if (height_ratio < width_ratio) { // Cropping width
96+
const double target_ratio = static_cast<double>(image_width_) /
97+
static_cast<double>(image_height_);
98+
const double crop_height = image_msg->height;
99+
// Make sure the amount cropped is less than or equal to the current width of image
100+
const bool cropped_less = target_ratio * image_msg->height < image_msg->width;
101+
const double crop_width =
102+
(cropped_less) ? target_ratio * image_msg->height : image_msg->width;
103+
cv::Rect cropped_area(
104+
(center_crop_) ? (static_cast<double>(image_msg->width) - crop_width) / 2.0 : 0,
105+
0, crop_width, crop_height);
106+
image_ptr->image = image_ptr->image(cropped_area);
107+
} else { // Cropping height
108+
const double target_ratio = static_cast<double>(image_height_) /
109+
static_cast<double>(image_width_);
110+
const double crop_width = image_msg->width;
111+
// Make sure the amount cropped is less than or equal to the current height of image
112+
const bool cropped_less = target_ratio * image_msg->width < image_msg->height;
113+
const double crop_height =
114+
(cropped_less) ? target_ratio * image_msg->width : image_msg->height;
115+
cv::Rect cropped_area(0,
116+
(center_crop_) ? (static_cast<double>(image_msg->height) - crop_height) / 2.0 : 0,
117+
crop_width, crop_height);
118+
image_ptr->image = image_ptr->image(cropped_area);
119+
}
120+
}
76121
cv::resize(image_ptr->image, image_resized, cv::Size(image_width_, image_height_));
77122

78123
// Normalize tensor depending on normalization type required
@@ -83,6 +128,16 @@ struct DnnImageEncoderNode::DnnImageEncoderImpl
83128
case NormalizationTypes::kPositiveNegative:
84129
image_resized.convertTo(image_resized, CV_32F, 2.0f / 255.0f, -1.0f);
85130
break;
131+
case NormalizationTypes::kImageNormalization:
132+
image_resized.convertTo(image_resized, CV_32F);
133+
image_resized.forEach<cv::Vec3f>(
134+
[this](cv::Vec3f & pixel, const int *) -> void
135+
{
136+
pixel[0] = (pixel[0] / 255.0f - image_mean_[0]) / image_stddev_[0];
137+
pixel[1] = (pixel[1] / 255.0f - image_mean_[1]) / image_stddev_[1];
138+
pixel[2] = (pixel[2] / 255.0f - image_mean_[2]) / image_stddev_[2];
139+
});
140+
break;
86141
default:
87142
image_resized.convertTo(image_resized, CV_32F);
88143
}
@@ -126,6 +181,10 @@ DnnImageEncoderNode::DnnImageEncoderNode(const rclcpp::NodeOptions options)
126181
network_image_width_(declare_parameter<int>("network_image_width", 224)),
127182
network_image_height_(declare_parameter<int>("network_image_height", 224)),
128183
network_image_encoding_(declare_parameter<std::string>("network_image_encoding", "rgb8")),
184+
maintain_aspect_ratio_(declare_parameter<bool>("maintain_aspect_ratio", false)),
185+
center_crop_(declare_parameter<bool>("center_crop", false)),
186+
image_mean_(declare_parameter<std::vector<double>>("image_mean", {0.5, 0.5, 0.5})),
187+
image_stddev_(declare_parameter<std::vector<double>>("image_stddev", {0.5, 0.5, 0.5})),
129188
tensor_name_(declare_parameter<std::string>("tensor_name", "input")),
130189
network_normalization_type_(declare_parameter<std::string>(
131190
"network_normalization_type", "unit_scaling")),
@@ -155,6 +214,13 @@ DnnImageEncoderNode::DnnImageEncoderNode(const rclcpp::NodeOptions options)
155214
network_normalization_type_);
156215
}
157216

217+
if (network_normalization_type_ == "image_normalization" &&
218+
(image_mean_.size() != 3 || image_stddev_.size() != 3))
219+
{
220+
throw std::runtime_error(
221+
"Error: if normalization type is set to Image Normalization, vectors image_mean "
222+
"and image_stddev must have exactly 3 elements");
223+
}
158224
impl_->Initialize(this);
159225
}
160226

Lines changed: 130 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,130 @@
1+
# Copyright (c) 2021, NVIDIA CORPORATION. All rights reserved.
2+
#
3+
# NVIDIA CORPORATION and its licensors retain all intellectual property
4+
# and proprietary rights in and to this software, related documentation
5+
# and any modifications thereto. Any use, reproduction, disclosure or
6+
# distribution of this software and related documentation without an express
7+
# license agreement from NVIDIA CORPORATION is strictly prohibited.
8+
9+
from math import floor
10+
import os
11+
import pathlib
12+
import struct
13+
import time
14+
15+
from cv_bridge import CvBridge
16+
from isaac_ros_nvengine_interfaces.msg import TensorList
17+
from isaac_ros_test import IsaacROSBaseTest
18+
from launch_ros.actions import ComposableNodeContainer
19+
from launch_ros.descriptions import ComposableNode
20+
import numpy as np
21+
22+
import pytest
23+
import rclpy
24+
25+
from sensor_msgs.msg import Image
26+
27+
28+
DIMENSION_WIDTH = 500
29+
DIMENSION_HEIGHT = 500
30+
31+
32+
@pytest.mark.rostest
33+
def generate_test_description():
34+
encoder_node = ComposableNode(
35+
name='encoder',
36+
package='isaac_ros_dnn_encoders',
37+
plugin='isaac_ros::dnn_inference::DnnImageEncoderNode',
38+
namespace=IsaacROSDnnImageEncoderImageNormNodeTest.generate_namespace(),
39+
parameters=[{
40+
'network_image_width': DIMENSION_WIDTH,
41+
'network_image_height': DIMENSION_HEIGHT,
42+
'network_image_encoding': 'rgb8',
43+
'network_normalization_type': 'image_normalization',
44+
'image_mean': [0.5, 0.6, 0.25],
45+
'image_stddev': [0.25, 0.8, 0.5]
46+
}],
47+
remappings=[('encoded_tensor', 'tensors')])
48+
49+
return IsaacROSDnnImageEncoderImageNormNodeTest.generate_test_description([
50+
ComposableNodeContainer(
51+
name='tensor_rt_container',
52+
package='rclcpp_components',
53+
executable='component_container',
54+
composable_node_descriptions=[encoder_node],
55+
namespace=IsaacROSDnnImageEncoderImageNormNodeTest.generate_namespace(),
56+
output='screen'
57+
)
58+
])
59+
60+
61+
class IsaacROSDnnImageEncoderImageNormNodeTest(IsaacROSBaseTest):
62+
filepath = pathlib.Path(os.path.dirname(__file__))
63+
64+
def test_image_normalization(self):
65+
"""
66+
Test Image Normalization feature.
67+
68+
Test that the DNN Image encoder is correctly normalizing the image based on
69+
the given image mean and standard deviation vectors.
70+
Given that the image mean vector is <0.5, 0.6, 0.25>, and the image standard
71+
deviation vector is <0.25, 0.8, 0.5>, and that our input image is white
72+
(each pixel value is 255), the value for each channel should be:
73+
RED: ((255 / 255) - 0.5) / 0.25 = 2.0
74+
GREEN: ((255 / 255) - 0.6) / 0.8 = 0.5
75+
BLUE: ((255/ 255) - 0.25) / 0.5 = 1.5
76+
This test verifies that each channel's values should be the calculated values
77+
above.
78+
"""
79+
TIMEOUT = 300
80+
received_messages = {}
81+
RED_EXPECTED_VAL = 2.0
82+
GREEN_EXPECTED_VAL = 0.5
83+
BLUE_EXPECTED_VAL = 1.5
84+
85+
self.generate_namespace_lookup(['image', 'tensors'])
86+
87+
image_pub = self.node.create_publisher(
88+
Image, self.namespaces['image'], self.DEFAULT_QOS)
89+
90+
subs = self.create_logging_subscribers(
91+
[('tensors', TensorList)], received_messages)
92+
93+
try:
94+
# Create white image
95+
cv_image = np.zeros((500, 500, 3), np.uint8)
96+
cv_image[:] = (255, 255, 255)
97+
image = CvBridge().cv2_to_imgmsg(cv_image)
98+
image.encoding = 'rgb8'
99+
100+
end_time = time.time() + TIMEOUT
101+
done = False
102+
103+
while time.time() < end_time:
104+
image_pub.publish(image)
105+
rclpy.spin_once(self.node, timeout_sec=(0.1))
106+
if 'tensors' in received_messages:
107+
done = True
108+
break
109+
self.assertTrue(done, 'Appropriate output not received')
110+
tensor = received_messages['tensors'].tensors[0]
111+
112+
# This tensor has the format NCHW, so the stride for channel is
113+
# calculated by VALUES_PER_CHANNEL. `tensor.data` is also storing
114+
# raw bytes - the tensor values are floats, which are 4 bytes.
115+
VALUES_PER_CHANNEL = DIMENSION_HEIGHT * DIMENSION_WIDTH
116+
SIZEOF_FLOAT = 4
117+
for i in range(0, floor(len(tensor.data) / SIZEOF_FLOAT)):
118+
# struct.unpack returns a tuple with one element
119+
result_val = struct.unpack(
120+
'<f', tensor.data[SIZEOF_FLOAT * i: SIZEOF_FLOAT * i + SIZEOF_FLOAT])[0]
121+
if i // VALUES_PER_CHANNEL == 0: # Red
122+
self.assertTrue(result_val == RED_EXPECTED_VAL)
123+
elif i // VALUES_PER_CHANNEL == 1: # Green
124+
self.assertTrue(result_val == GREEN_EXPECTED_VAL)
125+
else: # Blue
126+
self.assertTrue(result_val == BLUE_EXPECTED_VAL)
127+
128+
finally:
129+
self.node.destroy_subscription(subs)
130+
self.node.destroy_publisher(image_pub)

0 commit comments

Comments
 (0)