|
| 1 | +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES |
| 2 | +# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. |
| 3 | +# |
| 4 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 5 | +# you may not use this file except in compliance with the License. |
| 6 | +# You may obtain a copy of the License at |
| 7 | +# |
| 8 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 9 | +# |
| 10 | +# Unless required by applicable law or agreed to in writing, software |
| 11 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 12 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 13 | +# See the License for the specific language governing permissions and |
| 14 | +# limitations under the License. |
| 15 | +# |
| 16 | +# SPDX-License-Identifier: Apache-2.0 |
| 17 | + |
| 18 | +from math import ceil |
| 19 | +import os |
| 20 | +import pathlib |
| 21 | +import struct |
| 22 | +import time |
| 23 | + |
| 24 | +from cv_bridge import CvBridge |
| 25 | +from isaac_ros_tensor_list_interfaces.msg import TensorList |
| 26 | +from isaac_ros_test import IsaacROSBaseTest |
| 27 | +from launch_ros.actions import ComposableNodeContainer |
| 28 | +from launch_ros.descriptions import ComposableNode |
| 29 | +import numpy as np |
| 30 | + |
| 31 | +import pytest |
| 32 | +import rclpy |
| 33 | + |
| 34 | +from sensor_msgs.msg import Image |
| 35 | + |
| 36 | + |
| 37 | +INPUT_IMAGE_WIDTH = 1920 |
| 38 | +INPUT_IMAGE_HEIGHT = 1080 |
| 39 | + |
| 40 | +NETWORK_IMAGE_WIDTH = 512 |
| 41 | +NETWORK_IMAGE_HEIGHT = 512 |
| 42 | +IMAGE_MEAN = np.array([0.5, 0.6, 0.25]) |
| 43 | +IMAGE_STDDEV = np.array([0.25, 0.8, 0.5]) |
| 44 | + |
| 45 | + |
| 46 | +@pytest.mark.rostest |
| 47 | +def generate_test_description(): |
| 48 | + encoder_node = ComposableNode( |
| 49 | + name='encoder', |
| 50 | + package='isaac_ros_dnn_encoders', |
| 51 | + plugin='nvidia::isaac_ros::dnn_inference::DnnImageEncoderNode', |
| 52 | + namespace=IsaacROSDnnImageEncoderImageResizeNodeTest.generate_namespace(), |
| 53 | + parameters=[{ |
| 54 | + 'network_image_width': NETWORK_IMAGE_WIDTH, |
| 55 | + 'network_image_height': NETWORK_IMAGE_HEIGHT, |
| 56 | + 'image_mean': list(IMAGE_MEAN), |
| 57 | + 'image_stddev': list(IMAGE_STDDEV) |
| 58 | + }], |
| 59 | + remappings=[('encoded_tensor', 'tensors')]) |
| 60 | + |
| 61 | + return IsaacROSDnnImageEncoderImageResizeNodeTest.generate_test_description([ |
| 62 | + ComposableNodeContainer( |
| 63 | + name='tensor_rt_container', |
| 64 | + package='rclcpp_components', |
| 65 | + executable='component_container_mt', |
| 66 | + composable_node_descriptions=[encoder_node], |
| 67 | + namespace=IsaacROSDnnImageEncoderImageResizeNodeTest.generate_namespace(), |
| 68 | + output='screen', |
| 69 | + arguments=['--ros-args', '--log-level', 'info', |
| 70 | + '--log-level', 'isaac_ros_test.encoder:=debug'], |
| 71 | + ) |
| 72 | + ]) |
| 73 | + |
| 74 | + |
| 75 | +class IsaacROSDnnImageEncoderImageResizeNodeTest(IsaacROSBaseTest): |
| 76 | + filepath = pathlib.Path(os.path.dirname(__file__)) |
| 77 | + |
| 78 | + def test_image_resize(self): |
| 79 | + """Test Image Resize feature.""" |
| 80 | + TIMEOUT = 300 |
| 81 | + received_messages = {} |
| 82 | + |
| 83 | + self.generate_namespace_lookup(['image', 'tensors']) |
| 84 | + |
| 85 | + image_pub = self.node.create_publisher( |
| 86 | + Image, self.namespaces['image'], self.DEFAULT_QOS) |
| 87 | + |
| 88 | + subs = self.create_logging_subscribers( |
| 89 | + [('tensors', TensorList)], received_messages) |
| 90 | + |
| 91 | + try: |
| 92 | + # Create gray image with colored pixels |
| 93 | + cv_image = np.ones((INPUT_IMAGE_HEIGHT, INPUT_IMAGE_WIDTH, 3), np.uint8) * 127 |
| 94 | + |
| 95 | + # What fraction of each dimension should be colored for tracing |
| 96 | + TRACER_PATCH_SIZE_FRACTION = 0.05 |
| 97 | + |
| 98 | + # Patch guaranteed to be at least 1 pixel large |
| 99 | + TRACER_PATCH_HEIGHT = ceil(TRACER_PATCH_SIZE_FRACTION * INPUT_IMAGE_HEIGHT) |
| 100 | + TRACER_PATCH_WIDTH = ceil(TRACER_PATCH_SIZE_FRACTION * INPUT_IMAGE_WIDTH) |
| 101 | + |
| 102 | + # Input image layout: |
| 103 | + # ------------------- |
| 104 | + # | R G | |
| 105 | + # | | |
| 106 | + # | | |
| 107 | + # | B | |
| 108 | + # ------------------- |
| 109 | + |
| 110 | + # Red pixels in top left corner |
| 111 | + cv_image[:TRACER_PATCH_HEIGHT, :TRACER_PATCH_WIDTH] = (0, 0, 255) |
| 112 | + |
| 113 | + # Green pixels in top right corner |
| 114 | + cv_image[:TRACER_PATCH_HEIGHT, -TRACER_PATCH_WIDTH:] = (0, 255, 0) |
| 115 | + |
| 116 | + # Blue pixels in bottom left corner |
| 117 | + cv_image[-TRACER_PATCH_HEIGHT:, :TRACER_PATCH_WIDTH] = (255, 0, 0) |
| 118 | + |
| 119 | + image = CvBridge().cv2_to_imgmsg(cv_image) |
| 120 | + image.encoding = 'bgr8' |
| 121 | + |
| 122 | + end_time = time.time() + TIMEOUT |
| 123 | + done = False |
| 124 | + |
| 125 | + while time.time() < end_time: |
| 126 | + image_pub.publish(image) |
| 127 | + rclpy.spin_once(self.node, timeout_sec=(0.1)) |
| 128 | + if 'tensors' in received_messages: |
| 129 | + done = True |
| 130 | + break |
| 131 | + self.assertTrue(done, 'Appropriate output not received') |
| 132 | + tensor = received_messages['tensors'].tensors[0] |
| 133 | + |
| 134 | + SIZEOF_FLOAT = 4 |
| 135 | + self.assertTrue( |
| 136 | + len(tensor.data) / SIZEOF_FLOAT == |
| 137 | + NETWORK_IMAGE_HEIGHT * NETWORK_IMAGE_WIDTH * 3, |
| 138 | + 'Tensor did not have the expected length!' |
| 139 | + ) |
| 140 | + |
| 141 | + def offset_nchw(n, c, h, w): |
| 142 | + # Tensor has been encoded in NCHW format |
| 143 | + # N = 1 # Since only one image has been sent, N = 1 |
| 144 | + C = 3 # Tensor encoding is R, G, B ordering |
| 145 | + H = NETWORK_IMAGE_HEIGHT # Output height |
| 146 | + W = NETWORK_IMAGE_WIDTH # Output width |
| 147 | + return n * C * H * W + c * H * W + h * W + w |
| 148 | + |
| 149 | + def extract_pixel(data, x, y): |
| 150 | + return ( |
| 151 | + # Convert bytes to float representing color channel |
| 152 | + struct.unpack('<f', data[ |
| 153 | + SIZEOF_FLOAT * offset: |
| 154 | + SIZEOF_FLOAT * (offset + 1) |
| 155 | + ])[0] # struct.unpack returns a tuple with one element |
| 156 | + for offset in ( |
| 157 | + # Calculate byte offsets for each color channel |
| 158 | + offset_nchw(0, i, y, x) for i in range(3) |
| 159 | + ) |
| 160 | + ) |
| 161 | + |
| 162 | + red_pixel, green_pixel, blue_pixel = None, None, None |
| 163 | + |
| 164 | + # Compute expected values corresponding to R, G, B after normalization |
| 165 | + RED_EXPECTED_VAL, GREEN_EXPECTED_VAL, BLUE_EXPECTED_VAL = ( |
| 166 | + 1 - IMAGE_MEAN) / IMAGE_STDDEV |
| 167 | + |
| 168 | + COLOR_MATCH_TOLERANCE = 0.05 |
| 169 | + for y in range(NETWORK_IMAGE_HEIGHT): |
| 170 | + for x in range(NETWORK_IMAGE_WIDTH): |
| 171 | + # Extract 3 float values corresponding to the |
| 172 | + r, g, b = extract_pixel(tensor.data, x, y) |
| 173 | + |
| 174 | + # Match pixel based on color channels |
| 175 | + # Only record the first matching pixel |
| 176 | + if red_pixel is None and abs(r - RED_EXPECTED_VAL) < COLOR_MATCH_TOLERANCE: |
| 177 | + red_pixel = (x, y) |
| 178 | + if green_pixel is None and abs(g - GREEN_EXPECTED_VAL) < COLOR_MATCH_TOLERANCE: |
| 179 | + green_pixel = (x, y) |
| 180 | + if blue_pixel is None and abs(b - BLUE_EXPECTED_VAL) < COLOR_MATCH_TOLERANCE: |
| 181 | + blue_pixel = (x, y) |
| 182 | + |
| 183 | + self.assertIsNotNone( |
| 184 | + red_pixel, f'Failed to find any red pixels with r={RED_EXPECTED_VAL}') |
| 185 | + self.assertIsNotNone( |
| 186 | + green_pixel, f'Failed to find any green pixels with g={GREEN_EXPECTED_VAL}') |
| 187 | + self.assertIsNotNone( |
| 188 | + blue_pixel, f'Failed to find any blue pixels with b={BLUE_EXPECTED_VAL}') |
| 189 | + |
| 190 | + # Calculate distances between tracer pixels |
| 191 | + output_width = green_pixel[0] - red_pixel[0] + 1 # Top right - Top left |
| 192 | + output_height = blue_pixel[1] - red_pixel[1] + 1 # Bottom left - Top left |
| 193 | + |
| 194 | + # Ensure aspect ratio was preserved |
| 195 | + self.assertAlmostEquals( |
| 196 | + output_width / output_height, |
| 197 | + INPUT_IMAGE_WIDTH / INPUT_IMAGE_HEIGHT, |
| 198 | + places=2, |
| 199 | + msg='Aspect ratio was not preserved!' |
| 200 | + ) |
| 201 | + |
| 202 | + finally: |
| 203 | + self.node.destroy_subscription(subs) |
| 204 | + self.node.destroy_publisher(image_pub) |
0 commit comments