|
| 1 | +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES |
| 2 | +# Copyright (c) 2024 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 | +import struct |
| 19 | + |
| 20 | +from isaac_ros_tensor_list_interfaces.msg import Tensor, TensorList |
| 21 | +import numpy as np |
| 22 | +import rclpy |
| 23 | +from rclpy.node import Node |
| 24 | + |
| 25 | + |
| 26 | +class TensorInspectorNode(Node): |
| 27 | + # Conversion map from Tensor.msg's data types to Python types |
| 28 | + MSG_TO_PYTHON_MAP = { |
| 29 | + # data_type_number : ('struct_specifier', num_bytes) |
| 30 | + 1: ('b', 1), # int8 |
| 31 | + 2: ('B', 1), # uint8 |
| 32 | + 3: ('h', 2), # int16 |
| 33 | + 4: ('H', 2), # uint16 |
| 34 | + 5: ('i', 4), # int32 |
| 35 | + 6: ('I', 4), # uint32 |
| 36 | + 7: ('q', 8), # int64 |
| 37 | + 8: ('Q', 8), # uint64 |
| 38 | + 9: ('f', 4), # float32 |
| 39 | + 10: ('d', 8) # float64 |
| 40 | + } |
| 41 | + |
| 42 | + # Conversion map from Numpy types to Tensor.msg's data types |
| 43 | + PYTHON_TO_MSG_MAP = { |
| 44 | + # dtype : data_type_number |
| 45 | + np.dtype('int8'): 1, |
| 46 | + np.dtype('uint8'): 2, |
| 47 | + np.dtype('int16'): 3, |
| 48 | + np.dtype('uint16'): 4, |
| 49 | + np.dtype('int32'): 5, |
| 50 | + np.dtype('uint32'): 6, |
| 51 | + np.dtype('int64'): 7, |
| 52 | + np.dtype('uint64'): 8, |
| 53 | + np.dtype('float32'): 9, |
| 54 | + np.dtype('float64'): 10 |
| 55 | + } |
| 56 | + |
| 57 | + def __init__(self): |
| 58 | + super().__init__('tensor_inspector') |
| 59 | + |
| 60 | + # Input side: whether or not to save the original tensor received |
| 61 | + self.subscription = self.create_subscription( |
| 62 | + TensorList, |
| 63 | + 'original_tensor', |
| 64 | + self.listener_callback, |
| 65 | + 10) |
| 66 | + |
| 67 | + self.declare_parameter('original_tensor_npz_path', '') |
| 68 | + |
| 69 | + self.original_tensor_npz_path = self.get_parameter( |
| 70 | + 'original_tensor_npz_path').get_parameter_value().string_value |
| 71 | + |
| 72 | + self.should_save_original = len(self.original_tensor_npz_path) > 0 |
| 73 | + |
| 74 | + if self.should_save_original: |
| 75 | + self.get_logger().info( |
| 76 | + f'Original tensor received will be saved to {self.original_tensor_npz_path}') |
| 77 | + |
| 78 | + # Output side: whether or not to replace the original tensor with an edited one |
| 79 | + self.publisher = self.create_publisher( |
| 80 | + TensorList, |
| 81 | + 'edited_tensor', |
| 82 | + 10) |
| 83 | + |
| 84 | + self.declare_parameter('edited_tensor_npz_path', '') |
| 85 | + |
| 86 | + edited_tensor_npz_path = self.get_parameter( |
| 87 | + 'edited_tensor_npz_path').get_parameter_value().string_value |
| 88 | + |
| 89 | + self.should_edit = len(edited_tensor_npz_path) > 0 |
| 90 | + |
| 91 | + if self.should_edit: |
| 92 | + self.edited_tensor_data = np.load(edited_tensor_npz_path) |
| 93 | + self.get_logger().info( |
| 94 | + f'Edited tensor will be loaded from {edited_tensor_npz_path}') |
| 95 | + |
| 96 | + def listener_callback(self, msg): |
| 97 | + |
| 98 | + if self.should_save_original: |
| 99 | + tensor_dict = {} |
| 100 | + for tensor in msg.tensors: |
| 101 | + dims = tensor.shape.dims |
| 102 | + N = np.prod(dims) |
| 103 | + self.get_logger().debug( |
| 104 | + f'Tensor {tensor.name} with dims {dims} has N={N} elements') |
| 105 | + |
| 106 | + conversion = self.MSG_TO_PYTHON_MAP.get(tensor.data_type) |
| 107 | + if conversion is None: |
| 108 | + self.get_logger().error( |
| 109 | + f'Original tensor {tensor.name} has unknown data type {tensor.data_type}') |
| 110 | + continue |
| 111 | + |
| 112 | + element_format, element_num_bytes = conversion |
| 113 | + |
| 114 | + elements = [] |
| 115 | + for i in range(N): |
| 116 | + # Interpret tensor fields as particular numeric type from bytes |
| 117 | + element = struct.unpack(f'<{element_format}', tensor.data[ |
| 118 | + element_num_bytes * i: |
| 119 | + element_num_bytes * (i + 1) |
| 120 | + ])[0] # struct.unpack returns a tuple with one element |
| 121 | + |
| 122 | + elements.append(element) |
| 123 | + |
| 124 | + # Add element as numpy array to dictionary |
| 125 | + tensor_dict[tensor.name] = np.resize(elements, dims) |
| 126 | + |
| 127 | + np.savez(self.original_tensor_npz_path, **tensor_dict) |
| 128 | + self.get_logger().debug('Saved original tensor') |
| 129 | + |
| 130 | + if self.should_edit: |
| 131 | + tensors = [] |
| 132 | + for tensor_name, tensor_npz in self.edited_tensor_data.items(): |
| 133 | + # Create new tensor from data |
| 134 | + tensor = Tensor() |
| 135 | + |
| 136 | + tensor.name = tensor_name |
| 137 | + |
| 138 | + tensor.shape.rank = len(tensor_npz.shape) |
| 139 | + tensor.shape.dims = tensor_npz.shape |
| 140 | + |
| 141 | + element_data_type = self.PYTHON_TO_MSG_MAP.get(tensor_npz.dtype) |
| 142 | + if element_data_type is None: |
| 143 | + self.get_logger().error( |
| 144 | + f'Edited tensor {tensor.name} has unknown data type {tensor_npz.dtype}') |
| 145 | + continue |
| 146 | + |
| 147 | + tensor.data_type = element_data_type |
| 148 | + tensor.strides = tensor_npz.strides |
| 149 | + |
| 150 | + tensor.data = tensor_npz.tobytes() |
| 151 | + |
| 152 | + tensors.append(tensor) |
| 153 | + |
| 154 | + # Overwrite original tensors with new tensors |
| 155 | + msg.tensors = tensors |
| 156 | + self.get_logger().debug('Edited tensor') |
| 157 | + |
| 158 | + self.publisher.publish(msg) |
| 159 | + self.get_logger().debug('Published tensor message') |
| 160 | + |
| 161 | + |
| 162 | +def main(args=None): |
| 163 | + rclpy.init(args=args) |
| 164 | + node = TensorInspectorNode() |
| 165 | + rclpy.spin(node) |
| 166 | + rclpy.shutdown() |
| 167 | + |
| 168 | + |
| 169 | +if __name__ == '__main__': |
| 170 | + main() |
0 commit comments