diff --git a/README.md b/README.md index 9c5df13..2eb8567 100644 --- a/README.md +++ b/README.md @@ -31,6 +31,9 @@ Isaac ROS NITROS is composed of a number of individual packages, each with eithe `isaac_ros_nitros_type`: : This folder contains a number of packages, each defining a specific NITROS type and the associated type adaptation logic to convert to and from a standard ROS type. +`isaac_ros_pynitros`: +: This folder contains the implementation of Python NITROS. + --- ## Documentation @@ -45,11 +48,28 @@ Please visit the [Isaac ROS Documentation](https://nvidia-isaac-ros.github.io/re * [`isaac_ros_managed_nitros`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_managed_nitros/index.html) * [`isaac_ros_nitros`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros/index.html) * [Quickstart](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros/index.html#quickstart) +* [Isaac ROS NITROS Bridge](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/index.html) + * [Overview](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/index.html#overview) + * [Performance](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/index.html#performance) + * [Packages](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/index.html#packages) + * [Quickstart](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/index.html#quickstart) + * [Try Another Example](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/index.html#try-another-example) + * [Troubleshooting](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/index.html#troubleshooting) + * [Updates](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/index.html#updates) +* [`isaac_ros_nitros_bridge_ros1`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros1/index.html) + * [API](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros1/index.html#api) +* [`isaac_ros_nitros_bridge_ros2`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/index.html) + * [API](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/index.html#api) * [`isaac_ros_nitros_interfaces`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_interfaces/index.html) * [`isaac_ros_nitros_topic_tools`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_topic_tools/index.html) * [NitrosCameraDrop Node](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_topic_tools/index.html#nitroscameradrop-node) * [`isaac_ros_nitros_type`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_nitros_type/index.html) +* [`isaac_ros_pynitros`](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_pynitros/index.html) + * [Creating PyNITROS-Accelerated Nodes](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_pynitros/index.html#creating-pynitros-accelerated-nodes) + * [Quickstart](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_pynitros/index.html#quickstart) + * [Try More Examples](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_pynitros/index.html#try-more-examples) + * [API Reference](https://nvidia-isaac-ros.github.io/repositories_and_packages/isaac_ros_nitros/isaac_ros_pynitros/index.html#api-reference) ## Latest -Update 2024-09-26: Update for Isaac ROS 3.1 +Update 2024-12-10: Update to be compatible with JetPack 6.1 diff --git a/isaac_ros_gxf/CMakeLists.txt b/isaac_ros_gxf/CMakeLists.txt index 29d3b5d..5279c25 100644 --- a/isaac_ros_gxf/CMakeLists.txt +++ b/isaac_ros_gxf/CMakeLists.txt @@ -34,17 +34,17 @@ install( # Install extensions directory if( ${ARCHITECTURE} STREQUAL "x86_64" ) - install(DIRECTORY gxf/core/lib/gxf_x86_64_cuda_12_2/ DESTINATION share/${PROJECT_NAME}/gxf/lib) - install(FILES gxf/core/lib/gxf_x86_64_cuda_12_2/core/libgxf_core.so DESTINATION lib) - install(FILES gxf/core/lib/gxf_x86_64_cuda_12_2/logger/libgxf_logger.so DESTINATION lib) - install(FILES gxf/core/lib/gxf_x86_64_cuda_12_2/multimedia/libgxf_multimedia.so DESTINATION lib) - install(FILES gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/libgxf_cuda.so DESTINATION lib) + install(DIRECTORY gxf/core/lib/gxf_x86_64_cuda_12_6/ DESTINATION share/${PROJECT_NAME}/gxf/lib) + install(FILES gxf/core/lib/gxf_x86_64_cuda_12_6/core/libgxf_core.so DESTINATION lib) + install(FILES gxf/core/lib/gxf_x86_64_cuda_12_6/logger/libgxf_logger.so DESTINATION lib) + install(FILES gxf/core/lib/gxf_x86_64_cuda_12_6/multimedia/libgxf_multimedia.so DESTINATION lib) + install(FILES gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/libgxf_cuda.so DESTINATION lib) elseif( ${ARCHITECTURE} STREQUAL "aarch64" ) - install(DIRECTORY gxf/core/lib/gxf_jetpack60/ DESTINATION share/${PROJECT_NAME}/gxf/lib) - install(FILES gxf/core/lib/gxf_jetpack60/core/libgxf_core.so DESTINATION lib) - install(FILES gxf/core/lib/gxf_jetpack60/logger/libgxf_logger.so DESTINATION lib) - install(FILES gxf/core/lib/gxf_jetpack60/multimedia/libgxf_multimedia.so DESTINATION lib) - install(FILES gxf/core/lib/gxf_jetpack60/cuda/libgxf_cuda.so DESTINATION lib) + install(DIRECTORY gxf/core/lib/gxf_jetpack61/ DESTINATION share/${PROJECT_NAME}/gxf/lib) + install(FILES gxf/core/lib/gxf_jetpack61/core/libgxf_core.so DESTINATION lib) + install(FILES gxf/core/lib/gxf_jetpack61/logger/libgxf_logger.so DESTINATION lib) + install(FILES gxf/core/lib/gxf_jetpack61/multimedia/libgxf_multimedia.so DESTINATION lib) + install(FILES gxf/core/lib/gxf_jetpack61/cuda/libgxf_cuda.so DESTINATION lib) endif() # Register cmake in install. @@ -124,4 +124,10 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE cmake) diff --git a/isaac_ros_gxf/gxf/core/include/common/assert.hpp b/isaac_ros_gxf/gxf/core/include/common/assert.hpp index 3446951..2332e39 100644 --- a/isaac_ros_gxf/gxf/core/include/common/assert.hpp +++ b/isaac_ros_gxf/gxf/core/include/common/assert.hpp @@ -126,4 +126,15 @@ std::to_string(_vb).c_str()); \ } +// Asserts that abs(A - B) <= abs_error. If not prints a panic message and aborts the program. +#define GXF_ASSERT_NEAR(exp_a, exp_b, exp_abs_error) \ + { \ + const auto _va = exp_a; \ + const auto _vb = exp_b; \ + const auto _verror = exp_abs_error; \ + GXF_ASSERT(std::abs(_va - _vb) <= _verror, "Assert failed: abs(%s - %s) <= %s.", \ + std::to_string(_va).c_str(), std::to_string(_vb).c_str(), \ + std::to_string(_verror).c_str()); \ + } + #endif // NVIDIA_COMMON_ASSERT_HPP_ diff --git a/isaac_ros_gxf/gxf/core/include/common/fixed_vector.hpp b/isaac_ros_gxf/gxf/core/include/common/fixed_vector.hpp index a09e8bd..ab0c59f 100644 --- a/isaac_ros_gxf/gxf/core/include/common/fixed_vector.hpp +++ b/isaac_ros_gxf/gxf/core/include/common/fixed_vector.hpp @@ -57,6 +57,7 @@ class FixedVectorBase { kArgumentOutOfRange, // Argument is out of valid range kContainerEmpty, // Container is empty kContainerFull, // Container is fixed and reached max capacity + kInvalidIterator, // Iterator is invalid }; // Expected type which uses class specific errors @@ -187,6 +188,27 @@ class FixedVectorBase { constexpr Expected insert(size_t index, T&& obj) { return emplace(index, std::forward(obj)); } + + // Insert elements from another fixed vector object to the specified index + constexpr Expected insert(iterator index, iterator start, iterator end) { + size_t count = static_cast(std::distance(start, end)); + size_t pos = static_cast(std::distance(begin(), index)); + if ((pos > size_) || (pos + count > capacity_) || (count < 0)) { + return Unexpected{Error::kArgumentOutOfRange}; + } + + auto maybe_value = *start; + if (maybe_value) { + T* ptr = &(*maybe_value); + ArrayCopyConstruct(BytePointer(data_ + pos), ptr, count); + size_ += count; + } else { + return Unexpected{Error::kInvalidIterator}; + } + + return kSuccess; + } + // Copies the object to the end of the vector constexpr Expected push_back(const T& obj) { return emplace_back(obj); } // Moves the object to the end of the vector diff --git a/isaac_ros_gxf/gxf/core/include/common/type_name.hpp b/isaac_ros_gxf/gxf/core/include/common/type_name.hpp index 874690f..c7f2985 100644 --- a/isaac_ros_gxf/gxf/core/include/common/type_name.hpp +++ b/isaac_ros_gxf/gxf/core/include/common/type_name.hpp @@ -20,7 +20,10 @@ #include #if defined(__clang__) -// Not yet implemented +inline char* TypenameAsStringImpl(const char* begin, char* output, int32_t max_length) { + // Return nullptr since this is not implemented + return nullptr; +} #elif defined(__GNUC__) #include "type_name_gnuc.hpp" #elif defined(_MSC_VER) diff --git a/isaac_ros_gxf/gxf/core/include/gxf/app/application.hpp b/isaac_ros_gxf/gxf/core/include/gxf/app/application.hpp index 740fad8..09b0d96 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/app/application.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/app/application.hpp @@ -162,28 +162,28 @@ class Application : public Segment { * each segment is launched asynchronously and this thread is blocked until each one of * the segments have finished execution. If the graph contains multiple entities, * then this thread is blocked until the graph execution is complete. - * @return gxf_result_t On success the function returns GXF_SUCCESS. + * @return Expected Success or error code */ Expected run(); /** * @brief A non blocking api call to run an application. If the application contains multiple * segments, each segment is launched asynchronously. - * @return gxf_result_t On success the function returns GXF_SUCCESS. + * @return Expected Success or error code */ Expected runAsync(); /** * @brief A non blocking api to stop all running running segments or entities. * - * @return gxf_result_t On success the function returns GXF_SUCCESS. + * @return Expected Success or error code */ Expected interrupt(); /** * @brief A blocking API to waits until the graph execution has completed * - * @return gxf_result_t On success the function returns GXF_SUCCESS. + * @return Expected Success or error code */ Expected wait(); @@ -284,6 +284,7 @@ class Application : public Segment { Expected activate(); Expected deactivate(); Expected finalize(); + Expected setupCrashHandler(); std::map> segments_; std::map> segments_plan_; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/app/arg.hpp b/isaac_ros_gxf/gxf/core/include/gxf/app/arg.hpp index 10a17fe..f480b95 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/app/arg.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/app/arg.hpp @@ -92,7 +92,7 @@ struct ArgOverride> { GXF_LOG_ERROR("Unable to find the entity for %s", c_name.c_str()); return Unexpected{result}; } - result = GxfParameterGetStr(value.context(), eid, kInternalNameParameterKey, &entity_name); + result = GxfEntityGetName(value.context(), eid, &entity_name); if (result != GXF_SUCCESS) { GXF_LOG_ERROR("Unable to get the entity name"); return Unexpected{result}; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/app/entity_group.hpp b/isaac_ros_gxf/gxf/core/include/gxf/app/entity_group.hpp new file mode 100644 index 0000000..83a1926 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/app/entity_group.hpp @@ -0,0 +1,93 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef NVIDIA_GXF_ENTITY_GROUP_HPP_ +#define NVIDIA_GXF_ENTITY_GROUP_HPP_ + +#include +#include +#include +#include + +#include "gxf/app/graph_entity.hpp" + +namespace nvidia { +namespace gxf { + +/** + * @brief A wrapper over EntityGroup C APIs to manage a programmable + * entity group in C++ API layer + * + */ +class EntityGroup { + public: + EntityGroup() = default; + + ~EntityGroup() = default; + + EntityGroup(const EntityGroup&) = delete; + + EntityGroup& operator=(const EntityGroup&) = delete; + + /** + * @brief Creates a programmable entity group with the runtime context and sets its name + * + * @param context A valid GXF context + * @param name Name of the graph entity + */ + Expected setup(gxf_context_t context, const char* name); + + /** + * @brief Add single entity into this entity group. + * All Resouce components within the group will be automatically resolved to owner components + * that has corresponding type of Resource members registered. + * + * @param GraphEntityPtr An entity in C++ API representation + */ + Expected add(GraphEntityPtr entity); + + /** + * @brief Add a list of entities into this entity group. + * All Resouce components within the group will be automatically resolved to owner components + * that has corresponding type of Resource members registered. + * + * @param entity_members A list of entities in C++ API representation + */ + Expected add(std::vector entity_members); + + /** + * @return This entity group ID. + */ + gxf_uid_t gid() const { return gid_; } + + /** + * @return This entity group name. + */ + std::string name() const { return name_; } + + private: + gxf_uid_t gid_{kNullUid}; + std::string name_; + std::map entity_members_; +}; + +typedef std::shared_ptr EntityGroupPtr; + +} // namespace gxf +} // namespace nvidia + +#endif // NVIDIA_GXF_ENTITY_GROUP_HPP_ diff --git a/isaac_ros_gxf/gxf/core/include/gxf/app/graph_entity.hpp b/isaac_ros_gxf/gxf/core/include/gxf/app/graph_entity.hpp index 940dc5d..f4f5401 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/app/graph_entity.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/app/graph_entity.hpp @@ -81,13 +81,13 @@ class GraphEntity { * @tparam T Type of component. Must be derived from nvidia::gxf::Component * @param name Name of the component * @param args Args must be of type Arg - * @return Handle Handle to newly created component + * @return Handle Handle to newly created component. Null handle if component was not created. */ template Handle add(const char* name = nullptr, Args... args) { std::vector arg_list; if constexpr (sizeof...(args) > 0) { arg_list = parseArgsOfType(args...); } - return add(name, arg_list); + return add(name, std::move(arg_list)); } /** @@ -98,7 +98,7 @@ class GraphEntity { * @tparam T Type of component. Must be derived from nvidia::gxf::Component * @param name Name of the component * @param arg_list vector of Arg used for initializing the component's parameters. - * @return Handle Handle to newly created component + * @return Handle Handle to newly created component. Null handle if component was not created. */ template Handle add(const char* name, std::vector arg_list) { @@ -115,7 +115,7 @@ class GraphEntity { */ template FixedVector, N> findAll() const { - auto maybe_result = entity_.findAll(); + auto maybe_result = entity_.findAll(); return maybe_result ? maybe_result.value() : FixedVector, N>(); } @@ -685,7 +685,7 @@ class GraphEntity { // resource lookup by name std::map> resources_; - gxf_uid_t eid_; + gxf_uid_t eid_{kNullUid}; Entity entity_; }; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/app/segment.hpp b/isaac_ros_gxf/gxf/core/include/gxf/app/segment.hpp index e792707..ca9cdb6 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/app/segment.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/app/segment.hpp @@ -30,6 +30,7 @@ #include "common/assert.hpp" #include "gxf/app/arg.hpp" #include "gxf/app/arg_parse.hpp" +#include "gxf/app/entity_group.hpp" #include "gxf/app/graph_entity.hpp" #include "gxf/app/graph_utils.hpp" #include "gxf/app/proxy_component.hpp" @@ -175,9 +176,13 @@ class Segment { virtual ~Segment() = default; - Segment(Segment&&) = default; + Segment(Segment&&) = delete; - Segment& operator=(Segment&&) = default; + Segment& operator=(Segment&&) = delete; + + Segment(const Segment&) = delete; + + Segment& operator=(const Segment&) = delete; virtual void compose() {} @@ -254,6 +259,14 @@ class Segment { return entity; } + EntityGroupPtr makeEntityGroup(const char* name, + const std::vector& entity_members = {}) { + auto entity_group = createEntityGroup(name); + entity_group->add(entity_members); + + return entity_group; + } + /** * @brief Creates a scheduling term of requested type and applies parameter component values * from a parameter pack of arguments. This api does not create the requested gxf native component. @@ -305,7 +318,7 @@ class Segment { * @tparam T Type of GXF clock component. Type must be derived from nvidia::gxf::Clock type. * @param name Name of the clock component * @param args Parameter pack of arguments / parameter values to be applied to the component - * @return Handle Handle to newly created clock component. Nullptr if component was not + * @return Handle Handle to newly created clock component. Null handle if component was not * created. */ template @@ -325,9 +338,8 @@ class Segment { * from a parameter pack of arguments. * * @tparam T Type of GXF scheduler component. Type must be derived from nvidia::gxf::Scheduler type. - * @param name Name of the scheduler component * @param args Parameter pack of arguments / parameter values to be applied to the component - * @return Handle Handle to newly created scheduler component. Nullptr if component was not + * @return Handle Handle to newly created scheduler component. Null handle if component was not * created. */ template @@ -344,7 +356,8 @@ class Segment { * are found in the segment, a new RealTimeClock component will be added to the segment. * * @param scheduler Type of the scheduler to be added. One of kGreedy, kMultithread or kEventBased - * @return Expected On success the function returns Success + * @return Handle Handle to newly created scheduler component. Null handle if component was not + * created. */ Handle setScheduler(const SchedulerType& scheduler, std::vector arg_list = {}); @@ -401,7 +414,7 @@ class Segment { /** * @brief Fetch the name of the segment * - * @return const char* + * @return const char* pointer to name of the segment */ const char* name() const { return name_.c_str(); } @@ -472,7 +485,7 @@ class Segment { } /** - * @brief A blocking API to waitW until the segment execution has completed. + * @brief A blocking API to wait until the segment execution has completed. * * @return gxf_result_t On success the function returns GXF_SUCCESS. */ @@ -577,6 +590,22 @@ class Segment { return entity; } + /** + * @brief Creates a programmable graph entity group with the given name + * + * @param name Name of the graph entity + * @return EntityGroupPtr Pointer to newly created entity group + */ + EntityGroupPtr createEntityGroup(std::string name) { + GXF_LOG_DEBUG("Creating graph entity group [%s]", name.c_str()); + auto entity_group = std::make_shared(); + if (!entity_group->setup(context_, name.c_str())) { + return nullptr; + } + entity_groups_.emplace(entity_group->gid(), entity_group); + return entity_group; + } + // Registers a new codelet type with the runtime extension template gxf_result_t registerCodelet() { @@ -591,6 +620,7 @@ class Segment { // Extension to register components on the fly std::shared_ptr runtime_ext_; std::map entities_; + std::map entity_groups_; GraphEntityPtr scheduler_entity_; GraphEntityPtr clock_entity_; GraphEntityPtr connect_entity_; @@ -601,7 +631,6 @@ class Segment { }; typedef std::shared_ptr SegmentPtr; -// typedef std::shared_ptr> ProxySegmentPtr; struct SegmentConnection { SegmentConnection(SegmentPtr source, SegmentPtr target, std::vector port_maps) diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/component.hpp b/isaac_ros_gxf/gxf/core/include/gxf/core/component.hpp index 0011600..3e1c894 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/component.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/component.hpp @@ -19,6 +19,7 @@ #include #include +#include #include #include "common/assert.hpp" @@ -51,9 +52,9 @@ class Component { // class Foo : public Component { // public: // gxf_result_t registerInterface(Registrar* registrar) override { - // GXF_REGISTER_PARAMETER(count, 1); + // registrar->parameter(count_, "count", 1); // } - // GXF_PARAMETER(int, count); + // Parameter count_; // }; virtual gxf_result_t registerInterface(Registrar* registrar) { registrar_ = registrar; @@ -114,7 +115,7 @@ class Component { template Expected setParameter(const char* key, T value) { if (!parameter_storage_) { return Unexpected{GXF_ARGUMENT_NULL}; } - return parameter_storage_->set(cid_, key, value); + return parameter_storage_->set(cid_, key, std::move(value)); } // set a parameter "key" of handle type with value diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/entity.hpp b/isaac_ros_gxf/gxf/core/include/gxf/core/entity.hpp index 12e9114..3d31f31 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/entity.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/entity.hpp @@ -23,47 +23,72 @@ #include "common/fixed_vector.hpp" #include "common/type_name.hpp" #include "gxf/core/expected.hpp" +#include "gxf/core/expected_macro.hpp" #include "gxf/core/gxf.h" #include "gxf/core/handle.hpp" namespace nvidia { namespace gxf { -// All GXF objects are entities. An entity owns multiple components which define the functionality -// of the entity. Entities themselves are nothing more than a unique identifier. -// FIXME This type is a bit strange as it looks like and entity, but is in face just a handle. +/** + * @brief All GXF objects are entities. An entity owns multiple components which define the functionality + * of the entity. Entities themselves are nothing more than a unique identifier. Entities created using the + * C++ type is ref counted. The ref count is automatically decreased when the entity object is destructed or + * goes out of scope. + * + */ class Entity { public: - // Creates a new entity + /** + * @brief Creates a new entity using the given context and optionally set the given name. The + * caller of this api own's the object. The reference count is set to 1 and it is automatically + * reduced when this object is destroyed or goes out of scope. + * + * @param context A valid GXF context + * @param name Name for the entity object to be created + * @return Expected Entity object wrapped in an expected type to capture error on failure + */ static Expected New(gxf_context_t context, const char* name = nullptr) { gxf_uid_t eid; const GxfEntityCreateInfo info = {0}; - gxf_result_t code = GxfCreateEntity(context, &info, &eid); + void* item_ptr = nullptr; + gxf_result_t code = GxfCreateEntityAndGetItem(context, &info, &eid, &item_ptr); if (code != GXF_SUCCESS) { return Unexpected{code}; } - if (name) { - code = GxfParameterSetStr(context, eid, kInternalNameParameterKey, name); - if (code != GXF_SUCCESS) { return Unexpected{code}; } - } - - return Shared(context, eid); + return Shared(context, eid, item_ptr); } - // Creates an entity handle based on an existing ID and takes ownership. - // Reference count is not increased. - static Expected Own(gxf_context_t context, gxf_uid_t eid) { + /** + * @brief Creates an entity handle based on an existing ID and takes ownership. + * Reference count is not increased. + * + * @param context A valid GXF context + * @param eid The unique object ID (UID) of a valid entity + * @param item_ptr An optional entity item pointer + * @return Expected Entity object wrapped in an expected type to capture error on failure + */ + static Expected Own(gxf_context_t context, gxf_uid_t eid, void* item_ptr = nullptr) { Entity result; result.context_ = context; result.eid_ = eid; + result.entity_item_ptr_ = item_ptr; return result; } - // Creates an entity handle based on an existing ID and shares ownership. - // Reference count is increased by one. - static Expected Shared(gxf_context_t context, gxf_uid_t eid) { + /** + * @brief Creates an entity handle based on an existing ID and shares ownership. + * Reference count is increased by one. + * + * @param context A valid GXF context + * @param eid The unique object ID (UID) of a valid entity + * @param item_ptr An optional entity item pointer + * @return Expected Entity object wrapped in an expected type to capture error on failure + */ + static Expected Shared(gxf_context_t context, gxf_uid_t eid, void* ptr = nullptr) { Entity result; result.context_ = context; result.eid_ = eid; + result.entity_item_ptr_ = ptr; const gxf_result_t code = GxfEntityRefCountInc(context, eid); if (code != GXF_SUCCESS) { return Unexpected{code}; @@ -72,24 +97,48 @@ class Entity { } } + /** + * @brief Construct a new entity object using default constructor. + * This is a null entity without a valid context of entity ID. + * + */ Entity() = default; + /** + * @brief Construct a new entity object by copying from another entity object. + * + * @param other A valid Entity object + */ Entity(const Entity& other) { eid_ = other.eid(); context_ = other.context(); + entity_item_ptr_ = other.entity_item_ptr(); if (eid_ != kNullUid) { // FIXME(dweikersdorf) How do we deal with failure? GxfEntityRefCountInc(context_, eid_); } } + /** + * @brief Construct a new entity object by moving the contents from an existing entity object. + * + * @param other A valid Entity object + */ Entity(Entity&& other) { context_ = other.context_; eid_ = other.eid_; + entity_item_ptr_ = other.entity_item_ptr_; other.context_ = kNullContext; other.eid_ = kNullUid; + other.entity_item_ptr_ = kNullUid; } + /** + * @brief Operator overload for copy assignment operation + * + * @param other A valid Entity object + * @return Entity& The resulting copied entity object + */ Entity& operator=(const Entity& other) { // In case other point to the same entity, nothing needs to be done. if (eid_ == other.eid() && context_ == other.context()) { @@ -100,6 +149,7 @@ class Entity { } context_ = other.context(); eid_ = other.eid(); + entity_item_ptr_ = other.entity_item_ptr(); if (eid_ != kNullUid) { // FIXME(dweikersdorf) How do we deal with failure? GxfEntityRefCountInc(context_, eid_); @@ -107,6 +157,12 @@ class Entity { return *this; } + /** + * @brief Operator overload for move assignment operation + * + * @param other A valid Entity object + * @return Entity& The resulting moved entity object + */ Entity& operator=(Entity&& other) { // In case other is this, then nothing should be done. if (&other == this) { @@ -117,53 +173,123 @@ class Entity { } context_ = other.context_; eid_ = other.eid_; + entity_item_ptr_ = other.entity_item_ptr_; + other.entity_item_ptr_ = nullptr; other.context_ = kNullContext; other.eid_ = kNullUid; return *this; } + /** + * @brief Destroy the Entity object. Reduces the reference count by 1. + * + */ ~Entity() { if (eid_ != kNullUid) { release(); } } - // See GxfEntityActivate + /** + * @brief Activates the entity. See GxfEntityActivate in gxf.h + * + * @return Expected + */ Expected activate() { return ExpectedOrCode(GxfEntityActivate(context(), eid())); } - // See GxfEntityDectivate + /** + * @brief Deactivates the entity. See GxfEntityDectivate in gxf.h + * + * @return Expected + */ Expected deactivate() { return ExpectedOrCode(GxfEntityDeactivate(context(), eid())); } + /** + * @brief Clone an entity from an existing entity object. The returned entity shares the + * ownership with the entity being cloned from. Reference count is increased by one. + * + * @return Expected + */ Expected clone() const { - return Shared(context(), eid()); + return Shared(context(), eid(), entity_item_ptr()); } + /** + * @brief Returns the GXF context of the entity. + * + * @return gxf_context_t + */ gxf_context_t context() const { return context_; } + + /** + * @brief Returns the unique object ID (UID) of the entity + * + * @return gxf_uid_t + */ gxf_uid_t eid() const { return eid_; } + + /** + * @brief Checks if an entity object is null (empty) or not + * + * @return true If entity is not null (empty) entity object + * @return false If the entity is a valid object + */ bool is_null() const { return eid_ == kNullUid; } - // The name of the entity or empty string if no name has been given to the entity. + /** + * @brief The name of the entity or empty string if no name has been given to the entity. + * + * @return const char* pointer to name of the entity + */ const char* name() const { const char* ptr; - const gxf_result_t result = GxfParameterGetStr(context_, eid_, kInternalNameParameterKey, &ptr); + const gxf_result_t result = GxfEntityGetName(context_, eid_, &ptr); return (result == GXF_SUCCESS) ? ptr : ""; } - // Adds a component with given type ID + /** + * @brief Adds a component with given type ID. + * + * @param tid A valid type ID of a registered component + * @param name Name to be given to the newly created component instance + * @return Expected An untyped handle to component or error on failure + */ Expected add(gxf_tid_t tid, const char* name = nullptr) { gxf_uid_t cid; - const auto result = GxfComponentAdd(context(), eid(), tid, name, &cid); + void* comp_ptr = nullptr; + GXF_RETURN_IF_ERROR(check_entity_item_ptr()); + const auto result = GxfComponentAddAndGetPtr(context(), entity_item_ptr(), tid, + name, &cid, &comp_ptr); if (result != GXF_SUCCESS) { return Unexpected{result}; } - return UntypedHandle::Create(context(), cid); + return UntypedHandle::Create(context(), cid, tid, comp_ptr); + } + + /** + * @brief Removes a component with given type ID. + * + * @param tid A valid type ID of a registered component + * @param name Name to be given to the newly created component instance + * @return Expected or error on failure + */ + Expected remove(gxf_tid_t tid, const char* name = nullptr) { + // TODO(pshekdar): Add new API GxfComponentRemoveCpp + const auto result = GxfComponentRemove(context(), eid(), tid, name); + return ExpectedOrCode(result); } - // Adds a component with given type + /** + * @brief Adds a component with given template component type + * + * @tparam T A valid template type of a registered component + * @param name Name to be given to the newly created component instance + * @return Expected> Typed Handle to the component instance + */ template Expected> add(const char* name = nullptr) { gxf_tid_t tid; @@ -172,57 +298,100 @@ class Entity { return Unexpected{result_1}; } gxf_uid_t cid; - const auto result_2 = GxfComponentAdd(context(), eid(), tid, name, &cid); + void* comp_ptr = nullptr; + GXF_RETURN_IF_ERROR(check_entity_item_ptr()); + const auto result_2 = GxfComponentAddAndGetPtr(context(), entity_item_ptr(), tid, name, &cid, + &comp_ptr); if (result_2 != GXF_SUCCESS) { return Unexpected{result_2}; } - return Handle::Create(context(), cid); + return Handle::Create(context(), cid, tid, comp_ptr); } - // Gets a component by type ID. Asserts if no such component. + /** + * @brief Removes a component with given template component type + * + * @tparam T A valid template type of a registered component + * @param name Name of the component + * @return Expected or error on failure + */ + template + Expected remove(const char* name = nullptr) { + gxf_tid_t tid; + // TODO(pshekdar): Add new API GxfComponentRemoveCpp + const auto result_1 = GxfComponentTypeId(context(), TypenameAsString(), &tid); + if (result_1 != GXF_SUCCESS) { + return Unexpected{result_1}; + } + const auto result_2 = GxfComponentRemove(context(), eid(), tid, name); + return ExpectedOrCode(result_2); + } + + /** + * @brief Removes a component with given uid + * + * @tparam cid A valid uid of the component + * @return Expected or error on failure + */ + Expected remove(gxf_uid_t& cid) { + const auto result = GxfComponentRemoveWithUID(context(), cid); + return ExpectedOrCode(result); + } + + /** + * @brief Gets a component by type ID. Asserts if no such component. + * + * @param tid A valid type ID of a registered component + * @param name Name of the component to lookup + * @return Expected An untyped handle to component or error on failure + */ Expected get(gxf_tid_t tid, const char* name = nullptr) const { gxf_uid_t cid; - const auto result = GxfComponentFind(context(), eid(), tid, name, nullptr, &cid); + void* comp_ptr = nullptr; + GXF_RETURN_IF_ERROR(check_entity_item_ptr()); + const auto result = GxfComponentFindAndGetPtr(context(), eid(), + static_cast(entity_item_ptr()), + tid, name, nullptr, &cid, &comp_ptr); if (result != GXF_SUCCESS) { return Unexpected{result}; } - return UntypedHandle::Create(context(), cid); + return UntypedHandle::Create(context(), cid, tid, comp_ptr); } - // Gets a component by type. Asserts if no such component. + /** + * @brief Gets a component by type. Asserts if no such component. + * + * @tparam T A valid template type of a registered component + * @param name Name of the component to lookup + * @return Expected> Typed Handle to the component instance or error on failure + */ template Expected> get(const char* name = nullptr) const { gxf_tid_t tid; + GXF_RETURN_IF_ERROR(check_entity_item_ptr()); const auto result_1 = GxfComponentTypeId(context(), TypenameAsString(), &tid); if (result_1 != GXF_SUCCESS) { return Unexpected{result_1}; } gxf_uid_t cid; - const auto result_2 = GxfComponentFind(context(), eid(), tid, name, nullptr, &cid); + void* comp_ptr = nullptr; + const auto result_2 = GxfComponentFindAndGetPtr(context(), eid(), + static_cast(entity_item_ptr()), + tid, name, nullptr, &cid, &comp_ptr); if (result_2 != GXF_SUCCESS) { return Unexpected{result_2}; } - return Handle::Create(context(), cid); + return Handle::Create(context(), cid, tid, comp_ptr); } - // Finds all components. - // Deprecated, will be removed in GXF 2.5 - Expected findAll(FixedVectorBase& components) const { - const gxf_context_t c_context = context(); - const gxf_uid_t c_eid = eid(); - for (int offset = 0; ; offset++) { - gxf_uid_t cid; - const auto code = GxfComponentFind(c_context, c_eid, GxfTidNull(), nullptr, &offset, &cid); - if (code != GXF_SUCCESS) { break; } - const auto handle = UntypedHandle::Create(c_context, cid); - if (!handle) { return ForwardError(handle); } - const auto result = components.push_back(handle.value()); - if (!result) { return Unexpected{GXF_EXCEEDING_PREALLOCATED_SIZE}; } - } - return Success; - } - - // Finds all components. + /** + * @brief Finds all components in an entity. A fixed-size vector of untyped handles of all the + * components are returned. + * + * @tparam N Capacity of the FixedVector + * @return Expected> A fixed-size vector of untyped handles of all + * the components allocated on stack + */ template Expected> findAll() const { const gxf_context_t c_context = context(); @@ -247,30 +416,85 @@ class Entity { return components; } - // Finds all components of given type. - // Deprecated, will be removed in GXF 2.5 - template - Expected findAll(FixedVectorBase>& components) const { + /** + * @brief Finds all components of given type. + * + * @tparam T A valid template type of a registered component + * @tparam N Capacity of the FixedVector + * @return Expected, N>> A fixed-size vector of typed handles of given + * component type allocated on stack + */ + template + Expected, N>> findAll() const { const gxf_context_t c_context = context(); const gxf_uid_t c_eid = eid(); gxf_tid_t tid; - const auto code = GxfComponentTypeId(c_context, TypenameAsString(), &tid); - if (code != GXF_SUCCESS) { return Unexpected{code}; } - for (int offset = 0; ; offset++) { + const gxf_result_t code = GxfComponentTypeId(c_context, TypenameAsString(), &tid); + if (code != GXF_SUCCESS) { + return Unexpected{code}; + } + FixedVector, N> components; + for (int offset = 0; static_cast(offset) < N; offset++) { gxf_uid_t cid; - const auto code = GxfComponentFind(c_context, c_eid, tid, nullptr, &offset, &cid); - if (code != GXF_SUCCESS) { break; } - const auto handle = Handle::Create(c_context, cid); - if (!handle) { return ForwardError(handle); } - const auto result = components.push_back(handle.value()); - if (!result) { return Unexpected{GXF_EXCEEDING_PREALLOCATED_SIZE}; } + const gxf_result_t code = GxfComponentFind(c_context, c_eid, tid, nullptr, &offset, &cid); + if (code != GXF_SUCCESS) { + break; + } + const auto result = Handle::Create(c_context, cid) + .map([&](Handle component) { + return components.push_back(component) + .substitute_error(GXF_EXCEEDING_PREALLOCATED_SIZE); + }); + if (!result) { + return ForwardError(result); + } } - return Success; + return components; } - // Finds all components of given type. + /** + * @brief Finds all components in an entity. A fixed-size vector of untyped handles of all the + * components are returned. + * + * @tparam N Capacity of the FixedVector + * @return Expected> A fixed-size vector of untyped handles of all + * the components allocated on heap + */ + template + Expected> findAllHeap() const { + const gxf_context_t c_context = context(); + const gxf_uid_t c_eid = eid(); + gxf_uid_t cids[N]; + uint64_t num_cids = N; + const gxf_result_t code = GxfComponentFindAll(c_context, c_eid, &num_cids, cids); + if (code != GXF_SUCCESS) { + return Unexpected{code}; + } + FixedVector components; + components.reserve(num_cids); + for (size_t i = 0; i < num_cids; i++) { + const auto result = UntypedHandle::Create(c_context, cids[i]) + .map([&](UntypedHandle component) { + return components.push_back(component) + .substitute_error(GXF_EXCEEDING_PREALLOCATED_SIZE); + }); + if (!result) { + return ForwardError(result); + } + } + return components; + } + + /** + * @brief Finds all components of given type. + * + * @tparam T A valid template type of a registered component + * @tparam N Capacity of the FixedVector + * @return Expected>> A fixed-size vector of typed handles of given + * component type allocated on heap + */ template - Expected, N>> findAll() const { + Expected>> findAllHeap() const { const gxf_context_t c_context = context(); const gxf_uid_t c_eid = eid(); gxf_tid_t tid; @@ -278,7 +502,8 @@ class Entity { if (code != GXF_SUCCESS) { return Unexpected{code}; } - FixedVector, N> components; + FixedVector> components; + components.reserve(N); for (int offset = 0; static_cast(offset) < N; offset++) { gxf_uid_t cid; const gxf_result_t code = GxfComponentFind(c_context, c_eid, tid, nullptr, &offset, &cid); @@ -297,15 +522,41 @@ class Entity { return components; } + /** + * @brief Returns the pointer to Entity Item for the entity + * + * @return void * entity item ptr + */ + void* entity_item_ptr() const { + check_entity_item_ptr(); + return entity_item_ptr_; + } + private: + /** + * @brief Set the entity item ptr if its not set already + * + * @return Expected Success or error code + */ + Expected check_entity_item_ptr() const { + if (entity_item_ptr_ != nullptr) { + return Success; + } + auto code = GxfEntityGetItemPtr(context(), eid(), + reinterpret_cast(&(entity_item_ptr_))); + return code == GXF_SUCCESS ? Success : Unexpected(code); + } + void release() { GxfEntityRefCountDec(context_, eid_); // TODO(v2) We should use the error code, but we can't // do anything about it.. eid_ = kNullUid; + entity_item_ptr_ = nullptr; } gxf_context_t context_ = kNullContext; gxf_uid_t eid_ = kNullUid; + mutable void* entity_item_ptr_ = nullptr; }; } // namespace gxf diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/gxf.h b/isaac_ros_gxf/gxf/core/include/gxf/core/gxf.h index 9da6f6b..a3b0199 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/gxf.h +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/gxf.h @@ -63,8 +63,12 @@ typedef enum { GXF_FACTORY_INCOMPATIBLE, GXF_ENTITY_NOT_FOUND, + GXF_ENTITY_NAME_EXCEEDS_LIMIT, GXF_ENTITY_COMPONENT_NOT_FOUND, + GXF_ENTITY_COMPONENT_NAME_EXCEEDS_LIMIT, GXF_ENTITY_CAN_NOT_ADD_COMPONENT_AFTER_INITIALIZATION, + GXF_ENTITY_CAN_NOT_REMOVE_COMPONENT_AFTER_INITIALIZATION, + GXF_ENTITY_MAX_COMPONENTS_LIMIT_EXCEEDED, GXF_PARAMETER_NOT_FOUND, GXF_PARAMETER_ALREADY_REGISTERED, @@ -176,7 +180,7 @@ typedef void* gxf_context_t; #define kNullContext nullptr /// @brief GXF Core Version -#define kGxfCoreVersion "4.0.0" +#define kGxfCoreVersion "4.1.0" /// @brief Creates a new GXF context /// @@ -224,12 +228,6 @@ gxf_result_t GxfContextDestroy(gxf_context_t context); /// @brief Maximum number of extensions in a context #define kMaxExtensions 1024 -/// @deprecated Use 'GxfLoadExtensions' instead -gxf_result_t GxfLoadExtension(gxf_context_t context, const char* filename); - -/// @deprecated Use 'GxfLoadExtensions' instead -gxf_result_t GxfLoadExtensionManifest(gxf_context_t context, const char* manifest_filename); - /// @brief Loads an extension from a pointer to the Extension object. /// /// `extension_ptr` must be a pointer to a valid object with `Extension` type. @@ -317,9 +315,6 @@ typedef enum { GXF_BEHAVIOR_UNKNOWN = 4, } entity_state_t; -/// @deprecated Use 'GxfCreateEntity' instead -gxf_result_t GxfEntityCreate(gxf_context_t context, gxf_uid_t* eid); - /// @brief Activates a previously created and inactive entity /// /// Activating an entity generally marks the official start of its lifetime and has multiple @@ -333,7 +328,7 @@ gxf_result_t GxfEntityCreate(gxf_context_t context, gxf_uid_t* eid); /// - Adding or removing components of an entity after activation will result in a failure. /// /// @param context A valid GXF context -/// @param eid UID of a valid entity +/// @param eid The unique object ID (UID) of a valid entity /// @return GXF error code gxf_result_t GxfEntityActivate(gxf_context_t context, gxf_uid_t eid); @@ -350,7 +345,7 @@ gxf_result_t GxfEntityActivate(gxf_context_t context, gxf_uid_t eid); /// the current execution is finished. /// /// @param context A valid GXF context -/// @param eid UID of a valid entity +/// @param eid The unique object ID (UID) of a valid entity /// @return GXF error code gxf_result_t GxfEntityDeactivate(gxf_context_t context, gxf_uid_t eid); @@ -391,13 +386,13 @@ gxf_result_t GxfEntityFindAll(gxf_context_t context, uint64_t* num_entities, gxf /// @brief Increases the reference count for an entity by 1. /// /// By default reference counting is disabled for an entity. This means that entities created with -/// 'GxfEntityCreate' are not automatically destroyed. If this function is called for an entity +/// 'GxfCreateEntity' are not automatically destroyed. If this function is called for an entity /// with disabled reference count, reference counting is enabled and the reference count is set to /// 1. Once reference counting is enabled an entity will be automatically destroyed if the reference -/// count reaches zero, or if 'GxfEntityCreate' is called explicitly. +/// count reaches zero, or if 'GxfEntityDestroy' is called explicitly. /// /// @param context A valid GXF context -/// @param eid The UID of a valid entity +/// @param eid The unique object ID (UID) of a valid entity /// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. gxf_result_t GxfEntityRefCountInc(gxf_context_t context, gxf_uid_t eid); @@ -406,27 +401,47 @@ gxf_result_t GxfEntityRefCountInc(gxf_context_t context, gxf_uid_t eid); /// See 'GxfEntityRefCountInc' for more details on reference counting. /// /// @param context A valid GXF context -/// @param eid The UID of a valid entity +/// @param eid The unique object ID (UID) of a valid entity /// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. gxf_result_t GxfEntityRefCountDec(gxf_context_t context, gxf_uid_t eid); +/// @brief Provides the reference count for an entity. +/// +/// See 'GxfEntityRefCountInc' for more details on reference counting. +/// +/// @param context A valid GXF context +/// @param eid The unique object ID (UID) of a valid entity +/// @param count The reference count of a valid entity +/// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. +gxf_result_t GxfEntityGetRefCount(gxf_context_t context, gxf_uid_t eid, int64_t* count); + /// @brief Gets the status of the entity. /// /// See 'gxf_entity_status_t' for the various status. /// /// @param context A valid GXF context -/// @param eid The UID of a valid entity +/// @param eid The unique object ID (UID) of a valid entity /// @param entity_status output; status of an entity eid /// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. gxf_result_t GxfEntityGetStatus(gxf_context_t context, gxf_uid_t eid, gxf_entity_status_t* entity_status); +/// @brief Gets the name of the entity. +/// +/// +/// @param context A valid GXF context +/// @param eid The unique object ID (UID) of a valid entity +/// @param entity_name output; name of the entity +/// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. +gxf_result_t GxfEntityGetName(gxf_context_t context, gxf_uid_t eid, + const char** entity_name); + /// @brief Gets the state of the entity. /// /// See 'entity_state_t' for the various status. /// /// @param context A valid GXF context -/// @param eid The UID of a valid entity +/// @param eid The unique object ID (UID) of a valid entity /// @param entity_state output; behavior status of an entity eid used by the /// behavior tree parent codelet /// @return GXF_SUCCESS if the operation was successful, or otherwise one of the @@ -444,7 +459,7 @@ gxf_result_t GxfEntityGetState(gxf_context_t context, gxf_uid_t eid, /// See 'AsynchronousEventState' for various states /// /// @param context A valid GXF context -/// @param eid The UID of a valid entity +/// @param eid The unique object ID (UID) of a valid entity /// @return GXF_SUCCESS if the operation was successful, or otherwise one of the /// GXF error codes. @@ -469,10 +484,24 @@ typedef enum { gxf_result_t GxfEntityNotifyEventType(gxf_context_t context, gxf_uid_t eid, gxf_event_t event); +/// @brief Gets a string describing an GXF event type +/// +/// The caller does not get ownership of the return C string and must not delete it. +/// +/// @param result A GXF error code +/// @return A pointer to a C string with the error code description. +const char* GxfEventStr(gxf_event_t event); + // -- Components --------------------------------------------------------------------------------- /// @brief Maximum number of components in an entity or extension -#define kMaxComponents 10240 +#define kMaxComponents 1024 + +/// @brief Maximum number of characters in the name of an entity +#define kMaxEntityNameSize 2048 + +/// @brief Maximum number of characters in the name of a component +#define kMaxComponentNameSize 256 /// @brief Gets the GXF unique type ID (TID) of a component /// @@ -527,10 +556,22 @@ gxf_result_t GxfComponentName(gxf_context_t context, gxf_uid_t cid, const char** /// /// @param context A valid GXF context /// @param cid The unique object ID (UID) of the component -/// @param eid The returned UID of the entity +/// @param eid The returned unique object ID (UID) of the entity /// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. gxf_result_t GxfComponentEntity(gxf_context_t context, gxf_uid_t cid, gxf_uid_t* eid); +/// @brief Gets the pointer to an entity item +/// +/// Each entity has a unique ID with respect to the context and is stored in the entity warden. This +/// function can be used to retrieve the pointer to entity item stored in the entity warden for a +/// given entity id. +/// +/// @param context A valid GXF context +/// @param eid The unique object ID (UID) of the entity +/// @param ptr The returned pointer to the entity item +/// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. +gxf_result_t GxfEntityGetItemPtr(gxf_context_t context, gxf_uid_t eid, void** ptr); + /// @brief Adds a new component to an entity /// /// An entity can contain multiple components and this function can be used to add a new component @@ -547,8 +588,50 @@ gxf_result_t GxfComponentEntity(gxf_context_t context, gxf_uid_t cid, gxf_uid_t* gxf_result_t GxfComponentAdd(gxf_context_t context, gxf_uid_t eid, gxf_tid_t tid, const char* name, gxf_uid_t* cid); +/// @brief Adds a new component to an entity +/// +/// An entity can contain multiple components and this function can be used to add a new component +/// to an Entity. A component must be added before an entity is activated, or after it was +/// deactivated. Components must not be added to active entities. The order of components is stable +/// and identical to the order in which components are added (see 'GxfComponentFind'). +/// +/// @param context A valid GXF context +/// @param item_ptr The pointer to entity item +/// @param tid The unique type ID (TID) of the component to be added to the entity. +/// @param name The name of the new component. Ownership is not transferred. +/// @param cid The returned UID of the created component +/// @param comp_ptr The returned pointer to the created component object +/// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. +gxf_result_t GxfComponentAddAndGetPtr(gxf_context_t context, void* item_ptr, gxf_tid_t tid, + const char* name, gxf_uid_t* cid, void ** comp_ptr); + +/// @brief Removes a component from an entity +/// +/// An entity can contain multiple components and this function can be used to remove a component +/// from an entity. A component must be removed before an entity is activated, or after it was +/// deactivated. Components must not be removed from active entities. +/// +/// @param context A valid GXF context +/// @param cid The UID of the component +/// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. +gxf_result_t GxfComponentRemoveWithUID(gxf_context_t context, gxf_uid_t cid); + +/// @brief Removes a component from an entity +/// +/// An entity can contain multiple components and this function can be used to remove a component +/// from an entity. A component must be removed before an entity is activated, or after it was +/// deactivated. Components must not be removed from active entities. +/// /// @brief Adds an existing component to the interface of an entity /// +/// @param context A valid GXF context +/// @param eid The unique object ID (UID) of the entity to which the component is added. +/// @param tid The unique type ID (TID) of the component to be added to the entity. +/// @param name The name of the new component. Ownership is not transferred. +/// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. +gxf_result_t GxfComponentRemove(gxf_context_t context, gxf_uid_t eid, gxf_tid_t tid, + const char * name); + /// An entity can holds references to other components in its interface, so that when finding a /// component in an entity, both the component this entity holds and those it refers to will be /// returned. @@ -584,6 +667,30 @@ gxf_result_t GxfComponentAddToInterface(gxf_context_t context, gxf_uid_t eid, gxf_result_t GxfComponentFind(gxf_context_t context, gxf_uid_t eid, gxf_tid_t tid, const char* name, int32_t* offset, gxf_uid_t* cid); +/// @brief Finds a component in an entity and returns pointer to component +/// +/// Searches components in an entity which satisfy certain criteria: component type, component name +/// . All two criteria are optional; in case no criteria is given the first component is returned +/// The main use case for "component min index" is a repeated search which continues at the index +/// which was returned by a previous search. +/// +/// In case no entity with the given criteria was found GXF_ENTITY_NOT_FOUND is returned. +/// +/// @param context A valid GXF context +/// @param eid The unique object ID (UID) of the entity which is searched. +/// @param item_ptr The pointer to entity item +/// @param tid The component type ID (TID) of the component to find (optional) +/// @param name The component name of the component to find (optional). Ownership not transferred. +/// @param offset The index of the first component in the entity to search. Also contains the index +/// of the component which was found. +/// @param cid The returned UID of the searched component +/// @param ptr The returned pointer of the searched component +/// @return GXF_SUCCESS if a component matching the criteria was found, GXF_ENTITY_NOT_FOUND if no +/// component matching the criteria was found, or otherwise one of the GXF error codes. +gxf_result_t GxfComponentFindAndGetPtr(gxf_context_t context, gxf_uid_t eid, void* item_ptr, + gxf_tid_t tid, const char* name, int32_t* offset, + gxf_uid_t* cid, void** ptr); + /// @brief Finds all components in an entity /// /// Finds and returns all component ids for the given entity. If more than `num_cids` exist diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/gxf_ext.h b/isaac_ros_gxf/gxf/core/include/gxf/core/gxf_ext.h index 40477af..08b33f3 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/gxf_ext.h +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/gxf_ext.h @@ -75,9 +75,9 @@ typedef struct { /// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. gxf_result_t GxfLoadExtensions(gxf_context_t context, const GxfLoadExtensionsInfo* info); -/// @brief Loads a metadata file generated by the nvgraph_registry +/// @brief Loads a metadata file generated by the GXF registry /// -/// The nvgraph_registry tool generates a metadata file of the contents of an extension during +/// The GXF registry tool generates a metadata file of the contents of an extension during /// registration. These metadata files can be used to resolve typename and TID's of components for /// other extensions which depend on them. metadata files do not contain the actual implementation /// of the extension and must be loaded only to run the extension query API's on extension @@ -140,6 +140,26 @@ typedef struct { gxf_result_t GxfCreateEntity(gxf_context_t context, const GxfEntityCreateInfo* info, gxf_uid_t* eid); + +/// @brief Create a new GXF entity and return the entity item ptr +/// +/// Entities are light-weight containers to hold components and form the basic building blocks +/// of a GXF application. Entities are created when a GXF file is loaded, or they can be created +/// manually using this function. Entities created with this function must be destroyed using +/// 'GxfEntityDestroy'. After the entity was created components can be added to it with +/// 'GxfComponentAdd'. To start execution of codelets on an entity the entity needs to be +/// activated first. This can happen automatically using 'GXF_ENTITY_CREATE_PROGRAM_BIT' or +/// manually using 'GxfEntityActivate'. This function also returns the pointer entity item +/// which can be used to create C++ nvidia::gxf::Entity type objects. +/// +/// @param context is the GXF context that creates the entity. +/// @param info is a pointer to a GxfEntityCreateInfo structure containing parameters affecting +/// the creation of the entity. +/// @param eid is a pointer to a gxf_uid_t handle in which the resulting entity is returned. +/// @param item_ptr is a pointer to pointer to entity item which is created +/// @return On success the function returns GXF_SUCCESS. +gxf_result_t GxfCreateEntityAndGetItem(gxf_context_t context, const GxfEntityCreateInfo* info, + gxf_uid_t* eid, void** item_ptr); // ------------------------------------------------------------------------------------------------- /// @brief Name of default EntityGroup #define kDefaultEntityGroupName "default_entity_group" @@ -164,13 +184,13 @@ gxf_result_t GxfCreateEntityGroup(gxf_context_t context, const char* name, gxf_u /// /// @param context A valid GXF context /// @param gid UID of an existing (new) EntityGroup -/// @param eid eid of an Entity +/// @param eid The unique object ID (UID) of a valid entity /// @return GXF error code gxf_result_t GxfUpdateEntityGroup(gxf_context_t context, gxf_uid_t gid, gxf_uid_t eid); /// @brief Check if an entity id is valid currently in GXF runtime /// @param context A valid GXF context -/// @param eid eid of an Entity to check +/// @param eid The unique object ID (UID) of a valid entity to check /// @param valid returned boolean indicating if the entity is valid in Gxf runtime(warden) /// @return GXF error code gxf_result_t GxfEntityIsValid(gxf_context_t context, gxf_uid_t eid, bool* valid); @@ -181,7 +201,7 @@ gxf_result_t GxfEntityIsValid(gxf_context_t context, gxf_uid_t eid, bool* valid) /// If more than `max_entities` exist only `max_entities` will be returned. /// /// @param context A valid GXF context -/// @param eid eid of an Entity +/// @param eid The unique object ID (UID) of a valid entity /// @param num_resource_cids In/Out: the max number of components that can fit in /// the buffer/the number of resources in eid's EntityGroup /// @param resource_cids A buffer allocated by the caller for returned UIDs of all resources, with @@ -191,7 +211,21 @@ gxf_result_t GxfEntityIsValid(gxf_context_t context, gxf_uid_t eid, bool* valid) gxf_result_t GxfEntityGroupFindResources(gxf_context_t context, gxf_uid_t eid, uint64_t* num_resource_cids, gxf_uid_t* resource_cids); -/// @brief Find name of EntityGroup held by entity +/// @brief Find the EntityGroup gid that the entity belongs to +/// +/// EntityGroup is a group of EntityItems, such that these entities are bonded to some +/// common properties. For now the common property is all kinds of resources. Through +/// life time of each entity, it always corresponds to an EntityGroup. Eg, newly created +/// EntityItem points to Default EntityGroup, and user can update its EntityGroup to valid +/// one only. +/// +/// @param context A valid GXF context +/// @param eid eid of an EntityItem, whose EntityGroup id field is used find EntityGroup name +/// @param gid The returned id of the entity group. +/// @return GXF_SUCCESS if the operation was successful, or otherwise one of the GXF error codes. +gxf_result_t GxfEntityGroupId(gxf_context_t context, gxf_uid_t eid, gxf_uid_t* gid); + +/// @brief Find name of EntityGroup that holds the entity /// /// EntityGroup is a group of EntityItems, such that these entities are bonded to some /// common properties. For now the common property is all kinds of resources. Through @@ -208,7 +242,7 @@ gxf_result_t GxfEntityGroupName(gxf_context_t context, gxf_uid_t eid, const char /// @brief Gets cid of a resource component that is grouped with the given entity /// /// @param context A valid GXF context -/// @param eid eid of an Entity +/// @param eid The unique object ID (UID) of a valid entity /// @param type The fully qualified C++ type name of the component /// @param resource_key the key or name of the resource /// @param resource_cid The returned cid of the resource component diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/handle.hpp b/isaac_ros_gxf/gxf/core/include/gxf/core/handle.hpp index 67754f0..8c2e167 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/handle.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/handle.hpp @@ -17,6 +17,9 @@ #ifndef NVIDIA_GXF_CORE_HANDLE_HPP #define NVIDIA_GXF_CORE_HANDLE_HPP +#include +#include + #include "common/assert.hpp" #include "common/type_name.hpp" #include "gxf/core/expected.hpp" @@ -53,12 +56,20 @@ class UntypedHandle { return untyped_handle; } + // Creates a new untyped handle with component pointer + static Expected Create(gxf_context_t context, gxf_uid_t cid, + gxf_tid_t tid, void* ptr) { + return UntypedHandle{context, cid, tid, ptr}; + } + // The context to which the component belongs gxf_context_t context() const { return context_; } // The ID of the component. gxf_uid_t cid() const { return cid_; } // The type ID describing the component type. gxf_tid_t tid() const { return tid_; } + // Get the pointer to underlying component object + void* get_ptr() const {return pointer_;} // Returns null if the handle is equivalent to a nullptr. bool is_null() const { return context_ == kNullContext || cid_ == kNullUid || pointer_ == nullptr; @@ -76,9 +87,15 @@ class UntypedHandle { UntypedHandle(gxf_context_t context, gxf_uid_t cid) : context_{context}, cid_{cid}, tid_{GxfTidNull()}, pointer_{nullptr} { } + UntypedHandle(gxf_context_t context, gxf_uid_t cid, gxf_tid_t tid, void* pointer) + : context_{context}, cid_{cid}, tid_{tid}, pointer_{pointer} {} + Expected initialize(gxf_tid_t tid) { tid_ = tid; - return ExpectedOrCode(GxfComponentPointer(context_, cid_, tid_, &pointer_)); + if (pointer_ == nullptr) { + return ExpectedOrCode(GxfComponentPointer(context_, cid_, tid_, &pointer_)); + } + return Success; } Expected initialize(const char* type_name) { @@ -143,9 +160,19 @@ class Handle : public UntypedHandle { return handle; } + static Expected Create(gxf_context_t context, gxf_uid_t cid, + gxf_tid_t tid, void * ptr) { + if (GxfTidIsNull(tid) || ptr == nullptr) { + return Create(context, cid); + } + Handle handle{context, cid, tid, ptr}; + return handle; + } + // Creates a new handle from an untyped handle static Expected Create(const UntypedHandle& untyped_handle) { - return Create(untyped_handle.context(), untyped_handle.cid()); + return Create(untyped_handle.context(), untyped_handle.cid(), + untyped_handle.tid(), untyped_handle.get_ptr()); } friend bool operator==(const Handle& lhs, const Handle& rhs) { @@ -163,6 +190,9 @@ class Handle : public UntypedHandle { Handle(gxf_context_t context = kNullContext, gxf_uid_t uid = kNullUid) : UntypedHandle{context, uid} {} + Handle(gxf_context_t context , gxf_uid_t uid , gxf_tid_t tid, void* ptr) + : UntypedHandle{context, uid, tid, ptr} {} + ~Handle() = default; Handle(const Handle& component) = default; @@ -184,12 +214,20 @@ class Handle : public UntypedHandle { } T* get() const { - GXF_ASSERT(verifyPointer(), "Invalid Component Pointer."); + // Verifying the pointer every time the handle is accessed causes a + // significant bottle neck in perf. This should be removed in a future + // release. Uncomment below line if there is any problem. + // GXF_ASSERT(verifyPointer(), "Invalid Component Pointer."); + GXF_ASSERT_FALSE(pointer_ == nullptr); return reinterpret_cast(pointer_); } Expected try_get() const { - if (!verifyPointer()) { return Unexpected{GXF_FAILURE}; } + // Verifying the pointer every time the handle is accessed causes a + // significant bottle neck in perf. This should be removed in a future + // release. Uncomment below line if there is any problem. + // if (!verifyPointer()) { return Unexpected{GXF_FAILURE}; } + if (pointer_ == nullptr) { return Unexpected{GXF_FAILURE}; } return reinterpret_cast(pointer_); } @@ -197,6 +235,62 @@ class Handle : public UntypedHandle { using UntypedHandle::UntypedHandle; }; + +// Creates a new handle given the string representation of the handle in a yaml blob +// If the value is of format / then cid is ignored. +// If the entity name is not specified, the value indicates just the component name, then +// 'cid' is used to query the entity name to create the handle +template +static Expected> CreateHandleFromString(gxf_context_t context, gxf_uid_t cid, + const char* value) { + gxf_uid_t eid; + std::string component_name; + const std::string tag{value}; + const size_t pos = tag.find('/'); + + if (pos == std::string::npos) { + // Get the entity of this component + auto result = GxfComponentEntity(context, cid, &eid); + if (result != GXF_SUCCESS) { + GXF_LOG_ERROR("Failed to find entity for component [C%05" PRId64 "] with name [%s] with" + " error %s", cid, value, GxfResultStr(result)); + return Unexpected{result}; + } + component_name = tag; + } else { + // Split the tag into entity and component name + const std::string entity_name = tag.substr(0, pos); + component_name = tag.substr(pos + 1); + // Search for the entity + auto result = GxfEntityFind(context, entity_name.c_str(), &eid); + if (result != GXF_SUCCESS) { + GXF_LOG_ERROR("Failed to find entity [E%05" PRId64 "] with name [%s] while parsing '%s'", + eid, entity_name.c_str(), tag.c_str()); + return Unexpected{result}; + } + } + + // Get the type id of the component we are are looking for. + gxf_tid_t tid; + auto result = GxfComponentTypeId(context, TypenameAsString(), &tid); + if (result != GXF_SUCCESS) { + GXF_LOG_ERROR("Failed to find type ID of component type [%s] with error %s", + TypenameAsString(), GxfResultStr(result)); + return Unexpected{result}; + } + + gxf_uid_t cid2; + // Find the component in the indicated entity + result = GxfComponentFind(context, eid, tid, component_name.c_str(), nullptr, &cid2); + if (result != GXF_SUCCESS) { + GXF_LOG_ERROR("Failed to find component in entity [E%05" PRId64 "] with name [%s]", + eid, component_name.c_str()); + return Unexpected{result}; + } + + return Handle::Create(context, cid2); +} + } // namespace gxf } // namespace nvidia diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/parameter.hpp b/isaac_ros_gxf/gxf/core/include/gxf/core/parameter.hpp index ccabf45..79be297 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/parameter.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/parameter.hpp @@ -78,13 +78,13 @@ class ParameterBackendBase { } // FIXME(v1) make private - gxf_context_t context_; - gxf_uid_t uid_; - gxf_parameter_flags_t flags_; - bool is_dynamic_; - const char* key_; - const char* headline_; - const char* description_; + gxf_context_t context_{nullptr}; + gxf_uid_t uid_{kNullUid}; + gxf_parameter_flags_t flags_{0}; + bool is_dynamic_{false}; + const char* key_{nullptr}; + const char* headline_{nullptr}; + const char* description_{nullptr}; }; template diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/parameter_parser.hpp b/isaac_ros_gxf/gxf/core/include/gxf/core/parameter_parser.hpp index 874bf55..698ba74 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/parameter_parser.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/parameter_parser.hpp @@ -167,15 +167,16 @@ struct ParameterParser> { &component_name); if (code != GXF_SUCCESS) { return Unexpected{code}; } + gxf_uid_t owner_eid, param_eid; + const char* owner_entity_name = "UNKNOWN"; + std::string param_entity_name; // Get the entity of this component - gxf_uid_t eid; - const gxf_result_t result_1 = GxfComponentEntity(context, component_uid, &eid); + const gxf_result_t result_1 = GxfComponentEntity(context, component_uid, &owner_eid); if (result_1 != GXF_SUCCESS) { return Unexpected{result_1}; } - const char* e_name = "UNKNOWN"; - code = GxfParameterGetStr(context, eid, kInternalNameParameterKey, &e_name); + code = GxfEntityGetName(context, owner_eid, &owner_entity_name); if (code != GXF_SUCCESS) { return Unexpected{code}; } // Parse string from node @@ -193,6 +194,8 @@ struct ParameterParser> { const size_t pos = tag.find('/'); if (pos == std::string::npos) { handle_component_name = tag; + // target param component and owner component reside in the same entity + param_eid = owner_eid; } else { handle_component_name = tag.substr(pos + 1); @@ -200,27 +203,31 @@ struct ParameterParser> { gxf_result_t result_1_with_prefix = GXF_FAILURE; // Try using entity name with prefix if (!prefix.empty()) { - const std::string entity_name = prefix + tag.substr(0, pos); - result_1_with_prefix = GxfEntityFind(context, entity_name.c_str(), &eid); + param_entity_name = prefix + tag.substr(0, pos); + // param eid + result_1_with_prefix = GxfEntityFind(context, param_entity_name.c_str(), ¶m_eid); if (result_1_with_prefix != GXF_SUCCESS) { GXF_LOG_WARNING("Could not find entity (with prefix) '%s' while parsing parameter '%s' " - "of component %s with id %zu", entity_name.c_str(), key, component_name, - component_uid); + "of component %s with id %zu", + param_entity_name.c_str(), key, component_name, component_uid); } } // Try using entity name without prefix, if lookup with prefix failed if (result_1_with_prefix != GXF_SUCCESS) { - const std::string entity_name = tag.substr(0, pos); - const gxf_result_t result_1_no_prefix = GxfEntityFind(context, entity_name.c_str(), &eid); + param_entity_name = tag.substr(0, pos); + // param eid + const gxf_result_t result_1_no_prefix = GxfEntityFind(context, + param_entity_name.c_str(), ¶m_eid); if (result_1_no_prefix != GXF_SUCCESS) { GXF_LOG_ERROR("Could not find entity '%s' while parsing parameter '%s' of component %s" - " with id %zu", entity_name.c_str(), key, component_name, component_uid); + " with id %zu", + param_entity_name.c_str(), key, component_name, component_uid); return Unexpected{result_1_no_prefix}; } else if (!prefix.empty()) { GXF_LOG_WARNING("Found entity (without prefix) '%s' while parsing parameter '%s' " "of component '%s' with id %zu in a subgraph, however the approach is" - " deprecated, please use prerequisites instead", entity_name.c_str(), - key, component_name, component_uid); + " deprecated, please use prerequisites instead", + param_entity_name.c_str(), key, component_name, component_uid); } } } @@ -233,20 +240,52 @@ struct ParameterParser> { } // Find the component in the indicated entity + // param eid gxf_uid_t cid; - const gxf_result_t result_3 = GxfComponentFind(context, eid, tid, handle_component_name.c_str(), - nullptr, &cid); + const gxf_result_t result_3 = GxfComponentFind(context, param_eid, tid, + handle_component_name.c_str(), nullptr, &cid); if (result_3 != GXF_SUCCESS) { if (handle_component_name == "") { GXF_LOG_DEBUG("Using an handle in entity '%s' with id %zu while parsing " "parameter '%s' of component '%s' with id %zu. This handle must be set to a valid component" - " before graph activation", e_name, eid, key, component_name, component_uid); + " before graph activation", + owner_entity_name, owner_eid, key, component_name, component_uid); return Handle::Unspecified(); } else { - GXF_LOG_WARNING("Could not find component '%s' in entity %s with id %zu while parsing " - "parameter '%s' of component '%s' with id %zu", - handle_component_name.c_str(), e_name, eid, key, component_name, - component_uid); + GXF_LOG_WARNING("Cannot find target paramter component[entity name: %s, component name: %s]" + " in type[%s] " + "for owner component[entity name: %s, component name: %s, cid: %ld], " + "during parsing its parameter[key: %s, value: %s]", + param_entity_name.c_str(), handle_component_name.c_str(), // param component info + TypenameAsString(), // expected param component type + owner_entity_name, component_name, component_uid, // owner component info + key, tag.c_str()); // param key:value string presentation + // print help info + for (int offset = 0; ; offset++) { + auto code1 = GxfComponentFind(context, param_eid, GxfTidNull(), + handle_component_name.c_str(), &offset, &cid); + if (code1 == GXF_ENTITY_COMPONENT_NOT_FOUND) { + GXF_LOG_DEBUG("No more component instance found as entity/component: %s", + tag.c_str()); + break; + } else if (code1 != GXF_SUCCESS) { + GXF_LOG_ERROR("Failed to execute component cid find with eid: %ld, " + "component name: %s, offset: %d", param_eid, handle_component_name.c_str(), offset); + return Unexpected{code1}; + } + const char* component_type_name = nullptr; + auto code2 = GxfComponentTypeNameFromUID(context, cid, &component_type_name); + if (code2 != GXF_SUCCESS) { + GXF_LOG_ERROR("Failed to find component type name from cid [%ld]", cid); + return Unexpected{code2}; + } + GXF_LOG_WARNING("Found component[%s] in type[%s]; " + "however type[%s] is expected for " + "component[entity name: %s, component name: %s, key: %s]", + tag.c_str(), component_type_name, + TypenameAsString(), owner_entity_name, component_name, key); + } + // end help info print } return Unexpected{result_3}; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/parameter_wrapper.hpp b/isaac_ros_gxf/gxf/core/include/gxf/core/parameter_wrapper.hpp index 5c23f38..fd238c6 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/parameter_wrapper.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/parameter_wrapper.hpp @@ -53,8 +53,7 @@ struct ParameterWrapper> { GXF_LOG_ERROR("Unable to find the entity for %s", c_name.c_str()); return Unexpected{result}; } - result = GxfParameterGetStr( - context, eid, kInternalNameParameterKey, &entity_name); + result = GxfEntityGetName(context, eid, &entity_name); if (result != GXF_SUCCESS) { GXF_LOG_ERROR("Unable to get the entity name"); return Unexpected{result}; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/core/resource.hpp b/isaac_ros_gxf/gxf/core/include/gxf/core/resource.hpp index e2cf8f1..87b88d5 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/core/resource.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/core/resource.hpp @@ -41,7 +41,7 @@ class Resource> { const Expected>& try_get(const char* name = nullptr) const { if (value_ == Handle::Unspecified()) { if (resource_manager_ == nullptr) { - GXF_LOG_WARNING("Resource [type: %s] from comonent [cid: %ld] cannot get " + GXF_LOG_WARNING("Resource [type: %s] from component [cid: %ld] cannot get " "its value because of nullptr ResourceManager", TypenameAsString(), owner_cid_); return unspecified_handle_; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_allocator.hpp b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_allocator.hpp new file mode 100644 index 0000000..6901fc4 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_allocator.hpp @@ -0,0 +1,41 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 +#ifndef NVIDIA_GXF_CUDA_ALLOCATOR_HPP +#define NVIDIA_GXF_CUDA_ALLOCATOR_HPP + +#include +#include + +#include "gxf/std/allocator.hpp" + +namespace nvidia { +namespace gxf { + +// Provides allocation and deallocation of memory. +class CudaAllocator : public Allocator { + public: + virtual Expected allocate_async(uint64_t size, cudaStream_t stream); + virtual Expected free_async(byte* pointer, cudaStream_t stream); + virtual gxf_result_t allocate_async_abi(uint64_t, void**, cudaStream_t) = 0; + virtual gxf_result_t free_async_abi(void*, cudaStream_t) = 0; + virtual Expected get_pool_size(MemoryStorageType type) const = 0; +}; + +} // namespace gxf +} // namespace nvidia + +#endif // NVIDIA_GXF_CUDA_ALLOCATOR_HPP diff --git a/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_buffer.hpp b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_buffer.hpp new file mode 100644 index 0000000..b113fbc --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_buffer.hpp @@ -0,0 +1,218 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 +#ifndef NVIDIA_GXF_CUDA_CUDA_BUFFER_HPP_ +#define NVIDIA_GXF_CUDA_CUDA_BUFFER_HPP_ + +#include +#include + +#include "common/byte.hpp" +#include "gxf/core/expected.hpp" +#include "gxf/core/handle.hpp" +#include "gxf/cuda/cuda_allocator.hpp" +#include "gxf/cuda/cuda_common.hpp" +#include "gxf/cuda/cuda_stream.hpp" +#include "gxf/cuda/cuda_stream_pool.hpp" +#include "gxf/std/allocator.hpp" +#include "gxf/std/memory_buffer.hpp" + +namespace nvidia { +namespace gxf { + +constexpr const char* kDefaultCudaBufferName = "gxf_cuda_buffer"; + +/** + * @brief A container for a single block of cuda memory with support for async + memory allocations. Each CudaBuffer is type of MemoryBuffer associated with a + CudaAllocator, CudaStreamPool & CudaStream. Memory is allocated by resizing the + buffer. Both cuda memory and the cuda stream is released back into the pool + when a cuda buffer object is destroyed. + */ +class CudaBuffer : public MemoryBuffer { + public: + // state of the buffer + enum class State : int8_t { + UNSET = 0, // Initial state not waiting for any cuda event callback + CALLBACK_REGISTERED, // Indicates a call back function is registered + DATA_AVAILABLE, // Indicates data is ready to be consumed + }; + + CudaBuffer() = default; + CudaBuffer(const CudaBuffer&) = delete; + CudaBuffer& operator=(const CudaBuffer&) = delete; + + CudaBuffer(CudaBuffer&& other) noexcept { *this = std::move(other); } + + CudaBuffer& operator=(CudaBuffer&& other) noexcept { + if (this == &other) { + return *this; + } + state_ = other.state_.load(); + release_func_ = std::move(other.release_func_); + stream_ = std::move(other.stream_); + stream_owner_ = other.stream_owner_.load(); + stream_pool_ = std::move(other.stream_pool_); + + other.state_ = State::UNSET; + other.stream_owner_ = false; + other.release_func_ = nullptr; + return *this; + } + + // callback function to release memory passed to the CudaBuffer + using release_function_t = std::function (void* pointer)>; + + // Host callback function prototype + using callback_function_t = void(*)(void*); + + static void CUDART_CB cudaHostCallback(void* buffer_ptr) { + auto buffer = reinterpret_cast(buffer_ptr); + GXF_LOG_VERBOSE("Received host callback from cuda stream for cuda buffer"); + auto cb_registered = State::CALLBACK_REGISTERED; + GXF_ASSERT_TRUE(buffer->state_.compare_exchange_strong(cb_registered, State::DATA_AVAILABLE)); + } + + Expected freeBuffer() { + auto state = state_.load(); + // If another callback is already registered, buffer should not be freed + GXF_ASSERT_NE(static_cast(state), static_cast(State::CALLBACK_REGISTERED)); + state_ = State::UNSET; + if (release_func_ && pointer_) { + const Expected result = release_func_(pointer_); + if (!result) { + return ForwardError(result); + } + release_func_ = nullptr; + } + + return Success; + } + + ~CudaBuffer() { freeBuffer(); } + + // Resizes the cuda buffer to given size on custom cuda stream. A new stream is allocated + // from the stream pool if a pre allocated stream is not provided. + Expected resizeAsync(Handle allocator, + Handle stream_pool, + uint64_t size, + Handle stream_handle = Handle::Null()) { + if (!allocator) { + GXF_LOG_ERROR("Invalid cuda allocator provided while resizing a cuda buffer"); + return Unexpected{GXF_ARGUMENT_INVALID}; + } + + if (!stream_pool) { + GXF_LOG_ERROR("Invalid cuda stream pool provided while resizing a cuda buffer"); + return Unexpected{GXF_ARGUMENT_INVALID}; + } + + const auto code = freeBuffer(); + if (!code) { + GXF_LOG_ERROR("Failed to free memory. Error code: %s", GxfResultStr(code.error())); + return ForwardError(code); + } + + // Allocate new stream if its not pre-allocated + if (!stream_handle) { + stream_handle = GXF_UNWRAP_OR_RETURN(stream_pool->allocateStream()); + } + auto stream = GXF_UNWRAP_OR_RETURN(stream_handle->stream()); + auto result = GXF_UNWRAP_OR_RETURN(allocator->allocate_async(size, stream)); + + GXF_LOG_VERBOSE("Registering callback for cuda buffer"); + auto unset = State::UNSET; + GXF_ASSERT_TRUE(state_.compare_exchange_strong(unset, State::CALLBACK_REGISTERED)); + cudaError_t cuda_result = cudaLaunchHostFunc(stream, cudaHostCallback, this); + CHECK_CUDA_ERROR(cuda_result, + "Unable to register host function using cudaLaunchHostFunc"); + + storage_type_ = MemoryStorageType::kDevice; + pointer_ = result; + size_ = size; + + // TODO(chandrahasj) should allow custom stream to release the data ? + release_func_ = [allocator, stream_pool, stream_handle, this] (void *data) { + auto stream = stream_handle->stream().value(); + allocator->free_async(reinterpret_cast(data), stream); + if (this->stream_owner_.load()) { + // synchronize the stream before releasing it back into the pool + auto code = cudaStreamSynchronize(stream_handle->stream().value()); + if (code != cudaSuccess) { + GXF_LOG_ERROR("Failed to synchronize cuda stream"); + return ExpectedOrCode(GXF_FAILURE); + } + return stream_pool->releaseStream(stream_handle); + } + return Success; + }; + + stream_ = stream_handle; + stream_pool_ = stream_pool; + return Success; + } + + // Retrieves cuda buffer state + State state() const { return state_.load(); } + + // Retrieves CudaStream + Handle stream() { + return stream_; + } + + // Retrieves CudaStreamPool + Handle streamPool() { + return stream_pool_; + } + + // Ownership of CudaStream is transferred to the caller. + // Stream will not be released when this object is destroyed. + Handle transferStreamOwnership() { + stream_owner_ = false; + return stream_; + } + + // Register a host function callback on the cuda stream associated with the buffer + Expected registerCallbackOnStream(callback_function_t func, void* data) { + if (!stream_) { + GXF_LOG_ERROR("CudaStream is not set for the CudaBuffer"); + return Unexpected{GXF_FAILURE}; + } + + auto stream = GXF_UNWRAP_OR_RETURN(stream_->stream()); + GXF_LOG_VERBOSE("Registering callback for cuda buffer"); + cudaError_t cuda_result = cudaLaunchHostFunc(stream, func, data); + CHECK_CUDA_ERROR(cuda_result, "Unable to register host function using cudaLaunchHostFunc"); + return Success; + } + + private: + // State of the buffer + std::atomic state_{State::UNSET}; + // Flag to keep track of shared ownership of the cuda stream + std::atomic stream_owner_{true}; + // cuda host callback function on completion of all the queued work + release_function_t release_func_ = nullptr; + // CudaStream used to allocate memory for the cuda buffer + Handle stream_ = Handle::Null(); + // CudaStreamPool used to allocate the CudaStream used by the buffer + Handle stream_pool_ = Handle::Null(); +}; + +} // namespace gxf +} // namespace nvidia + +#endif // NVIDIA_GXF_CUDA_CUDA_BUFFER_HPP_ diff --git a/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_common.hpp b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_common.hpp index 595fa59..f3598db 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_common.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_common.hpp @@ -32,6 +32,16 @@ } \ } while (0) +#define CHECK_CUDA_ERROR_RESULT(cu_result, fmt, ...) \ + do { \ + cudaError_t err = (cu_result); \ + if (err != cudaSuccess) { \ + GXF_LOG_ERROR(fmt ", cuda_error: %s, error_str: %s", ##__VA_ARGS__, \ + cudaGetErrorName(err), cudaGetErrorString(err)); \ + return GXF_FAILURE; \ + } \ + } while (0) + #define CONTINUE_CUDA_ERROR(cu_result, fmt, ...) \ do { \ cudaError_t err = (cu_result); \ diff --git a/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_scheduling_terms.hpp b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_scheduling_terms.hpp new file mode 100644 index 0000000..ec273bb --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_scheduling_terms.hpp @@ -0,0 +1,139 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 +#ifndef NVIDIA_GXF_CUDA_CUDA_SCHEDULING_TERMS_HPP_ +#define NVIDIA_GXF_CUDA_CUDA_SCHEDULING_TERMS_HPP_ + +#include + +#include +#include +#include +#include +#include +#include + +#include "gxf/core/parameter_registrar.hpp" +#include "gxf/cuda/cuda_common.hpp" +#include "gxf/cuda/cuda_event.hpp" +#include "gxf/cuda/cuda_stream_id.hpp" +#include "gxf/std/receiver.hpp" +#include "gxf/std/scheduling_term.hpp" + +namespace nvidia { +namespace gxf { + +/** + * @brief Scheduling term to monitor activity on a cuda stream + * + * A component which specifies the availability of data at the receiver on completion of + * the work on the provided cuda stream with the help of callback function to host. + * This scheduling term will register a call back function which will be called once the work on the + * specified cuda stream completes indicating that the data is available for consumption + */ +class CudaStreamSchedulingTerm : public SchedulingTerm { + public: + // state of the scheduling term + enum class State : int8_t { + UNSET = 0, // Initial state not waiting for any cuda host callback + CALLBACK_REGISTERED, // Indicates a call back function is registered + DATA_AVAILABLE, // Indicates data is ready to be consumed + }; + + gxf_result_t registerInterface(Registrar* registrar) override; + gxf_result_t check_abi(int64_t timestamp, SchedulingConditionType* type, + int64_t* target_timestamp) const override; + gxf_result_t onExecute_abi(int64_t timestamp) override; + gxf_result_t update_state_abi(int64_t timestamp) override; + + private: + // Receiver to monitor cuda stream activity + Parameter> receiver_; + // The current state of the scheduling term + SchedulingConditionType current_state_; + // Current message entity being monitored + std::atomic message_eid_ = kNullUid; + // State of the scheduling term + std::atomic state_{State::UNSET}; + // cuda host callback function on completion of all the queued work + static void CUDART_CB cudaHostCallback(void* term_ptr); +}; + +/** + * @brief Scheduling term based on cuda event + * + * A component which specifies the availability of data at the receiver on completion of the + * work on the provided cuda stream with the help of cuda event. + * This scheduling term will keep polling on the event provided to check for data availability for + * consumption. + */ +class CudaEventSchedulingTerm : public SchedulingTerm { + public: + gxf_result_t registerInterface(Registrar* registrar) override; + gxf_result_t initialize() override; + gxf_result_t check_abi(int64_t timestamp, SchedulingConditionType* type, + int64_t* target_timestamp) const override; + gxf_result_t onExecute_abi(int64_t timestamp) override; + gxf_result_t update_state_abi(int64_t timestamp) override; + + private: + Parameter> receiver_; + Parameter event_name_{}; + SchedulingConditionType current_state_; // The current state of the scheduling term + int64_t last_state_change_; // timestamp when the state changed the last time +}; + + +/** + * @brief Scheduling term based on data availability in a cuda buffer + * + * A component which specifies the availability of data at the receiver based on + * the cuda buffers present in incoming messages. + * + */ +class CudaBufferAvailableSchedulingTerm : public SchedulingTerm { + public: + // state of the scheduling term + enum class State : int8_t { + UNSET = 0, // Initial state not waiting for any cuda host callback + CALLBACK_REGISTERED, // Indicates a call back function is registered + DATA_AVAILABLE, // Indicates data is ready to be consumed + }; + gxf_result_t registerInterface(Registrar* registrar) override; + gxf_result_t check_abi(int64_t timestamp, SchedulingConditionType* type, + int64_t* target_timestamp) const override; + gxf_result_t onExecute_abi(int64_t timestamp) override; + gxf_result_t update_state_abi(int64_t timestamp) override; + + private: + // Receiver to monitor cuda stream activity + Parameter> receiver_; + // The current state of the scheduling term + SchedulingConditionType current_state_; + // Current message entity being monitored + std::atomic message_eid_ = kNullUid; + // State of the scheduling term + std::atomic state_{State::UNSET}; + // timestamp when the state changed the last time + int64_t last_state_change_; + // cuda host callback function on completion of all the queued work + static void CUDART_CB cudaHostCallback(void* term_ptr); +}; + +} // namespace gxf +} // namespace nvidia + +#endif // NVIDIA_GXF_CUDA_CUDA_SCHEDULING_TERMS_HPP_ diff --git a/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_stream.hpp b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_stream.hpp index ae53d8c..77d0186 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_stream.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/cuda/cuda_stream.hpp @@ -33,8 +33,6 @@ namespace nvidia { namespace gxf { -class CudaStreamPool; - // Holds and provides access to cudaStream_t. CudaStream is allocated and // recycled by CudaStreamPool class CudaStream { diff --git a/isaac_ros_gxf/gxf/core/include/gxf/cuda/stream_ordered_allocator.hpp b/isaac_ros_gxf/gxf/core/include/gxf/cuda/stream_ordered_allocator.hpp new file mode 100644 index 0000000..58f3afa --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/cuda/stream_ordered_allocator.hpp @@ -0,0 +1,73 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 +#ifndef NVIDIA_GXF_STREAM_ORDERED_ALLOCATOR_HPP_ +#define NVIDIA_GXF_STREAM_ORDERED_ALLOCATOR_HPP_ + +#include +#include + +#include +#include + +#include "common/assert.hpp" +#include "common/logger.hpp" +#include "gxf/core/parameter.hpp" +#include "gxf/cuda/cuda_allocator.hpp" +#include "gxf/std/resources.hpp" + +namespace nvidia { +namespace gxf { + +// An allocator which uses cudaMalloc/cudaMallocHost dynamically without a pool. +// Does not provide bounded execution times. +class StreamOrderedAllocator : public CudaAllocator { + public: + StreamOrderedAllocator() = default; + ~StreamOrderedAllocator() = default; + + gxf_result_t initialize() override; + gxf_result_t deinitialize() override; + + gxf_result_t registerInterface(Registrar* registrar) override; + gxf_result_t is_available_abi(uint64_t size) override; + gxf_result_t allocate_abi(uint64_t size, int32_t storage_type, void** pointer) override; + gxf_result_t allocate_async_abi(uint64_t size, void** pointer, + cudaStream_t stream) override; + gxf_result_t free_async_abi(void* pointer, cudaStream_t stream) override; + gxf_result_t free_abi(void* pointer) override; + + Expected get_pool_size(MemoryStorageType type) const override; + + private: + Resource> gpu_device_; + Parameter release_threshold_; + Parameter device_memory_initial_size_; + Parameter device_memory_max_size_; + + std::unordered_map pool_map_; + + AllocatorStage stage_{AllocatorStage::kUninitialized}; + std::mutex mutex_; + cudaStream_t stream_; + cudaMemPool_t memory_pool_; + cudaMemPoolProps pool_props_ = {}; +}; + +} // namespace gxf +} // namespace nvidia + +#endif // NVIDIA_GXF_STREAM_ORDERED_ALLOCATOR_HPP_ diff --git a/isaac_ros_gxf/gxf/core/include/gxf/cuda/tests/convolution.h b/isaac_ros_gxf/gxf/core/include/gxf/cuda/tests/convolution.h new file mode 100644 index 0000000..a1c8a63 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/cuda/tests/convolution.h @@ -0,0 +1,30 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 +#ifndef NVIDIA_GXF_CUDA_TESTS_CONVOLUTION_HPP +#define NVIDIA_GXF_CUDA_TESTS_CONVOLUTION_HPP + +#include + +#define THREADS_PER_BLOCK 32 +#define THREADS_PER_BLOCK_1 (THREADS_PER_BLOCK - 1) + +// A simple GPU based 2d convolution operation +extern "C" void convolveKernel(float *input, float *kernel, + float *output, int width, int height, + int kernelSize, cudaStream_t stream); + +#endif // NVIDIA_GXF_CUDA_TESTS_CONVOLUTION_HPP diff --git a/isaac_ros_gxf/gxf/core/include/gxf/cuda/tests/test_cuda_helper.hpp b/isaac_ros_gxf/gxf/core/include/gxf/cuda/tests/test_cuda_helper.hpp index efa2fa0..df530f3 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/cuda/tests/test_cuda_helper.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/cuda/tests/test_cuda_helper.hpp @@ -18,12 +18,20 @@ #define NVIDIA_GXF_CUDA_TESTS_TEST_CUDA_HELPER_HPP #include +#include #include #include +#include +#include #include +#include #include +#include + +#include "convolution.h" #include "common/assert.hpp" +#include "gxf/cuda/cuda_buffer.hpp" #include "gxf/cuda/cuda_common.hpp" #include "gxf/cuda/cuda_event.hpp" #include "gxf/cuda/cuda_stream.hpp" @@ -139,6 +147,11 @@ class StreamTensorGenerator : public StreamBasedOps { return GXF_SUCCESS; } + gxf_result_t deinitialize() override { + auto result = stream_pool_->releaseStream(stream_); + return ToResultCode(result); + } + gxf_result_t tick() override { Expected maybe_dev_msg = Entity::New(context()); GXF_ASSERT(maybe_dev_msg, "New dev message failed"); @@ -329,9 +342,10 @@ class CublasDotProduct : public StreamBasedOps { auto maybe_event = codelet_->addNewEvent(out_msg, "cudotproduct_event"); GXF_ASSERT(maybe_event, "failed to add cublas dot product event"); - ret = stream->record(maybe_event.value(), in_msg, - []() { GXF_LOG_DEBUG("cublas dotproduct event synced"); }); - GXF_ASSERT(ret, "cublas dotproduct record event failed"); + // Recording this event here causes a leak + // ret = stream->record(maybe_event.value(), in_msg, + // []() { GXF_LOG_ERROR("cublas dotproduct event synced"); }); + // GXF_ASSERT(ret, "cublas dotproduct record event failed"); return ret; } }; @@ -457,9 +471,10 @@ class MemCpy2Host : public StreamBasedOps { auto maybe_event = addNewEvent(out_msg.value(), "memcpy_event"); GXF_ASSERT(maybe_event, "failed to add memcpy_event"); - ret = stream->record(maybe_event.value(), in.value(), - []() { GXF_LOG_DEBUG("memcpy_to_host event synced"); }); - GXF_ASSERT(ret, "memcpy_to_host record event failed"); + // Recording this event here causes a leak + // ret = stream->record(maybe_event.value(), in.value(), + // []() { GXF_LOG_ERROR("memcpy_to_host event synced"); }); + // GXF_ASSERT(ret, "memcpy_to_host record event failed"); ret = tx_->publish(out_msg.value()); GXF_ASSERT(ret, "memcpy_to_host publishing tensors failed"); @@ -537,6 +552,264 @@ class VerifyEqual : public Codelet { int32_t count_ = 0; }; +// Creates a CudaBuffer object on each iteration with memory allocated in an +// asynchronous manner. Downstream receivers can either enqueue more work on to +// CudaStream associated with the CudaBuffer or sync on the stream before accessing the memory +class CudaAsyncBufferGenerator : public Codelet { + public: + virtual ~CudaAsyncBufferGenerator() = default; + + gxf_result_t registerInterface(Registrar* registrar) override { + Expected result; + result &= registrar->parameter(signal_, "signal", "Signal", + "Transmitter channel publishing messages to other graph entities"); + result &= registrar->parameter(allocator_, "allocator", "Allocator", + "A cuda allocator component that can serve device memory asynchronously"); + result &= registrar->parameter(stream_pool_, "stream_pool", "StreamPool", + "A cuda stream pool component"); + result &= registrar->parameter(size_, "size", "Size", + "Size of the CudaBuffer to be allocated", 1UL); + return ToResultCode(result); + } + + gxf_result_t tick() override { + auto maybe_message = Entity::New(context()); + if (!maybe_message) { + GXF_LOG_ERROR("Failure creating message entity."); + return maybe_message.error(); + } + + auto message = maybe_message.value(); + auto maybe_buffer = message.add(kDefaultCudaBufferName); + if (!maybe_buffer) { + GXF_LOG_ERROR("Failure creating cuda buffer"); + return maybe_buffer.error(); + } + + auto buffer = maybe_buffer.value(); + auto code = buffer->resizeAsync(allocator_, stream_pool_, size_); + + auto min = std::numeric_limits::min(); + auto max = std::numeric_limits::max(); + std::uniform_real_distribution distribution(min, max); + std::vector elements; + auto element_count = size_ / sizeof(float); + + for (size_t idx = 0; idx < element_count; idx++) { + elements.push_back(distribution(generator_)); + } + + auto stream_component = buffer->stream(); + auto stream = stream_component->stream().value(); + + const cudaError_t error = cudaMemcpyAsync(buffer->pointer(), elements.data(), + size_, cudaMemcpyHostToDevice, stream); + CHECK_CUDA_ERROR_RESULT(error, "cudaMemcpyAsync failed"); + + auto result = signal_->publish(message); + GXF_LOG_INFO("Message Sent"); + return GXF_SUCCESS; + } + + private: + Parameter> signal_; + Parameter> allocator_; + Parameter> stream_pool_; + Parameter size_; + std::default_random_engine generator_; +}; + +// Performs an async 2D convolution operation on +// incoming CudaBuffer objects. +class Convolve2D: public Codelet { + public: + virtual ~Convolve2D() = default; + + gxf_result_t registerInterface(Registrar* registrar) override { + Expected result; + result &= registrar->parameter(kernel_, "kernel", "Kernel", + "2d matrix of float values represented as a vector of vectors"); + result &= registrar->parameter(output_, "output", "Output", + "Transmitter channel publishing messages to other graph entities"); + result &= registrar->parameter(input_, "input", "Input", + "Receiver channel receiving messages from other graph entities"); + result &= registrar->parameter(allocator_, "allocator", "Allocator", + "A cuda allocator component that can serve device memory asynchronously"); + return ToResultCode(result); + } + + gxf_result_t start() override { + auto& kernel = kernel_.get(); + size_t kernel_size = kernel.size(); + + size_t index = 0; + float kernel_flat_host[kernel_size * kernel_size]; // NOLINT + for (const auto& k : kernel) { + GXF_ASSERT_EQ(k.size(), kernel_size); + for (const auto& value : k) { + kernel_flat_host[index] = value; + ++index; + } + } + + auto maybe_kernel = allocator_->allocate(kernel_size * kernel_size * sizeof(float), + MemoryStorageType::kDevice); + if (!maybe_kernel) { + return maybe_kernel.error(); + } + + kernel_flat_ = maybe_kernel.value(); + const cudaError_t error = + cudaMemcpy(kernel_flat_, kernel_flat_host, kernel_size * kernel_size * sizeof(float), + cudaMemcpyHostToDevice); + if (error != cudaSuccess) { + GXF_LOG_ERROR("CUDA Mem copy Error: %s\n", cudaGetErrorString(error)); + return GXF_FAILURE; + } + return GXF_SUCCESS; + } + + + gxf_result_t stop() override { + entity_queue_map_.clear(); + return ToResultCode(allocator_->free(kernel_flat_)); + } + + gxf_result_t tick() override { + return ToResultCode(_tick()); + } + + // payload struct to access on the callback used to + // dereference the underlying message entity + typedef struct callBackData { + Entity data; + Convolve2D* ptr; + } callBackData; + + static void CUDART_CB cudaEntityFreeCallback(void* data_ptr) { + auto data = reinterpret_cast(data_ptr); + auto convolve = data->ptr; + GXF_LOG_VERBOSE("Received entity free callback from cuda stream for " + "cuda buffer in message entity E[%05ld]", data->data.eid()); + // Entities consumed until now cannot be freed just yet in the host callback function. + // Host callback function gets executed from a cuda driver thread which cannot be used + // to call another cuda runtime api like cudaFreeAsync. Hence keep track of the + // entities to be freed the next time this codelet is executed. + std::unique_lock lock(convolve->mutex_); + convolve->entity_free_list_.push(data->data.eid()); + } + + Expected _tick() { + // Dequeue any previously consumed message entities + { + std::unique_lock lock(mutex_); + while (!entity_free_list_.empty()) { + auto element = entity_free_list_.front(); + entity_queue_map_.erase(element); + entity_free_list_.pop(); + } + } + + auto in_message = GXF_UNWRAP_OR_RETURN(input_->receive()); + GXF_LOG_INFO("Message Received: %d", this->count_); + this->count_ = this->count_ + 1; + if (in_message.is_null()) { + return Unexpected{GXF_CONTRACT_MESSAGE_NOT_AVAILABLE}; + } + + auto in_buffer = GXF_UNWRAP_OR_RETURN(in_message.get()); + auto out_message = GXF_UNWRAP_OR_RETURN(Entity::New(context())); + auto out_buffer = GXF_UNWRAP_OR_RETURN(out_message.add(kDefaultCudaBufferName)); + + auto stream_pool = in_buffer->streamPool(); + auto stream_handle = in_buffer->transferStreamOwnership(); + auto code = out_buffer->resizeAsync(allocator_, stream_pool, in_buffer->size(), stream_handle); + + const int width = 32, height = 32; + auto cu_stream = GXF_UNWRAP_OR_RETURN(stream_handle->stream()); + + convolveKernel(reinterpret_cast(in_buffer->pointer()), + reinterpret_cast(kernel_flat_), + reinterpret_cast(out_buffer->pointer()), + width, height, kernel_.get().size(), cu_stream); + + cudaError_t err = cudaGetLastError(); + if (err != cudaSuccess) { + GXF_LOG_ERROR("CUDA convolveKernel Error: %s\n", cudaGetErrorString(err)); + return Unexpected{GXF_FAILURE}; + } + + // store the incoming message entity to prevent the cuda buffer getting released + // before it is consumed. The in_message entity is only released once the kernel + // has finished its execution + auto eid = in_message.eid(); + { + std::unique_lock lock(mutex_); + entity_queue_map_.insert({eid, callBackData{std::move(in_message), this}}); + } + auto it = entity_queue_map_.find(eid); + + + GXF_RETURN_IF_ERROR(in_buffer->registerCallbackOnStream(cudaEntityFreeCallback, + reinterpret_cast(&it->second))); + + auto stream_id = GXF_UNWRAP_OR_RETURN(out_message.add()); + stream_id->stream_cid = stream_handle.cid(); + return output_->publish(out_message); + } + + private: + Parameter> allocator_; + Parameter>> kernel_; + Parameter> output_; + Parameter> input_; + byte* kernel_flat_; + std::unordered_map entity_queue_map_; + std::queue entity_free_list_; + std::shared_mutex mutex_; + int count_ = 1; +}; + +// Dequeue a message entity with a cuda buffer and ensures +// the data is available +class CudaBufferRx: public Codelet { + public: + virtual ~CudaBufferRx() = default; + + gxf_result_t registerInterface(Registrar* registrar) override { + Expected result; + result &= registrar->parameter(signal_, "signal", "Signal", + "Channel to receive messages from another graph entity"); + return ToResultCode(result); + } + + gxf_result_t tick() override { + auto maybe_message = signal_->receive(); + GXF_LOG_INFO("Message Received: %d", this->count); + this->count = this->count + 1; + if (!maybe_message || maybe_message.value().is_null()) { + return GXF_CONTRACT_MESSAGE_NOT_AVAILABLE; + } + + auto message = maybe_message.value(); + auto maybe_cuda_buffer = message.get(); + if (!maybe_cuda_buffer) { return ToResultCode(maybe_cuda_buffer); } + + auto cuda_buffer = maybe_cuda_buffer.value(); + auto state = cuda_buffer->state(); + if (state != CudaBuffer::State::DATA_AVAILABLE) { + GXF_LOG_ERROR("CudaBuffer found in an invalid state %d", static_cast(state)); + return GXF_FAILURE; + } + + return GXF_SUCCESS; + } + + private: + Parameter> signal_; + int count = 1; +}; + } // namespace cuda } // namespace test diff --git a/isaac_ros_gxf/gxf/core/include/gxf/multimedia/camera.hpp b/isaac_ros_gxf/gxf/core/include/gxf/multimedia/camera.hpp index 3f869c8..c29b8f4 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/multimedia/camera.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/multimedia/camera.hpp @@ -121,7 +121,7 @@ struct CameraModelBase { // Distortion type of the camera. DistortionType distortion_type; // Distortion coefficients of the camera. - T distortion_coefficients[kMaxDistortionCoefficients]; + std::array distortion_coefficients; }; using CameraModel = CameraModelBase; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/multimedia/video.hpp b/isaac_ros_gxf/gxf/core/include/gxf/multimedia/video.hpp index 4be5def..d25cf06 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/multimedia/video.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/multimedia/video.hpp @@ -184,6 +184,7 @@ GXF_VIDEO_TYPE_TRAITS(GXF_VIDEO_FORMAT_RAW16_BGGR); GXF_VIDEO_TYPE_TRAITS(GXF_VIDEO_FORMAT_RAW16_GRBG); GXF_VIDEO_TYPE_TRAITS(GXF_VIDEO_FORMAT_RAW16_GBRG); + // Struct to hold the information regarding a single color plane struct ColorPlane { std::string color_space; @@ -878,6 +879,7 @@ class VideoBuffer { static Expected getPlanarPrimitiveType(VideoFormat color_format) { PrimitiveType primitive_type; switch (color_format) { + case VideoFormat::GXF_VIDEO_FORMAT_NV12: // BT.601 2 planes Y, UV case VideoFormat::GXF_VIDEO_FORMAT_RGBA: // RGBA-8-8-8-8 single plane case VideoFormat::GXF_VIDEO_FORMAT_BGRA: // BGRA-8-8-8-8 single plane case VideoFormat::GXF_VIDEO_FORMAT_ARGB: // ARGB-8-8-8-8 single plane @@ -925,6 +927,10 @@ class VideoBuffer { primitive_type = PrimitiveType::kFloat64; } break; + case VideoFormat::GXF_VIDEO_FORMAT_CUSTOM: { // CUSTOM undefined + primitive_type = PrimitiveType::kCustom; + } break; + default: { // Non-planar type given GXF_LOG_ERROR("VideoFormat is of non-planar color format (%ld)," " which cannot be moved from tensor", static_cast(color_format)); diff --git a/isaac_ros_gxf/gxf/core/include/gxf/rmm/rmm_allocator.hpp b/isaac_ros_gxf/gxf/core/include/gxf/rmm/rmm_allocator.hpp new file mode 100644 index 0000000..f849af3 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/rmm/rmm_allocator.hpp @@ -0,0 +1,85 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 +#ifndef NVIDIA_GXF_RMM_RMM_ALLOCATOR_HPP_ +#define NVIDIA_GXF_RMM_RMM_ALLOCATOR_HPP_ + +#include +#include + +#include +#include +#include +#include + +#include "common/assert.hpp" +#include "common/logger.hpp" +#include "gxf/core/parameter.hpp" +#include "gxf/cuda/cuda_allocator.hpp" +#include "gxf/std/resources.hpp" +#include "rmm/device_buffer.hpp" +#include "rmm/mr/device/cuda_async_memory_resource.hpp" +#include "rmm/mr/device/pool_memory_resource.hpp" +#include "rmm/mr/host/pinned_memory_resource.hpp" +namespace nvidia { +namespace gxf { + +// RMM based device memory allocator +class RMMAllocator : public CudaAllocator { + public: + RMMAllocator() = default; + ~RMMAllocator() = default; + + gxf_result_t initialize() override; + gxf_result_t deinitialize() override; + + gxf_result_t registerInterface(Registrar* registrar) override; + gxf_result_t is_available_abi(uint64_t size) override; + gxf_result_t is_rmm_available_abi(uint64_t size, MemoryStorageType type); + gxf_result_t allocate_abi(uint64_t size, int32_t storage_type, void** pointer) override; + gxf_result_t allocate_async_abi(uint64_t size, void** pointer, + cudaStream_t stream) override; + gxf_result_t free_async_abi(void* pointer, cudaStream_t stream) override; + gxf_result_t free_abi(void* pointer) override; + + Expected get_pool_size(MemoryStorageType type) const override; + + private: + Parameter device_memory_initial_size_; + Parameter device_memory_max_size_; + Parameter host_memory_initial_size_; + Parameter host_memory_max_size_; + Resource> gpu_device_; + + AllocatorStage stage_{AllocatorStage::kUninitialized}; + std::mutex mutex_; + cudaStream_t stream_ = {}; + size_t device_max_memory_pool_size_; + size_t host_max_memory_pool_size_; + + // Create a CUDA memory resource + std::unique_ptr device_mr; + std::unique_ptr> pool_mr_device; + std::unique_ptr pinned_mr; + std::unique_ptr> pool_mr_host; + + std::unordered_map> pool_map = {}; +}; + +} // namespace gxf +} // namespace nvidia + +#endif // NVIDIA_GXF_RMM_RMM_ALLOCATOR_HPP_ diff --git a/isaac_ros_gxf/gxf/core/include/gxf/serialization/file_stream.hpp b/isaac_ros_gxf/gxf/core/include/gxf/serialization/file_stream.hpp index b130d1e..cc6dc24 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/serialization/file_stream.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/serialization/file_stream.hpp @@ -46,7 +46,7 @@ class FileStream : public Endpoint { static constexpr const char* kBinaryFileExtension = ".gxf_entities"; FileStream(std::string input_file, std::string output_file) - : input_file_path_{input_file}, output_file_path_{output_file} {} + : input_file_path_{std::move(input_file)}, output_file_path_{output_file} {} FileStream() = default; ~FileStream() = default; FileStream(const FileStream& other) = delete; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/serialization/std_entity_id_serializer.hpp b/isaac_ros_gxf/gxf/core/include/gxf/serialization/std_entity_id_serializer.hpp index faab47b..907e4bf 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/serialization/std_entity_id_serializer.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/serialization/std_entity_id_serializer.hpp @@ -48,9 +48,9 @@ class StdEntityIdSerializer : public EntitySerializer { private: // Sequence number for outgoing messages - uint64_t outgoing_sequence_number_; + uint64_t outgoing_sequence_number_{0}; // Sequence number for incoming messages - uint64_t incoming_sequence_number_; + uint64_t incoming_sequence_number_{0}; }; } // namespace gxf diff --git a/isaac_ros_gxf/gxf/core/include/gxf/serialization/std_entity_serializer.hpp b/isaac_ros_gxf/gxf/core/include/gxf/serialization/std_entity_serializer.hpp index de91443..5daf948 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/serialization/std_entity_serializer.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/serialization/std_entity_serializer.hpp @@ -93,9 +93,9 @@ class StdEntitySerializer : EntitySerializer { // Table that caches type ID with a valid component serializer std::unordered_map, TidHash> serializer_cache_; // Sequence number for outgoing messages - uint64_t outgoing_sequence_number_; + uint64_t outgoing_sequence_number_ = 0; // Sequence number for incoming messages - uint64_t incoming_sequence_number_; + uint64_t incoming_sequence_number_ = 0; }; } // namespace gxf diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/allocator.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/allocator.hpp index 059df97..e288f6f 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/std/allocator.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/allocator.hpp @@ -17,13 +17,64 @@ #ifndef NVIDIA_GXF_STD_ALLOCATOR_HPP #define NVIDIA_GXF_STD_ALLOCATOR_HPP +#include + #include "common/byte.hpp" #include "gxf/core/component.hpp" namespace nvidia { namespace gxf { -enum struct MemoryStorageType { kHost = 0, kDevice = 1, kSystem = 2 }; +enum struct MemoryStorageType { + kHost = 0, // Host Pinned Memory + kDevice = 1, // Cuda Device Memory + kSystem = 2 // Heap Memory +}; + +// Custom parameter parser for MemoryStorageType +template <> +struct ParameterParser { + static Expected Parse(gxf_context_t context, gxf_uid_t component_uid, + const char* key, const YAML::Node& node, + const std::string& prefix) { + const std::string value = node.as(); + if (strcmp(value.c_str(), "Host") == 0) { + return MemoryStorageType::kHost; + } + if (strcmp(value.c_str(), "Device") == 0) { + return MemoryStorageType::kDevice; + } + if (strcmp(value.c_str(), "System") == 0) { + return MemoryStorageType::kSystem; + } + return Unexpected{GXF_ARGUMENT_OUT_OF_RANGE}; + } +}; + +// Custom parameter parser for MemoryStorageType +template<> +struct ParameterWrapper { + static Expected Wrap(gxf_context_t context, const MemoryStorageType& value) { + YAML::Node node(YAML::NodeType::Scalar); + switch (value) { + case MemoryStorageType::kHost: { + node = std::string("Host"); + break; + } + case MemoryStorageType::kDevice: { + node = std::string("Device"); + break; + } + case MemoryStorageType::kSystem: { + node = std::string("System"); + break; + } + default: + return Unexpected{GXF_PARAMETER_OUT_OF_RANGE}; + } + return node; + } +}; // Lifecycle stages of an allocator enum struct AllocatorStage : uint8_t { diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/async_buffer_receiver.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/async_buffer_receiver.hpp new file mode 100644 index 0000000..4af4343 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/async_buffer_receiver.hpp @@ -0,0 +1,83 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 +#ifndef NVIDIA_GXF_STD_ASYNC_BUFFER_RECEIVER_HPP_ +#define NVIDIA_GXF_STD_ASYNC_BUFFER_RECEIVER_HPP_ + +#include + +#include "gxf/core/component.hpp" +#include "gxf/core/entity.hpp" +#include "gxf/core/handle.hpp" +#include "gxf/std/receiver.hpp" + +namespace nvidia { +namespace gxf { + +/** + * @brief A receiver which uses a Simpson's four-slot buffer to enable lockless/lock-free and + * asynchronous communication. This receiver is designed to be used in a single producer and single + * consumer scenario. + * + */ +class AsyncBufferReceiver : public Receiver { + public: + gxf_result_t initialize() override; + + gxf_result_t deinitialize() override; + + gxf_result_t pop_abi(gxf_uid_t* uid) override; + + gxf_result_t push_abi(gxf_uid_t other) override; + + gxf_result_t peek_abi(gxf_uid_t* uid, int32_t index) override; + + gxf_result_t peek_back_abi(gxf_uid_t* uid, int32_t index) override; + + size_t capacity_abi() override; + + size_t size_abi() override; + + gxf_result_t receive_abi(gxf_uid_t* uid) override; + + size_t back_size_abi() override; + + gxf_result_t sync_abi() override; + + gxf_result_t sync_io_abi() override; + + private: + // Resets the four-slot control variables. + void reset_buffer(); + Entity read_freshest(); + + // The following variables are used to implement a Simpson's four-slot buffer. + Entity entity_data_[2][2]; + // Four-slot control variables + int32_t freshest_; + int32_t reading_; + // control bits + int32_t slots_[2]; + + // To indicate whether the buffer has been filled at least once. After first-time, receiving end + // will always be able to retrieve a value from the buffer. + bool is_filled_first_time_; +}; + +} // namespace gxf +} // namespace nvidia + +#endif /* NVIDIA_GXF_STD_ASYNC_BUFFER_RECEIVER_HPP_ */ diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/async_buffer_transmitter.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/async_buffer_transmitter.hpp new file mode 100644 index 0000000..f0e96aa --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/async_buffer_transmitter.hpp @@ -0,0 +1,69 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef NVIDIA_GXF_STD_ASYNC_BUFFER_TRANSMITTER_HPP_ +#define NVIDIA_GXF_STD_ASYNC_BUFFER_TRANSMITTER_HPP_ + +#include + +#include "gxf/core/component.hpp" +#include "gxf/core/entity.hpp" +#include "gxf/core/handle.hpp" +#include "gxf/std/transmitter.hpp" + +namespace nvidia { +namespace gxf { + +/** + * @brief A transmitter which uses a Simpson's four-slot buffer to enable lockless and asynchronous + * communication. This transmitter is designed to be used in a single producer and single consumer + * scenario. + * + */ +class AsyncBufferTransmitter : public Transmitter { + public: + gxf_result_t initialize() override; + + gxf_result_t pop_abi(gxf_uid_t* uid) override; + + gxf_result_t pop_io_abi(gxf_uid_t* uid) override; + + gxf_result_t push_abi(gxf_uid_t other) override; + + gxf_result_t peek_abi(gxf_uid_t* uid, int32_t index) override; + + size_t capacity_abi() override; + + size_t size_abi() override; + + gxf_result_t publish_abi(gxf_uid_t uid) override; + + size_t back_size_abi() override; + + gxf_result_t sync_abi() override; + + gxf_result_t sync_io_abi() override; + + private: + Entity entity_; + int size_; +}; + +} // namespace gxf +} // namespace nvidia + +#endif /* NVIDIA_GXF_STD_ASYNC_BUFFER_TRANSMITTER_HPP_ */ diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/codelet.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/codelet.hpp index 308b091..970004c 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/std/codelet.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/codelet.hpp @@ -82,15 +82,15 @@ class Codelet : public Component { void beforeStop(); // The number of times the codelet tick function was called. - int64_t execution_count_; + int64_t execution_count_{0}; // The timestamp of the previous execution. Equal to 'execution_timestamp' during 'start'. - int64_t previous_execution_timestamp_; + int64_t previous_execution_timestamp_{0}; // The timestamp of the current execution in nanoseconds. int64_t execution_timestamp_; // Same as execution_timestamp_ but in seconds and as a floating point. double execution_time_; // The difference between the current and the previous execution time in seconds. - double delta_time_; + double delta_time_{0.0}; }; } // namespace gxf diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/gems/suballocators/first_fit_allocator.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/gems/suballocators/first_fit_allocator.hpp index b732c1d..418c9da 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/std/gems/suballocators/first_fit_allocator.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/gems/suballocators/first_fit_allocator.hpp @@ -110,7 +110,7 @@ class FirstFitAllocator { // the requested size. int32_t chunk_size_; // Buffer holding the pre-allocated memory that is provided on demand. - std::unique_ptr buffer_; + std::unique_ptr buffer_{nullptr}; }; } // namespace gxf diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/memory_buffer.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/memory_buffer.hpp index fcc2044..f6339be 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/std/memory_buffer.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/memory_buffer.hpp @@ -64,7 +64,7 @@ class MemoryBuffer { return Success; } - ~MemoryBuffer() { freeBuffer(); } + virtual ~MemoryBuffer() { freeBuffer(); } Expected resize(Handle allocator, uint64_t size, MemoryStorageType storage_type) { @@ -121,7 +121,7 @@ class MemoryBuffer { // Size of buffer contents in bytes uint64_t size() const { return size_; } - private: + protected: uint64_t size_ = 0; byte* pointer_ = nullptr; MemoryStorageType storage_type_ = MemoryStorageType::kHost; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/scheduler.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/scheduler.hpp index 98eb4a2..bee3e8b 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/std/scheduler.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/scheduler.hpp @@ -27,7 +27,9 @@ namespace gxf { class EntityExecutor; // forward declaration -// A simple poll-based single-threaded scheduler which executes codelets. +// An interface which extends the nvidia::gxf::System interface to create schedulers +// which can execute codelets. + class Scheduler : public System { public: virtual gxf_result_t prepare_abi(EntityExecutor* executor) = 0; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/scheduling_term_combiner.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/scheduling_term_combiner.hpp new file mode 100644 index 0000000..7aa6edc --- /dev/null +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/scheduling_term_combiner.hpp @@ -0,0 +1,108 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 +#ifndef NVIDIA_GXF_STD_SCHEDULING_TERM_COMBINER_HPP +#define NVIDIA_GXF_STD_SCHEDULING_TERM_COMBINER_HPP + +#include + +#include + +#include "gxf/std/scheduling_term.hpp" + +namespace nvidia { +namespace gxf { + +/** + * @brief Base class for scheduling term combiner + * + * scheduling term combiners can be used to create complex execution patterns by interpreting + * combinations of scheduling terms differently + */ +class SchedulingTermCombiner : public Component { + public: + // Function to combine two SchedulingCondition types + virtual SchedulingCondition combine(SchedulingCondition a, SchedulingCondition b) = 0; + + // Get the list of scheduling terms in an entity being governed by the combiner + virtual FixedVector, kMaxComponents> getTermList() const = 0; +}; + +/** + * @brief OR combiners simulate the bitwise OR operation when combining scheduling conditions + * + */ +class OrSchedulingTermCombiner : public SchedulingTermCombiner { + public: + gxf_result_t registerInterface(Registrar* registrar) override { + Expected result; + result &= registrar->parameter(terms_, "terms", "SchedulingTerms", + "The list of scheduling terms to be combined using OR operation"); + return GXF_SUCCESS; + } + + SchedulingCondition combine(SchedulingCondition a, SchedulingCondition b) override { + // "never" has the highest significance + if (a.type == SchedulingConditionType::NEVER || b.type == SchedulingConditionType::NEVER) { + return {SchedulingConditionType::NEVER, 0}; + } + + // If both are ready, choose the max target timestamp + if (a.type == SchedulingConditionType::READY && b.type == SchedulingConditionType::READY) { + return {SchedulingConditionType::READY, std::max(a.target_timestamp, b.target_timestamp)}; + } + + // Check if either one of them is ready + if (a.type == SchedulingConditionType::READY) { + return {SchedulingConditionType::READY, a.target_timestamp}; + } else if (b.type == SchedulingConditionType::READY) { + return {SchedulingConditionType::READY, b.target_timestamp}; + } + + // "wait event" has the third highest significance + if (a.type == SchedulingConditionType::WAIT_EVENT || + b.type == SchedulingConditionType::WAIT_EVENT) { + return {SchedulingConditionType::WAIT_EVENT, 0}; + } + + // "wait time" events are combined so that the maximum time is returned + if (a.type == SchedulingConditionType::WAIT_TIME && + b.type == SchedulingConditionType::WAIT_TIME) { + return {SchedulingConditionType::WAIT_TIME, std::max(a.target_timestamp, b.target_timestamp)}; + } + + // Check if atleast one of them have a target time + if (a.type == SchedulingConditionType::WAIT_TIME) { + return a; + } else if (b.type == SchedulingConditionType::WAIT_TIME) { + return b; + } + + // The only remaining case is that both are wait + return {SchedulingConditionType::WAIT, 0}; + } + +FixedVector, kMaxComponents> getTermList() const { + return terms_; +} + +Parameter, kMaxComponents>> terms_; +}; + +} // namespace gxf +} // namespace nvidia + +#endif // NVIDIA_GXF_STD_SCHEDULING_TERM_COMBINER_HPP diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/scheduling_terms.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/scheduling_terms.hpp index 44e9df6..c93d6b1 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/std/scheduling_terms.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/scheduling_terms.hpp @@ -121,7 +121,7 @@ class PeriodicSchedulingTerm : public SchedulingTerm { Parameter recess_period_; Parameter policy_; - int64_t recess_period_ns_; + int64_t recess_period_ns_ = 0; Expected next_target_ = Unexpected{GXF_UNINITIALIZED_VALUE}; }; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/std/tensor.hpp b/isaac_ros_gxf/gxf/core/include/gxf/std/tensor.hpp index 6ee0c3e..f7ea245 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/std/tensor.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/std/tensor.hpp @@ -16,6 +16,8 @@ // SPDX-License-Identifier: Apache-2.0 #pragma once +#include + #include #include #include @@ -50,6 +52,7 @@ enum class PrimitiveType : int32_t { kFloat64, kComplex64, kComplex128, + kFloat16, }; // Returns the size of each element of specific PrimitiveType as number of bytes. @@ -73,6 +76,7 @@ GXF_PRIMITIVE_TYPE_TRAITS(int32_t, kInt32); GXF_PRIMITIVE_TYPE_TRAITS(uint32_t, kUnsigned32); GXF_PRIMITIVE_TYPE_TRAITS(int64_t, kInt64); GXF_PRIMITIVE_TYPE_TRAITS(uint64_t, kUnsigned64); +GXF_PRIMITIVE_TYPE_TRAITS(__half, kFloat16); GXF_PRIMITIVE_TYPE_TRAITS(float, kFloat32); GXF_PRIMITIVE_TYPE_TRAITS(double, kFloat64); GXF_PRIMITIVE_TYPE_TRAITS(complex64, kComplex64); diff --git a/isaac_ros_gxf/gxf/core/include/gxf/stream/tests/test_gxf_stream_sync_cuda_helper.hpp b/isaac_ros_gxf/gxf/core/include/gxf/stream/tests/test_gxf_stream_sync_cuda_helper.hpp index f662ebb..204df41 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/stream/tests/test_gxf_stream_sync_cuda_helper.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/stream/tests/test_gxf_stream_sync_cuda_helper.hpp @@ -25,6 +25,7 @@ #include "common/assert.hpp" #include "gxf/cuda/cuda_common.hpp" +#include "gxf/cuda/cuda_stream.hpp" #include "gxf/cuda/cuda_stream_id.hpp" #include "gxf/cuda/cuda_stream_pool.hpp" #include "gxf/std/allocator.hpp" @@ -125,8 +126,6 @@ class StreamTensorGeneratorNew : public StreamBasedOpsNew { stream_sync = stream_sync_.get(); - GXF_ASSERT_SUCCESS(stream_sync->initialize()); - void *syncObj{nullptr}; GXF_ASSERT_SUCCESS(stream_sync->allocate_sync_object(static_cast(signaler_.get()), static_cast(waiter_.get()), @@ -270,7 +269,7 @@ class DotProductExeNew { GXF_ASSERT(rx_ && tx_ && tensor_pool_, "dotproduct received empty in_msg"); // get tensors - auto in_tensors = in_msg.findAll(); + auto in_tensors = in_msg.findAllHeap(); GXF_ASSERT(in_tensors, "failed to find Tensors in in_msg"); GXF_ASSERT(in_tensors->size() == 2, "doesn't find Tensors in in_msg"); GXF_ASSERT(in_tensors->at(0).value()->rank() == 2, "Input tensor rank is not 2"); diff --git a/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_context.hpp b/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_context.hpp index 355dd3b..4144f10 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_context.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_context.hpp @@ -41,7 +41,7 @@ typedef struct ucx_server_ctx { volatile ucp_conn_request_h conn_request; ucp_listener_h listener; ucp_worker_h listener_worker; - int listener_fd; + int listener_fd; ///< epoll fd used only when enable_async_ == true } ucx_server_ctx_t; @@ -54,7 +54,7 @@ typedef struct UcxReceiverContext { ucx_am_data_desc am_data_desc; FixedVector, kMaxRxContexts> headers; ucp_worker_h ucp_worker; - int worker_fd; + int worker_fd; ///< epoll fd used only when enable_async_ == true int index; } UcxReceiverContext_; @@ -86,14 +86,21 @@ class UcxContext : public NetworkContext { gxf_result_t init_context(); gxf_result_t init_tx(Handle tx); gxf_result_t init_rx(Handle rx); + + /// @brief start server for the case with enable_async_ == false void start_server(); - void poll_queue(); + gxf_result_t am_desc_to_iov(std::shared_ptr rx_context); void destroy_rx_contexts(); void destroy_tx_contexts(); + // The remaining methods are specific to the case with enable_async_ == true - gxf_result_t wait_for_event(); + /// @brief start server for the case with enable_async_ == true + void start_server_async_queue(); + /// @brief method run by tx_thread_ when enable_async_ == true + void poll_queue(); + gxf_result_t wait_for_event(); ///< primary function called by start_server_async_queue gxf_result_t epoll_add_worker(std::shared_ptr rx_context, bool is_listener); gxf_result_t progress_work(std::shared_ptr rx_context); @@ -104,23 +111,27 @@ class UcxContext : public NetworkContext { bool is_listener); void copy_header_to_am_desc(std::shared_ptr rx_context); - ConnManager rx_conns_ = {0}; - bool close_server_loop_; FixedVector, kMaxRxContexts> rx_contexts_; FixedVector, kMaxRxContexts> tx_contexts_; ucp_context_h ucp_context_; - std::thread rx_thread_; - std::thread tx_thread_; Parameter> entity_serializer_; Parameter reconnect_; Resource> gpu_device_; + Parameter cpu_data_only_; + Parameter enable_async_; int32_t dev_id_ = 0; + + std::thread t_; ///< server thread used only when enable_async_ == false + + // The following data members are only used when enable_async_ == true + ConnManager rx_conns_ = {0}; + std::thread rx_thread_; ///< async receiver thread used only when enable_async_ == true + std::thread tx_thread_; ///< async transmitter thread used only when enable_async_ == true std::list pending_send_requests_; std::mutex mtx_; std::condition_variable cv_; bool areTransmittersDone = false; - int msg_id_ = 0; int epoll_fd_; int efd_signal_; }; diff --git a/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_entity_serializer.hpp b/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_entity_serializer.hpp index 3e1fa37..0de52d6 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_entity_serializer.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_entity_serializer.hpp @@ -22,6 +22,7 @@ #include #include "common/fixed_vector.hpp" +#include "gxf/core/gxf.h" #include "gxf/serialization/component_serializer.hpp" #include "gxf/serialization/entity_serializer.hpp" #include "gxf/serialization/tid_hash.hpp" @@ -56,7 +57,7 @@ class UcxEntitySerializer : public EntitySerializer { struct ComponentHeader { uint64_t serialized_size; // Size of the serialized component in bytes gxf_tid_t tid; // Type ID of the component - char name[256]; // Component name + char name[kMaxComponentNameSize]; // Component name }; #pragma pack(pop) @@ -97,9 +98,9 @@ class UcxEntitySerializer : public EntitySerializer { // Table that caches type ID with a valid component serializer std::unordered_map, TidHash> serializer_cache_; // Sequence number for outgoing messages - uint64_t outgoing_sequence_number_ = 0; + uint64_t outgoing_sequence_number_{0}; // Sequence number for incoming messages - uint64_t incoming_sequence_number_ = 0; + uint64_t incoming_sequence_number_{0}; }; } // namespace gxf diff --git a/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_receiver.hpp b/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_receiver.hpp index df51a53..d974541 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_receiver.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_receiver.hpp @@ -48,7 +48,8 @@ class UcxReceiver : public Receiver { gxf_result_t initialize() override; gxf_result_t deinitialize() override; gxf_result_t init_context(ucp_worker_h ucp_worker, - ucx_am_data_desc* am_data_desc, int fd); + ucx_am_data_desc* am_data_desc, int fd, + bool cpu_data_only, bool enable_async); gxf_result_t pop_abi(gxf_uid_t* uid) override; @@ -89,12 +90,18 @@ class UcxReceiver : public Receiver { private: gxf_result_t receive_message(); + /// @brief finalize request when enable_async_ == false + gxf_result_t request_finalize_sync(ucp_worker_h ucp_worker, test_req_t* request, + test_req_t* ctx); + ucp_worker_h ucp_worker_; ucx_am_data_desc* am_data_desc_; std::unique_ptr queue_; int32_t dev_id_ = 0; int efd_signal_; + bool cpu_data_only_ = false; std::list> requests; + int enable_async_ = true; }; } // namespace gxf diff --git a/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_transmitter.hpp b/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_transmitter.hpp index 1ab4eee..9a043c1 100644 --- a/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_transmitter.hpp +++ b/isaac_ros_gxf/gxf/core/include/gxf/ucx/ucx_transmitter.hpp @@ -49,6 +49,8 @@ class UcxTransmitter : public Transmitter { ucp_ep_h* ep, bool* connection_closed_p, bool reconnect, + bool cpu_data_only, + bool enable_async, std::list* send_queue, std::condition_variable* cv, std::mutex* mtx); @@ -107,11 +109,13 @@ class UcxTransmitter : public Transmitter { std::unique_ptr queue_; bool* connection_closed_p_; bool reconnect_; + bool cpu_data_only_; std::list* send_queue_; std::condition_variable* cv_; std::mutex* mtx_; int index = 0; int* id_; + int enable_async_ = true; }; } // namespace gxf diff --git a/isaac_ros_gxf/gxf/core/include/third_party/LICENSE.txt b/isaac_ros_gxf/gxf/core/include/third_party/LICENSE.txt index c652da9..22c3637 100644 --- a/isaac_ros_gxf/gxf/core/include/third_party/LICENSE.txt +++ b/isaac_ros_gxf/gxf/core/include/third_party/LICENSE.txt @@ -7242,3 +7242,1125 @@ available from http://www.cs.virginia.edu/stream/ =============================================================================== + +GitPython (Provided under following license) +=============================================================================== + +Copyright (C) 2008, 2009 Michael Trier and contributors +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions +are met: + +* Redistributions of source code must retain the above copyright +notice, this list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright +notice, this list of conditions and the following disclaimer in the +documentation and/or other materials provided with the distribution. + +* Neither the name of the GitPython project nor the names of +its contributors may be used to endorse or promote products derived +from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED +TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +=============================================================================== + +RAPIDS Memory Manager (RMM) (Provided under following license) +=============================================================================== + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + +=============================================================================== + +spdlog (Provided under following license) +=============================================================================== + +The MIT License (MIT) + +Copyright (c) 2016 Gabi Melman. + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. + +-- NOTE: Third party dependency used by this software -- +This software depends on the fmt lib (MIT License), +and users must comply to its license: https://raw.githubusercontent.com/fmtlib/fmt/master/LICENSE + +=============================================================================== + +fmt (Provided under following license) +=============================================================================== + +Copyright (c) 2012 - present, Victor Zverovich and {fmt} contributors + +Permission is hereby granted, free of charge, to any person obtaining +a copy of this software and associated documentation files (the +"Software"), to deal in the Software without restriction, including +without limitation the rights to use, copy, modify, merge, publish, +distribute, sublicense, and/or sell copies of the Software, and to +permit persons to whom the Software is furnished to do so, subject to +the following conditions: + +The above copyright notice and this permission notice shall be +included in all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND +NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE +LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION +OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION +WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + +--- Optional exception to the license --- + +As an exception, if, as a result of your compiling your source code, portions +of this Software are embedded into a machine-executable object form of such +source code, you may redistribute such embedded portions in such object form +without including the above copyright and permission notices. + +=============================================================================== + +yq (Provided under following license) +=============================================================================== +Apache License +Version 2.0, January 2004 +http://www.apache.org/licenses/ + +TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + +1. Definitions. + +"License" shall mean the terms and conditions for use, reproduction, and +distribution as defined by Sections 1 through 9 of this document. + +"Licensor" shall mean the copyright owner or entity authorized by the copyright +owner that is granting the License. + +"Legal Entity" shall mean the union of the acting entity and all other entities +that control, are controlled by, or are under common control with that entity. +For the purposes of this definition, "control" means (i) the power, direct or +indirect, to cause the direction or management of such entity, whether by +contract or otherwise, or (ii) ownership of fifty percent (50%) or more of the +outstanding shares, or (iii) beneficial ownership of such entity. + +"You" (or "Your") shall mean an individual or Legal Entity exercising +permissions granted by this License. + +"Source" form shall mean the preferred form for making modifications, including +but not limited to software source code, documentation source, and configuration +files. + +"Object" form shall mean any form resulting from mechanical transformation or +translation of a Source form, including but not limited to compiled object code, +generated documentation, and conversions to other media types. + +"Work" shall mean the work of authorship, whether in Source or Object form, made +available under the License, as indicated by a copyright notice that is included +in or attached to the work (an example is provided in the Appendix below). + +"Derivative Works" shall mean any work, whether in Source or Object form, that +is based on (or derived from) the Work and for which the editorial revisions, +annotations, elaborations, or other modifications represent, as a whole, an +original work of authorship. For the purposes of this License, Derivative Works +shall not include works that remain separable from, or merely link (or bind by +name) to the interfaces of, the Work and Derivative Works thereof. + +"Contribution" shall mean any work of authorship, including the original version +of the Work and any modifications or additions to that Work or Derivative Works +thereof, that is intentionally submitted to Licensor for inclusion in the Work +by the copyright owner or by an individual or Legal Entity authorized to submit +on behalf of the copyright owner. For the purposes of this definition, +"submitted" means any form of electronic, verbal, or written communication sent +to the Licensor or its representatives, including but not limited to +communication on electronic mailing lists, source code control systems, and +issue tracking systems that are managed by, or on behalf of, the Licensor for +the purpose of discussing and improving the Work, but excluding communication +that is conspicuously marked or otherwise designated in writing by the copyright +owner as "Not a Contribution." + +"Contributor" shall mean Licensor and any individual or Legal Entity on behalf +of whom a Contribution has been received by Licensor and subsequently +incorporated within the Work. + +2. Grant of Copyright License. + +Subject to the terms and conditions of this License, each Contributor hereby +grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, +irrevocable copyright license to reproduce, prepare Derivative Works of, +publicly display, publicly perform, sublicense, and distribute the Work and such +Derivative Works in Source or Object form. + +3. Grant of Patent License. + +Subject to the terms and conditions of this License, each Contributor hereby +grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, +irrevocable (except as stated in this section) patent license to make, have +made, use, offer to sell, sell, import, and otherwise transfer the Work, where +such license applies only to those patent claims licensable by such Contributor +that are necessarily infringed by their Contribution(s) alone or by combination +of their Contribution(s) with the Work to which such Contribution(s) was +submitted. If You institute patent litigation against any entity (including a +cross-claim or counterclaim in a lawsuit) alleging that the Work or a +Contribution incorporated within the Work constitutes direct or contributory +patent infringement, then any patent licenses granted to You under this License +for that Work shall terminate as of the date such litigation is filed. + +4. Redistribution. + +You may reproduce and distribute copies of the Work or Derivative Works thereof +in any medium, with or without modifications, and in Source or Object form, +provided that You meet the following conditions: + +You must give any other recipients of the Work or Derivative Works a copy of +this License; and +You must cause any modified files to carry prominent notices stating that You +changed the files; and +You must retain, in the Source form of any Derivative Works that You distribute, +all copyright, patent, trademark, and attribution notices from the Source form +of the Work, excluding those notices that do not pertain to any part of the +Derivative Works; and +If the Work includes a "NOTICE" text file as part of its distribution, then any +Derivative Works that You distribute must include a readable copy of the +attribution notices contained within such NOTICE file, excluding those notices +that do not pertain to any part of the Derivative Works, in at least one of the +following places: within a NOTICE text file distributed as part of the +Derivative Works; within the Source form or documentation, if provided along +with the Derivative Works; or, within a display generated by the Derivative +Works, if and wherever such third-party notices normally appear. The contents of +the NOTICE file are for informational purposes only and do not modify the +License. You may add Your own attribution notices within Derivative Works that +You distribute, alongside or as an addendum to the NOTICE text from the Work, +provided that such additional attribution notices cannot be construed as +modifying the License. +You may add Your own copyright statement to Your modifications and may provide +additional or different license terms and conditions for use, reproduction, or +distribution of Your modifications, or for any such Derivative Works as a whole, +provided Your use, reproduction, and distribution of the Work otherwise complies +with the conditions stated in this License. + +5. Submission of Contributions. + +Unless You explicitly state otherwise, any Contribution intentionally submitted +for inclusion in the Work by You to the Licensor shall be under the terms and +conditions of this License, without any additional terms or conditions. +Notwithstanding the above, nothing herein shall supersede or modify the terms of +any separate license agreement you may have executed with Licensor regarding +such Contributions. + +6. Trademarks. + +This License does not grant permission to use the trade names, trademarks, +service marks, or product names of the Licensor, except as required for +reasonable and customary use in describing the origin of the Work and +reproducing the content of the NOTICE file. + +7. Disclaimer of Warranty. + +Unless required by applicable law or agreed to in writing, Licensor provides the +Work (and each Contributor provides its Contributions) on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied, +including, without limitation, any warranties or conditions of TITLE, +NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A PARTICULAR PURPOSE. You are +solely responsible for determining the appropriateness of using or +redistributing the Work and assume any risks associated with Your exercise of +permissions under this License. + +8. Limitation of Liability. + +In no event and under no legal theory, whether in tort (including negligence), +contract, or otherwise, unless required by applicable law (such as deliberate +and grossly negligent acts) or agreed to in writing, shall any Contributor be +liable to You for damages, including any direct, indirect, special, incidental, +or consequential damages of any character arising as a result of this License or +out of the use or inability to use the Work (including but not limited to +damages for loss of goodwill, work stoppage, computer failure or malfunction, or +any and all other commercial damages or losses), even if such Contributor has +been advised of the possibility of such damages. + +9. Accepting Warranty or Additional Liability. + +While redistributing the Work or Derivative Works thereof, You may choose to +offer, and charge a fee for, acceptance of support, warranty, indemnity, or +other liability obligations and/or rights consistent with this License. However, +in accepting such obligations, You may act only on Your own behalf and on Your +sole responsibility, not on behalf of any other Contributor, and only if You +agree to indemnify, defend, and hold each Contributor harmless for any liability +incurred by, or claims asserted against, such Contributor by reason of your +accepting any such warranty or additional liability. + +END OF TERMS AND CONDITIONS + +APPENDIX: How to apply the Apache License to your work + +To apply the Apache License to your work, attach the following boilerplate +notice, with the fields enclosed by brackets "[]" replaced with your own +identifying information. (Don't include the brackets!) The text should be +enclosed in the appropriate comment syntax for the file format. We also +recommend that a file or class name and description of purpose be included on +the same "printed page" as the copyright notice for easier identification within +third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +=============================================================================== + +bazelbuild/bazel-gazelle 0.24.0 (Provided under following license) +=============================================================================== + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + +=============================================================================== + +bazelbuild/rules_go 0.24.2 (Provided under following license) +=============================================================================== + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + +=============================================================================== + +bazelbuild/rules_docker 0.22.0 (Provided under following license) +=============================================================================== + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "{}" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright {yyyy} {name of copyright owner} + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. + +=============================================================================== diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/behavior_tree/libgxf_behavior_tree.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/behavior_tree/libgxf_behavior_tree.so deleted file mode 100755 index 0becc31..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/behavior_tree/libgxf_behavior_tree.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:834c3a79f7ca5c9dbbc724d8d7f135217d5f2247aa7d8169a4ed7b7ae5484bc0 -size 3728656 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/core/core_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/core/core_pybind.so deleted file mode 100755 index 5a75a65..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/core/core_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:6743a3210ba8d3010a04dbfade87eac23c8d0bf362200c444be4ba968e3b6e3b -size 4125360 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/core/libgxf_core.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/core/libgxf_core.so deleted file mode 100755 index b527ad9..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/core/libgxf_core.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:e61c3bd6995d62c921d7f58d25f6bdb0fc07b58a411522a95b40e64205e8724c -size 2376696 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/cuda_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/cuda_pybind.so deleted file mode 100755 index 29258ae..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/cuda_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:b43c507ba5a247d400c9dc4145600c1a3c1a6179627d95a8593cbe5138bf9c1f -size 2841128 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/libgxf_cuda.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/libgxf_cuda.so deleted file mode 100755 index b59fb96..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/libgxf_cuda.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1886a98cfa7b935a4c2c7b2d519a1291767644ffe76cc9d3af623df2970239f6 -size 2675888 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/tests/libgxf_test_cuda.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/tests/libgxf_test_cuda.so deleted file mode 100755 index 3b81c7f..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/cuda/tests/libgxf_test_cuda.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:e6a58a5de54c5096e92f55c4e0328a2f74a4a6a9bfb8e23295bf31b827ca1a45 -size 3724488 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/ipc/grpc/libgxf_grpc.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/ipc/grpc/libgxf_grpc.so deleted file mode 100755 index e3e497c..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/ipc/grpc/libgxf_grpc.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:fc28195fa9edc064427e0386a2ba3def853d55fa87265984581c821b9abd76bf -size 17615912 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/ipc/http/libgxf_http.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/ipc/http/libgxf_http.so deleted file mode 100755 index c8b4829..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/ipc/http/libgxf_http.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:5170f10fb20fcfb7a578ed3b8f3ca956c1de174513abbc7fc2fd62bf6478984b -size 9114240 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/multimedia/libgxf_multimedia.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/multimedia/libgxf_multimedia.so deleted file mode 100755 index 161f659..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/multimedia/libgxf_multimedia.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:b7bed8cdc7d22c94d8868205ba7a285fd1f160a6a23da6d73b5897aecbee9be3 -size 2605008 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/network/libgxf_network.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/network/libgxf_network.so deleted file mode 100755 index e46ea00..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/network/libgxf_network.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:127da8835cce9984cf6dd44efef9eb650b1d4ef2c1274da1f892614a8f438afb -size 2768136 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/npp/libgxf_npp.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/npp/libgxf_npp.so deleted file mode 100755 index 759b2c2..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/npp/libgxf_npp.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:8a19dc1e976e183701db75ffe5fb870085ed5c268346543126852b7970e9f32e -size 3565120 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/python_codelet/libgxf_python_codelet.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/python_codelet/libgxf_python_codelet.so deleted file mode 100755 index 7e3f4ae..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/python_codelet/libgxf_python_codelet.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:ce472478d8c1b1060d736b1de532b88574e7346d1db195870a782998190b7479 -size 3728976 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/python_codelet/pycodelet.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/python_codelet/pycodelet.so deleted file mode 100755 index 21d8b38..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/python_codelet/pycodelet.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:5d509e19370ac167f4a05e1b2999ed3b36109aee73b4be5d0143e211329b9126 -size 3735936 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/sample/libgxf_sample.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/sample/libgxf_sample.so deleted file mode 100755 index 76be829..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/sample/libgxf_sample.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:5425daaf1ae11373c42cd860435b80ad1bd2f8d81d9ae1be890be37ecb71a371 -size 2668072 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/serialization/libgxf_serialization.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/serialization/libgxf_serialization.so deleted file mode 100755 index e938f46..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/serialization/libgxf_serialization.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:2b0407f671a3b63691e7e8c2925d560da08255d6985feae8bff9bbcf313d8b05 -size 3895616 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/allocator_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/allocator_pybind.so deleted file mode 100755 index 7b67612..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/allocator_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:d133932e3a8ac99e4813f4ec2d09456f906d1ecef0e16cb6ab49c280c9aa6f9a -size 3657304 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/clock_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/clock_pybind.so deleted file mode 100755 index 8df96c2..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/clock_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:28409e64b893ab47f4350a3e78d75e3dec3207e4c3c48a1fcfda2ffdcf6421a4 -size 3659328 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/libgxf_std.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/libgxf_std.so deleted file mode 100755 index c3b5153..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/libgxf_std.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:bb789125ac64f83b387a17fd2e64c49b1f764ae96865df52e942b82127681a85 -size 3918328 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/receiver_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/receiver_pybind.so deleted file mode 100755 index f26a44f..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/receiver_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:165ebff39f6af6479a39c360e1ddd163777fdb2923c519adbd130c332d324de0 -size 3658024 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/tensor_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/tensor_pybind.so deleted file mode 100755 index d23e25f..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/tensor_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:9696dfc7f524bc4fc3fe09997d250607e6a6bfba0d04c5393c2401d162b577e1 -size 3955152 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/timestamp_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/timestamp_pybind.so deleted file mode 100755 index dfb60cf..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/timestamp_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:00304f01900e01de2e278d5921438feda2823ea3830a13fc2b91c55b0b87c535 -size 3645648 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/transmitter_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/transmitter_pybind.so deleted file mode 100755 index 36822e4..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/transmitter_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:4ed2411c2b5a146aca25aa435e0cea82c05e743ab2577ea468443596efb6fbda -size 3657976 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/vault_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/vault_pybind.so deleted file mode 100755 index d91d151..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/std/vault_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:a16fcf68368320e0bc1ec16c8f3d55d65ccbbb4b8d1c2a388ae3378ffc6db758 -size 3646760 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/test/extensions/libgxf_test.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/test/extensions/libgxf_test.so deleted file mode 100755 index 67ecf4e..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/test/extensions/libgxf_test.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:94568002eb393a4ee83b1333cb0cd61ff545a8340d0e1f079e5c41d42d70811d -size 5474256 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/behavior_tree/libgxf_behavior_tree.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/behavior_tree/libgxf_behavior_tree.so new file mode 100755 index 0000000..bfbefcf --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/behavior_tree/libgxf_behavior_tree.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8f0670c636a54e96ff301a8563e7241cbde0408ce229e37b3f7480639ee0655f +size 3805976 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/core/core_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/core/core_pybind.so new file mode 100755 index 0000000..a6e78fa --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/core/core_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9a3952c422c70673802a815e9fc7c76edae8a9c7f6670ac6ace021d64f4cd185 +size 4139448 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/core/libgxf_core.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/core/libgxf_core.so new file mode 100755 index 0000000..f6cd072 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/core/libgxf_core.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e58c775e7911a70003c709c6402737a1c197ad987dcac52c0e9c81506f5d45c2 +size 2449368 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/cuda_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/cuda_pybind.so new file mode 100755 index 0000000..e79d295 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/cuda_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a3925bf327a6f3ff7cab981db30e331505d2399c71ba8b7a81f2282acd98d6f0 +size 2924840 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/libgxf_cuda.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/libgxf_cuda.so new file mode 100755 index 0000000..9b1bc12 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/libgxf_cuda.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5543719af0277f747d8717e5a97a0d5ad06f15d1187bdcb68aea22d9f8392e9e +size 2833240 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/tests/libgxf_test_cuda.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/tests/libgxf_test_cuda.so new file mode 100755 index 0000000..a8ecc04 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/cuda/tests/libgxf_test_cuda.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f72c2b3f4a780f4a797836b98f6f12bff70837e10204573a75f51a20ee70edb1 +size 3894576 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/ipc/grpc/libgxf_grpc.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/ipc/grpc/libgxf_grpc.so new file mode 100755 index 0000000..ea4f764 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/ipc/grpc/libgxf_grpc.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:0961933aa2549bea24deb69d739b838e4e51839522dd5a75da73af1f4ba92942 +size 14685216 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/ipc/http/libgxf_http.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/ipc/http/libgxf_http.so new file mode 100755 index 0000000..c7eae92 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/ipc/http/libgxf_http.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:52acfda8fc27cf8def234135f923adcdf357f3c6de5fdf6ba5adb268dadb61c1 +size 8436024 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/logger/libgxf_logger.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/logger/libgxf_logger.so similarity index 100% rename from isaac_ros_gxf/gxf/core/lib/gxf_jetpack60/logger/libgxf_logger.so rename to isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/logger/libgxf_logger.so diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/multimedia/libgxf_multimedia.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/multimedia/libgxf_multimedia.so new file mode 100755 index 0000000..b5887aa --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/multimedia/libgxf_multimedia.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:99bf2a85731ddd21286eace12dfc34befabc4de5a708382fe4a9b5abc17f304f +size 2677528 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/network/libgxf_network.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/network/libgxf_network.so new file mode 100755 index 0000000..c2b27bb --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/network/libgxf_network.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:21e8f73f45f6d6d1f75d35a7d71f779aebf32b2611041ce0c7f240ece49140c1 +size 2775576 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/npp/libgxf_npp.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/npp/libgxf_npp.so new file mode 100755 index 0000000..1d15332 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/npp/libgxf_npp.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8df8e774748e846d20f5de722461cc39a680ec12d178cfa2c6166ae1b548b64a +size 3577248 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/python_codelet/libgxf_python_codelet.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/python_codelet/libgxf_python_codelet.so new file mode 100755 index 0000000..5270dab --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/python_codelet/libgxf_python_codelet.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:2512030aa1f2bf08288424ff24aaefb13a0857f254b5cf51f44681a0ac8a1d8a +size 3809480 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/python_codelet/pycodelet.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/python_codelet/pycodelet.so new file mode 100755 index 0000000..e2b9b3d --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/python_codelet/pycodelet.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:813a8a62165357a3b115b3f332727605dc25fb96d29f5d8bc34e3813625a01de +size 3814576 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/sample/libgxf_sample.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/sample/libgxf_sample.so new file mode 100755 index 0000000..f1ecdf6 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/sample/libgxf_sample.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d9307da1b2f9c6dbbe2c552db3325f910d197b1bb2c491366206324fa2e7c9a8 +size 2747488 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/serialization/libgxf_serialization.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/serialization/libgxf_serialization.so new file mode 100755 index 0000000..be18bfc --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/serialization/libgxf_serialization.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:792226015449aaba7e6a16e76f3744ae0e5265a109c9541db4af035589f2fa68 +size 3908120 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/allocator_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/allocator_pybind.so new file mode 100755 index 0000000..b34c47f --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/allocator_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b229c67ebc9ad83b8fdd9483d7b3e8b814cdf487246d478a791726ff2732d599 +size 3735248 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/clock_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/clock_pybind.so new file mode 100755 index 0000000..a100d91 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/clock_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b5cbbd049b11acb8761420f8e3fa2b2a9f312f7bdc23a7be823f8beb83de15ea +size 3737192 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/libgxf_std.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/libgxf_std.so new file mode 100755 index 0000000..f6e1b62 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/libgxf_std.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:418e7016d5d9d3acdc919593dbf511bda6ab8f898617d020d85ddc404013e297 +size 4008040 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/receiver_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/receiver_pybind.so new file mode 100755 index 0000000..24ee5d2 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/receiver_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8e876700783ef1ec1e7ea50ee584e8fd9af6073694059b2def7818fdc2ea1289 +size 3735968 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/tensor_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/tensor_pybind.so new file mode 100755 index 0000000..3ebe0d6 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/tensor_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ce49b1c898e6de9e34e44d7fda7380d641b6f0802e1d98ba9827b4c6a627dd20 +size 4033848 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/timestamp_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/timestamp_pybind.so new file mode 100755 index 0000000..8617f12 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/timestamp_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:60a8656eb71918319f4b9830e7fc4f839d12a66d930f74afcb876dd68ec901d6 +size 3735712 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/transmitter_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/transmitter_pybind.so new file mode 100755 index 0000000..391bfd1 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/transmitter_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:0bc8d8e781b01578f3edd515efb76098fb1c1c662c01f0a421c2f4a5d4d42ab4 +size 3735920 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/vault_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/vault_pybind.so new file mode 100755 index 0000000..ebea1de --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/std/vault_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:841a22c17fb0499320558d5d010b7584de7f94b6c5db066d7c256a8eeccaeb78 +size 3659152 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/test/extensions/libgxf_test.so b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/test/extensions/libgxf_test.so new file mode 100755 index 0000000..0e0bfae --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_jetpack61/test/extensions/libgxf_test.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5a4190619a68fbb49eca91ec85e7dba63b2a822d9977057c03e261da58e29aba +size 4989688 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/behavior_tree/libgxf_behavior_tree.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/behavior_tree/libgxf_behavior_tree.so deleted file mode 100755 index 246eacd..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/behavior_tree/libgxf_behavior_tree.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:7bef246f7391073798c4c88ad91ba13f3f3fb136ca63769ab0cf837e723f2124 -size 3982848 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/core/core_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/core/core_pybind.so deleted file mode 100755 index 209003d..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/core/core_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:32e9c0939ec8c98352f101c0a9f62a638b8d46a9911f4874cd8c7976a6778279 -size 4371680 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/core/libgxf_core.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/core/libgxf_core.so deleted file mode 100755 index 56ff855..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/core/libgxf_core.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:08315be2cfc59f5764b999fb5fce9c24e8328241456d5510f2000998dd5de9f7 -size 2504568 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/cuda_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/cuda_pybind.so deleted file mode 100755 index 4189594..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/cuda_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:668f903b1e08bf7d324a6ac6095394723eed2e830f1a72c020776e187571dc95 -size 2964008 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/libgxf_cuda.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/libgxf_cuda.so deleted file mode 100755 index 0c42859..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/libgxf_cuda.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:686589616dc9173e16f0dbbcf6e7476cc51056a5f4da384b876a253dc64295e0 -size 2818600 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/tests/libgxf_test_cuda.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/tests/libgxf_test_cuda.so deleted file mode 100755 index dae0b19..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/cuda/tests/libgxf_test_cuda.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f6a4d2afe1594ffc5b0527383f4a513f7c87954206245803a7c510d2620aa27c -size 3911136 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/ipc/grpc/libgxf_grpc.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/ipc/grpc/libgxf_grpc.so deleted file mode 100755 index 89fd7d5..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/ipc/grpc/libgxf_grpc.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:69cf581beed87ed87b9f687e414361b605231250caa61bad5809605b3637ce91 -size 18465576 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/ipc/http/libgxf_http.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/ipc/http/libgxf_http.so deleted file mode 100755 index 9ba0131..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/ipc/http/libgxf_http.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:7b9b042db38190bae6eb446cfc5fcd3619aeba0ca2f3e4748eb17c35b9dbfeeb -size 9695480 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/multimedia/libgxf_multimedia.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/multimedia/libgxf_multimedia.so deleted file mode 100755 index 49e0ae3..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/multimedia/libgxf_multimedia.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:2343b6e759e77b1d3687c5e47df62b31644101993e3ec088b32fb8ffda4f5445 -size 2753352 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/network/libgxf_network.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/network/libgxf_network.so deleted file mode 100755 index c8a29a8..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/network/libgxf_network.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:fc815563ba03019ceb5250d073e01f1a53d493f3b3a4f24ff008879bf5953eed -size 2908888 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/npp/libgxf_npp.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/npp/libgxf_npp.so deleted file mode 100755 index 00e64b0..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/npp/libgxf_npp.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:16aa2e616358c99b3a87a438e5e20e58e0185fe5db229dc41955bd067c855a82 -size 3764440 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/python_codelet/libgxf_python_codelet.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/python_codelet/libgxf_python_codelet.so deleted file mode 100755 index 20391a3..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/python_codelet/libgxf_python_codelet.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:62efc5481fa4b63194aff16a07f8c8a4469becf6696f78d4f9033f771413c2c6 -size 3948240 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/python_codelet/pycodelet.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/python_codelet/pycodelet.so deleted file mode 100755 index 56b445e..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/python_codelet/pycodelet.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:d1e4f65e1b2a0b12e9198df576243e9b668ff9fed6eb656c3762b52131edcfec -size 3968192 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/sample/libgxf_sample.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/sample/libgxf_sample.so deleted file mode 100755 index e819ce0..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/sample/libgxf_sample.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:2342bc8a6012019edf353df0aa1829d2738c781f5abe7e85a86b686b2b99e3d3 -size 2793832 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/serialization/libgxf_serialization.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/serialization/libgxf_serialization.so deleted file mode 100755 index ff225a2..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/serialization/libgxf_serialization.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:ed5add7d3830d36301aa97720b7aacb6c3490f1057b93f65de063edd45d35b6a -size 4093088 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/allocator_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/allocator_pybind.so deleted file mode 100755 index 360a479..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/allocator_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:60fe2ec4fbd640239e24ba653e57634bc46a0b895e32121f4ecb7665d3bdeacf -size 3890160 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/clock_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/clock_pybind.so deleted file mode 100755 index 4539490..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/clock_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:48c6a9bd58c9b9e8af091b6efc365591024416b21e83bd12da565fdd391aa90e -size 3895728 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/libgxf_std.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/libgxf_std.so deleted file mode 100755 index 706ea25..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/libgxf_std.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1e00b3f75e51e4344a9f7e0109d5ca89b9d25b945bbf4ec087458e1ccafaab1f -size 4141256 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/receiver_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/receiver_pybind.so deleted file mode 100755 index 62a17b8..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/receiver_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:24cee7dfd70e6dcb2a8894860416c7fc6460ceb348e42ffbd0be66c8bf93e95c -size 3895360 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/tensor_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/tensor_pybind.so deleted file mode 100755 index 15e137b..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/tensor_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1534601499ec704103ce88dff8ec485e7b5d6a973c9c099595856ba783880369 -size 4208672 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/timestamp_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/timestamp_pybind.so deleted file mode 100755 index ab065bb..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/timestamp_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:26ac1c49fdafdcba95d153f637a1c69a444922f86c93b2c89b518cf7509931da -size 3839072 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/transmitter_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/transmitter_pybind.so deleted file mode 100755 index 72b1440..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/transmitter_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:d535afccdb82f1cb059d1abab438aa106f65f07fc22c4122ba32026eee8dc8e7 -size 3895344 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/vault_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/vault_pybind.so deleted file mode 100755 index 6de8809..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/std/vault_pybind.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:75a29e3c2396e3336ecf5ecb6b772dd3dbec25dbfca861e15397db166a0dbb5e -size 3844680 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/test/extensions/libgxf_test.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/test/extensions/libgxf_test.so deleted file mode 100755 index 2965a65..0000000 --- a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/test/extensions/libgxf_test.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:b6f216b4a7baf4fbc3ba9ec7398dde7e4b13f4a23a0e7c7fce9d9edf3f1b973c -size 5780624 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/behavior_tree/libgxf_behavior_tree.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/behavior_tree/libgxf_behavior_tree.so new file mode 100755 index 0000000..f02ce07 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/behavior_tree/libgxf_behavior_tree.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7f457ac91589924a6c877f55605d450a4ebdfa075657463ca7a18cf6701a1a77 +size 4043624 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/core/core_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/core/core_pybind.so new file mode 100755 index 0000000..d7dbca9 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/core/core_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:81f16e4f5942caf255aaf3801d510186f2fea14951685a4c85e9fff16b9b078b +size 4438912 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/core/libgxf_core.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/core/libgxf_core.so new file mode 100755 index 0000000..f13d733 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/core/libgxf_core.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:14583b507a447edaf108618478f3e155e98a7f8f15579619539f57550a336b28 +size 2547848 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/cuda_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/cuda_pybind.so new file mode 100755 index 0000000..26d8fe5 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/cuda_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:865ead5551dd39107ebffb7d7bcb782459ba9f950f9158ed3932f6ec5aedeafc +size 3085912 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/libgxf_cuda.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/libgxf_cuda.so new file mode 100755 index 0000000..9f8a734 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/libgxf_cuda.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e899c846a5de60b63ef95f1740c07e09c7da8f102e49a8633e28f4b09286514c +size 2983976 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/tests/libgxf_test_cuda.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/tests/libgxf_test_cuda.so new file mode 100755 index 0000000..620a9ca --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/cuda/tests/libgxf_test_cuda.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:27aaeeb0046ca27dfbb605366d7fa222065015f29b1e441bdd9a8fafe9ba539e +size 4170016 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/ipc/grpc/libgxf_grpc.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/ipc/grpc/libgxf_grpc.so new file mode 100755 index 0000000..a27418e --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/ipc/grpc/libgxf_grpc.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:fdf2a0df0b509d575b36259c688e7ed41727cfc8b8180f390f7281f4e63d00ee +size 15604808 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/ipc/http/libgxf_http.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/ipc/http/libgxf_http.so new file mode 100755 index 0000000..3b07fbe --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/ipc/http/libgxf_http.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:764452b9e09f3795397260a5edcf7d09413502c3fc76b75b385524afaed729bf +size 9050568 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/logger/libgxf_logger.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/logger/libgxf_logger.so similarity index 100% rename from isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_2/logger/libgxf_logger.so rename to isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/logger/libgxf_logger.so diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/multimedia/libgxf_multimedia.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/multimedia/libgxf_multimedia.so new file mode 100755 index 0000000..81e4bfa --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/multimedia/libgxf_multimedia.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:bef5c470f60e641fd50036139cb581c549af4413e6b1e93532506101fe6f1597 +size 2796744 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/network/libgxf_network.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/network/libgxf_network.so new file mode 100755 index 0000000..111b954 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/network/libgxf_network.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b8dc2127a03c2b3abc06f12f1347c519106c852a9e83e7bcc7da0197f99d9c0b +size 2964680 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/npp/libgxf_npp.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/npp/libgxf_npp.so new file mode 100755 index 0000000..41bdcbd --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/npp/libgxf_npp.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7b54e17a9257af8d14ea1d82b1b29898cc6801c7c9fd158bdb37f636d32d6d9f +size 3812384 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/python_codelet/libgxf_python_codelet.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/python_codelet/libgxf_python_codelet.so new file mode 100755 index 0000000..5829b79 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/python_codelet/libgxf_python_codelet.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f28804cc7112b4d5715ab4d35d86cf0ef2c0dc40a3ac74626c8f64d3aeeb48c5 +size 4019440 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/python_codelet/pycodelet.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/python_codelet/pycodelet.so new file mode 100755 index 0000000..d98c5d6 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/python_codelet/pycodelet.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:fad482af9df4d71e0e4fff6ccd876b31abb0348ebf87c38b7ac8978c4337ae11 +size 4030040 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/sample/libgxf_sample.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/sample/libgxf_sample.so new file mode 100755 index 0000000..d0a3372 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/sample/libgxf_sample.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:40502ce7729de340acf375285619d2b88134c2bd01ba0ed74ba90250bfa2966d +size 2890936 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/serialization/libgxf_serialization.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/serialization/libgxf_serialization.so new file mode 100755 index 0000000..7b4a4fd --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/serialization/libgxf_serialization.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:41f0a81aad0aa5690dc77c7a97c77ea401bd239ed5f648be4d2ff9a79cc16227 +size 4150336 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/allocator_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/allocator_pybind.so new file mode 100755 index 0000000..75ab2b1 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/allocator_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ab384e7574daf704373d8a86754db9235d2b4e38131e53750887f19a08f0099e +size 3946832 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/clock_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/clock_pybind.so new file mode 100755 index 0000000..1843bfb --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/clock_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:86da7cbece1adb5d82e47728285a37cd5a408b9c277bbc71c9347655c8e1991f +size 3952392 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/libgxf_std.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/libgxf_std.so new file mode 100755 index 0000000..d0180bf --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/libgxf_std.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8d5a1a5a881f10c4f6e668dea8d9d7f2c0142570154596894426128e8fc44f26 +size 4248528 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/receiver_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/receiver_pybind.so new file mode 100755 index 0000000..926152a --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/receiver_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5597a1acfcd184f4213e42379872ac13590ccfb3c7da09d42790bf4eda3eb50c +size 3952032 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/tensor_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/tensor_pybind.so new file mode 100755 index 0000000..29e1d4f --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/tensor_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9964c9a717844a380d6feb15a7a4b9124e98f2cb066434f5fc4757847bf68fd6 +size 4270888 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/timestamp_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/timestamp_pybind.so new file mode 100755 index 0000000..b695300 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/timestamp_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:00a320376f185526d530a710389b5ebb231e7e3cd9a2da9aa965a137eedca3ef +size 3951960 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/transmitter_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/transmitter_pybind.so new file mode 100755 index 0000000..963bded --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/transmitter_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f19ab1d3dd2aa833cd56c841798044109929093f26fe5d1333ca48475b7f4937 +size 3952016 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/vault_pybind.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/vault_pybind.so new file mode 100755 index 0000000..f1e433c --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/std/vault_pybind.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:11b65203ae3297e76a42681da44eea57d5677114ec528a3ec1003542187867ba +size 3905288 diff --git a/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/test/extensions/libgxf_test.so b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/test/extensions/libgxf_test.so new file mode 100755 index 0000000..248a094 --- /dev/null +++ b/isaac_ros_gxf/gxf/core/lib/gxf_x86_64_cuda_12_6/test/extensions/libgxf_test.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:1c1cbdfbddd867b4bd54f2531729699b996d7ce450cd84913cf82c66a5eac26e +size 5262520 diff --git a/isaac_ros_gxf/package.xml b/isaac_ros_gxf/package.xml index a901e08..25fb0cf 100644 --- a/isaac_ros_gxf/package.xml +++ b/isaac_ros_gxf/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_gxf - 3.1.0 + 3.2.0 Isaac ROS GXF Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_argus/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_argus/CMakeLists.txt index 4dab435..c7ee967 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_argus/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_argus/CMakeLists.txt @@ -27,7 +27,7 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") endif() # Add an interface target to export dependencies @@ -59,4 +59,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_argus/lib/gxf_jetpack60/libgxf_isaac_argus.so b/isaac_ros_gxf_extensions/gxf_isaac_argus/lib/gxf_jetpack60/libgxf_isaac_argus.so deleted file mode 100755 index 81d27e4..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_argus/lib/gxf_jetpack60/libgxf_isaac_argus.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f62b65633baa5cf126997d83a7941a85a7dfde84f834b96d5eb4bf7e22a06e5c -size 4134232 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_argus/lib/gxf_jetpack61/libgxf_isaac_argus.so b/isaac_ros_gxf_extensions/gxf_isaac_argus/lib/gxf_jetpack61/libgxf_isaac_argus.so new file mode 100755 index 0000000..6bdbf40 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_argus/lib/gxf_jetpack61/libgxf_isaac_argus.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:607b17612465a3eea02fdd0ecbeca3660f6fe6b1c2d530a6ffc85f4ddec0c072 +size 4296696 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_argus/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_argus/package.xml index 67f65ce..de82899 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_argus/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_argus/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_argus - 3.1.0 + 3.2.0 GXF extension containing argus components. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_atlas/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_atlas/CMakeLists.txt index ce4cffb..621ca8b 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_atlas/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_atlas/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_jetpack60/libgxf_isaac_atlas.so b/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_jetpack60/libgxf_isaac_atlas.so deleted file mode 100755 index f68d681..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_jetpack60/libgxf_isaac_atlas.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:68dc3a509adb5022a637ed6de938d5130089c18d8a1dcc5b5e5a53cec7073811 -size 7704184 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_jetpack61/libgxf_isaac_atlas.so b/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_jetpack61/libgxf_isaac_atlas.so new file mode 100755 index 0000000..327bc43 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_jetpack61/libgxf_isaac_atlas.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:872acf7793d7c63f69cf14345c86c08f0e43203034dd3116af6ee90421c76932 +size 7781872 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_atlas.so b/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_atlas.so deleted file mode 100755 index 126a602..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_atlas.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:4d4e532c00b0c705e7a3a3b3d381979228c56497a5c849b53bd11ee1e5a49964 -size 8000504 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_atlas.so b/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_atlas.so new file mode 100755 index 0000000..f018074 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_atlas/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_atlas.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ab5d0743d907bde678d1d44f57c0201ed8628c36eddc35a900570bcb92b34cc5 +size 8062056 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_atlas/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_atlas/package.xml index 7f83586..9f63e7b 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_atlas/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_atlas/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_atlas - 3.1.0 + 3.2.0 GXF extension containing environment management components, such as pose tree, map providers, and the composite schema server. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_cuda/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_cuda/CMakeLists.txt index 370e8ed..2836da9 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_cuda/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_cuda/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -59,4 +59,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_jetpack60/libgxf_isaac_cuda.so b/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_jetpack60/libgxf_isaac_cuda.so deleted file mode 100755 index e585545..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_jetpack60/libgxf_isaac_cuda.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:98c620a473cffdd3b2fd41d05587b6f02859dec522ca8bfd10dfe29ecd6d86f4 -size 3572200 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_jetpack61/libgxf_isaac_cuda.so b/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_jetpack61/libgxf_isaac_cuda.so new file mode 100755 index 0000000..d0ad59c --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_jetpack61/libgxf_isaac_cuda.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:20a6f63a59220907c34e9b6fdbe9e80132a0a91c4b9e6e8238551949d315d009 +size 3649120 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_cuda.so b/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_cuda.so deleted file mode 100755 index 2c2bebb..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_cuda.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:3a8ca4b67eff063cc9c0f3994d2d432bc2f4c491bf31a1071ea4455db522f42d -size 3739032 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_cuda.so b/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_cuda.so new file mode 100755 index 0000000..03d73c0 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_cuda/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_cuda.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b02b1cac995902ba5076ce9071d0ac9a98230427aa4b9dc07c869e39af230414 +size 3778416 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_cuda/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_cuda/package.xml index 5f6c0c5..45cd8b7 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_cuda/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_cuda/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_cuda - 3.1.0 + 3.2.0 GXF extension for Cuda related components in GXF Core. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/CMakeLists.txt index 4d6fff1..6a12f83 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_jetpack60/libgxf_isaac_flatscan_localization.so b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_jetpack60/libgxf_isaac_flatscan_localization.so deleted file mode 100755 index 01b25a6..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_jetpack60/libgxf_isaac_flatscan_localization.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:2beb0087754ccf6b8e08cb4c3274afb1827453564e45dffe1d78760cd9a084b9 -size 8501768 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_jetpack61/libgxf_isaac_flatscan_localization.so b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_jetpack61/libgxf_isaac_flatscan_localization.so new file mode 100755 index 0000000..bf05396 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_jetpack61/libgxf_isaac_flatscan_localization.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a0407137f59fdd1023b74d36888fef6672428df1d4be7b6faf25d8c8d2227a19 +size 8578872 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_flatscan_localization.so b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_flatscan_localization.so deleted file mode 100755 index c39af62..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_flatscan_localization.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:db1147c44dbf76dce3a4f9d8f4f1370d96cb1e33bdea26a2ee74d2ba0776f07a -size 8903696 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_flatscan_localization.so b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_flatscan_localization.so new file mode 100755 index 0000000..8f0ecf2 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_flatscan_localization.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:88774ee436d44f835cb46c1f2171bcdcf7967c5aa9c80e5ab8899b2a3ec35364 +size 8985504 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/package.xml index 80ef148..29ce6ba 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_flatscan_localization/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_flatscan_localization - 3.1.0 + 3.2.0 Extension containing flatscan localization related components. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_gems/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_gems/CMakeLists.txt index d52d10f..1e0f67f 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_gems/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_gems/CMakeLists.txt @@ -29,9 +29,9 @@ find_package(Eigen3 3.3 REQUIRED NO_MODULE) # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -57,4 +57,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_gems/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_gems/package.xml index 45e7fae..95d0be2 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_gems/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_gems/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_gems - 3.1.0 + 3.2.0 Headers that are used by Isaac GXF extensions. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/CMakeLists.txt index 888e312..cac9f29 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_jetpack60/libgxf_isaac_gxf_helpers.so b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_jetpack60/libgxf_isaac_gxf_helpers.so deleted file mode 100755 index fa3c2fb..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_jetpack60/libgxf_isaac_gxf_helpers.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:0d8369f17bfd25eed71126aee3686d8ff804c5558cc83862c4a1b02859db8ff3 -size 3802816 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_jetpack61/libgxf_isaac_gxf_helpers.so b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_jetpack61/libgxf_isaac_gxf_helpers.so new file mode 100755 index 0000000..e742a24 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_jetpack61/libgxf_isaac_gxf_helpers.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8f235c1227faff231ae336005ecca2b031e3b95e84dc8b2588667bdbd4c7b385 +size 3814744 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_gxf_helpers.so b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_gxf_helpers.so deleted file mode 100755 index c14172d..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_gxf_helpers.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:81cad59997ca4fa77470e257984c6325a782dd0cac1c6d620fdc3747c8bf9fa9 -size 3926480 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_gxf_helpers.so b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_gxf_helpers.so new file mode 100755 index 0000000..7b6cbca --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_gxf_helpers.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:37f5398b9ef9bcf762d716078ba9566770d7fd31b61f41f2ad67c03416220731 +size 3982600 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/package.xml index f00c0f7..61b4520 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_gxf_helpers/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_gxf_helpers - 3.1.0 + 3.2.0 GXF extension containing GXF helpers. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_hesai/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_hesai/CMakeLists.txt index 86202fd..ad72ac9 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_hesai/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_hesai/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_jetpack60/libgxf_isaac_hesai.so b/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_jetpack60/libgxf_isaac_hesai.so deleted file mode 100755 index 0c5c649..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_jetpack60/libgxf_isaac_hesai.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:2ea2df5998a82eb65b6999b3cea95077bb008f31bb5c4361b7cbadbe729962b9 -size 3810352 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_jetpack61/libgxf_isaac_hesai.so b/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_jetpack61/libgxf_isaac_hesai.so new file mode 100755 index 0000000..a9f782e --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_jetpack61/libgxf_isaac_hesai.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:babb827c900ef99e4be2b1b0d17b4f545f746279375b84420a18d327d8cdc476 +size 3888072 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_hesai.so b/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_hesai.so deleted file mode 100755 index 808f22b..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_hesai.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:d10e01c3bdd6e7cb43622fcdb6d97a3be7e9b6adf05908cb187a187eb4dd652f -size 3975816 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_hesai.so b/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_hesai.so new file mode 100755 index 0000000..b34e314 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_hesai/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_hesai.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:385b18a01bb95a289c0062c0e191b2b2734b07fdda78359dbb7f52c83f4427c8 +size 4040448 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_hesai/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_hesai/package.xml index 5da2f2b..6ba4e88 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_hesai/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_hesai/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_hesai - 3.1.0 + 3.2.0 GXF extension to interface with Hesai lidars. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_localization/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_localization/CMakeLists.txt index 7fbb177..584cd0a 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_localization/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_localization/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_jetpack60/libgxf_isaac_localization.so b/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_jetpack60/libgxf_isaac_localization.so deleted file mode 100755 index 443a067..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_jetpack60/libgxf_isaac_localization.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f7b97445eb22a6906be515d4842186dcc831b9f43679f715eb65d1605ddfb982 -size 7213728 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_jetpack61/libgxf_isaac_localization.so b/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_jetpack61/libgxf_isaac_localization.so new file mode 100755 index 0000000..ebeceb3 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_jetpack61/libgxf_isaac_localization.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7dc344de3ae7943ff79519f96e7d11366e431f303d2d6529b175b011fc8858c6 +size 7290224 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_localization.so b/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_localization.so deleted file mode 100755 index e3c8237..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_localization.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:04444d73e530f69d3c6d4b57601b865701c3cdf23f91f0106117e47c1eef1687 -size 7451184 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_localization.so b/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_localization.so new file mode 100755 index 0000000..3fbdaaa --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_localization/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_localization.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c13e0ffb2aca596ca8206ab9d7005f41dff4f04613a22b0bf49e13a8be8f2304 +size 7519072 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_localization/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_localization/package.xml index b2aa560..d578280 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_localization/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_localization/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_localization - 3.1.0 + 3.2.0 GXF extension containing environment management components, such as pose tree, map providers, and the composite schema server. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/CMakeLists.txt index 29171e6..bfcd39b 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_jetpack60/libgxf_isaac_message_compositor.so b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_jetpack60/libgxf_isaac_message_compositor.so deleted file mode 100755 index d7adb0c..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_jetpack60/libgxf_isaac_message_compositor.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f8e508890d7013e5171b413db8a220dbc0d154199a19a6117bc84341c61537b3 -size 329608 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_jetpack61/libgxf_isaac_message_compositor.so b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_jetpack61/libgxf_isaac_message_compositor.so new file mode 100755 index 0000000..d2e9c91 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_jetpack61/libgxf_isaac_message_compositor.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e6580740bc64c7cd5afa842c4d6f80d8838b14f92dbea0081df229a872024828 +size 3655952 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_message_compositor.so b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_message_compositor.so deleted file mode 100755 index f52c995..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_message_compositor.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:8cd51f098f50eabe3e5393c332c686f90badd1916642e4a0db77befaf439d427 -size 312568 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_message_compositor.so b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_message_compositor.so new file mode 100755 index 0000000..9e21d81 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_message_compositor.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ff8c7d5398de42238211481d3d9403cfc75af5081d6e77eb447b04c94b1760e6 +size 3825616 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/package.xml index 6af1f1d..e43b8cb 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_message_compositor/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_message_compositor - 3.1.0 + 3.2.0 Extension containing a message compositor for fusing messages. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_messages/CMakeLists.txt index 409f1d0..8a2bb10 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_messages/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_messages/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -62,4 +62,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_jetpack60/libgxf_isaac_messages.so b/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_jetpack60/libgxf_isaac_messages.so deleted file mode 100755 index 5300a6a..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_jetpack60/libgxf_isaac_messages.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:8e74ca55ee69b4e05f5e4ec74317c3d893d2df906662a3672a8b2c4aca94a1e7 -size 8286232 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_jetpack61/libgxf_isaac_messages.so b/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_jetpack61/libgxf_isaac_messages.so new file mode 100755 index 0000000..80ab58a --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_jetpack61/libgxf_isaac_messages.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5afe5cf05af35fabd6b8ef2b370ad24a660ebb9506ed2561b3d9adc0376354b3 +size 8365152 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_messages.so b/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_messages.so deleted file mode 100755 index efb8b17..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_messages.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:23f92a20a6bb624707faec6194566cd5d333bcd068a31b9c1d9085620c8cce9b -size 8624208 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_messages.so b/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_messages.so new file mode 100755 index 0000000..d036ade --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_messages/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_messages.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b22f2dfca02aa0cc8d3cf1979a928c4fa8c5ed89c717b380d417502bbc693d4b +size 8735096 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_messages/package.xml index d4fd6bc..aa305aa 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_messages/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_messages/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_messages - 3.1.0 + 3.2.0 Extension containing Isaac SDK related messages and data types. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/CMakeLists.txt index abaffb2..d7b25ab 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -52,4 +52,10 @@ if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/gxf") INTERFACE_INCLUDE_DIRECTORIES "$/share/${PROJECT_NAME}/gxf/include") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_jetpack60/libgxf_isaac_messages_throttler.so b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_jetpack60/libgxf_isaac_messages_throttler.so deleted file mode 100755 index 39a2bbb..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_jetpack60/libgxf_isaac_messages_throttler.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:39993eba680838b86c9b89a4a4097d4b9c387beaeb726a44d2f9d8b04f6f9ee9 -size 3557656 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_jetpack61/libgxf_isaac_messages_throttler.so b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_jetpack61/libgxf_isaac_messages_throttler.so new file mode 100755 index 0000000..fa17f50 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_jetpack61/libgxf_isaac_messages_throttler.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:101c28b4cce92cdba2e4b96dbaf157ac65589da70eaed15a74f472c8ce4fc4af +size 3570072 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_messages_throttler.so b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_messages_throttler.so deleted file mode 100755 index aee4dd5..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_messages_throttler.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:00a069a32f13ac4b717865c2dedfb7ebeadcb834ebedf917b339d60ca67ba82e -size 3665896 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_messages_throttler.so b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_messages_throttler.so new file mode 100755 index 0000000..30d5651 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_messages_throttler.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e77ee56d8bb0e5066870d0cbce349cda88ee0932ae2061722f9c6bf6668e13b9 +size 3726432 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/package.xml index 336445d..c2a5563 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_messages_throttler/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_messages_throttler - 3.1.0 + 3.2.0 NvIsaacMessagesThrottler Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/CMakeLists.txt index c68289d..4f0cb73 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_jetpack60/libgxf_isaac_optimizer.so b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_jetpack60/libgxf_isaac_optimizer.so deleted file mode 100755 index 139b7c3..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_jetpack60/libgxf_isaac_optimizer.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f190bc0477c074c9b0930c47efce1bffe107613a3b64a51de72ac65ff059d00f -size 4472104 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_jetpack61/libgxf_isaac_optimizer.so b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_jetpack61/libgxf_isaac_optimizer.so new file mode 100755 index 0000000..f79af23 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_jetpack61/libgxf_isaac_optimizer.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:78b3585e9868b6d521a141b886089841ee07c7c31bd94f6861148b317d48e565 +size 4549432 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_optimizer.so b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_optimizer.so deleted file mode 100755 index 849263f..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_optimizer.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:6dd97c660a709f57d1e472d77dfb53eae972d1ac751a3e14c933d450525a338b -size 4717416 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_optimizer.so b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_optimizer.so new file mode 100755 index 0000000..a0583e7 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_optimizer.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8491f36497563165b91975d71252b82356ae8b32b8c600038ace821dde5fb88c +size 4773448 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/package.xml index 6d49444..2462922 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_optimizer/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_optimizer/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_optimizer - 3.1.0 + 3.2.0 GXF extension containing environment management components, such as pose tree, map providers, and the composite schema server. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/CMakeLists.txt index c3bf995..b7b42c6 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_jetpack60/libgxf_isaac_point_cloud.so b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_jetpack60/libgxf_isaac_point_cloud.so deleted file mode 100755 index ba4340e..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_jetpack60/libgxf_isaac_point_cloud.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:b7b1d591f7e19ec03514afbb7612a51afc5adcfa42339848dcab9d22870f334b -size 805328 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_jetpack61/libgxf_isaac_point_cloud.so b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_jetpack61/libgxf_isaac_point_cloud.so new file mode 100755 index 0000000..06cc9c4 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_jetpack61/libgxf_isaac_point_cloud.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f58965c07758a88e720399d13835bd2782aaa66dda653edae851d57c19ad8ff9 +size 8444600 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_point_cloud.so b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_point_cloud.so deleted file mode 100755 index 6227de0..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_point_cloud.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:754b0cc94ab31cd07b91acc5674ece0c0d4b48445364dfb78a2939137d1d1689 -size 1066256 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_point_cloud.so b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_point_cloud.so new file mode 100755 index 0000000..671a5ec --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_point_cloud.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:fbcc44707b94ee06e506cfa7f394e8c0e80d9eb970abe8849044a89dfb31d3d7 +size 8862296 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/package.xml index 567cce9..ed67e3a 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_point_cloud/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_point_cloud - 3.1.0 + 3.2.0 GXF extension containing environment management components, such as pose tree, map providers, and the composite schema server. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/CMakeLists.txt index 6089134..3f36309 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_jetpack60/libgxf_isaac_range_scan_processing.so b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_jetpack60/libgxf_isaac_range_scan_processing.so deleted file mode 100755 index 2b85bc6..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_jetpack60/libgxf_isaac_range_scan_processing.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:237017939147c0137cd6f0d02b15e0e791729edee190dd9a23d07cb01c3f5aef -size 7595024 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_jetpack61/libgxf_isaac_range_scan_processing.so b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_jetpack61/libgxf_isaac_range_scan_processing.so new file mode 100755 index 0000000..6b916e0 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_jetpack61/libgxf_isaac_range_scan_processing.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:1c9967777fb86488dc404cd83cbed78872146b9895b976bf60010f6445e9b1d9 +size 7605232 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_range_scan_processing.so b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_range_scan_processing.so deleted file mode 100755 index 8beaa3b..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_range_scan_processing.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1a66e77add470b46e95c705304b8b445cef4d60e31bd9b4632ca3f1f73d5aba1 -size 7822936 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_range_scan_processing.so b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_range_scan_processing.so new file mode 100755 index 0000000..2521c06 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_range_scan_processing.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:131641ab2c681f98e3b895dfa78ec2eecef404ac469c5d0484f3cbf447ee3724 +size 7874568 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/package.xml index ae43125..39c6cce 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_range_scan_processing/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_range_scan_processing - 3.1.0 + 3.2.0 GXF extension containing components for processing range scan data. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/CMakeLists.txt index acdbdd7..9d931ec 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -62,4 +62,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_jetpack60/libgxf_isaac_ros_cuda.so b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_jetpack60/libgxf_isaac_ros_cuda.so deleted file mode 100755 index d878a3f..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_jetpack60/libgxf_isaac_ros_cuda.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:90d4dba1f079bfd13791517cba1554a7d4dd70b05cb1beee702b83f81e07601e -size 256848 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_jetpack61/libgxf_isaac_ros_cuda.so b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_jetpack61/libgxf_isaac_ros_cuda.so new file mode 100755 index 0000000..47f30b6 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_jetpack61/libgxf_isaac_ros_cuda.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9d8b2a098f0082e046135c1f2f0c86376aca36e70779a41757be661c324fad3d +size 3649768 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_ros_cuda.so b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_ros_cuda.so deleted file mode 100755 index 97ab805..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_ros_cuda.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:97f6dcabfea2e9ed364a1d149f8030d3071446f557e86bc5076e1e64a5a4238f -size 254560 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_ros_cuda.so b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_ros_cuda.so new file mode 100755 index 0000000..dc0274d --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_ros_cuda.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ce831924279f274adfcfda6f838e4ea03dfa11e87b9aec8288940956289d91e0 +size 3791072 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/package.xml index c8f04af..69cc1d9 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_ros_cuda/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_ros_cuda - 3.1.0 + 3.2.0 GXF extension for Cuda related components in Isaac. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/CMakeLists.txt index 4cf6149..b6a07b3 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_jetpack60/libgxf_isaac_ros_messages.so b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_jetpack60/libgxf_isaac_ros_messages.so deleted file mode 100755 index 5aa5c36..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_jetpack60/libgxf_isaac_ros_messages.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:107dc58d062e7927bf673c9c876db796516e785b3083eea55fb3fae818d86d20 -size 79096 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_jetpack61/libgxf_isaac_ros_messages.so b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_jetpack61/libgxf_isaac_ros_messages.so new file mode 100755 index 0000000..878f4f9 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_jetpack61/libgxf_isaac_ros_messages.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:dc995a61f2dcfecb0d92dcd2f2e4dff32c50e64ed7e8fd513a0a29d684304891 +size 8089656 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_ros_messages.so b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_ros_messages.so deleted file mode 100755 index 79d3637..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_ros_messages.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1e152932346a65df778ae611a791e922334dd198fc4ae663cb2d1850a2aa9510 -size 52520 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_ros_messages.so b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_ros_messages.so new file mode 100755 index 0000000..f6406ba --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_ros_messages.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:47ec83c797775358d831076c4ba4c8b9fce9cb7f6a7ee79235bf1b14d06f24eb +size 8436664 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/package.xml index 5385440..3967db0 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_ros_messages/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_ros_messages - 3.1.0 + 3.2.0 Extension containing Isaac ROS related messages and data types. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_segway/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_segway/CMakeLists.txt index 30a50cb..e4c38f2 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_segway/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_segway/CMakeLists.txt @@ -27,7 +27,7 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") else() message(WARNING "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}. " @@ -63,4 +63,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_segway/lib/gxf_jetpack60/libgxf_isaac_segway.so b/isaac_ros_gxf_extensions/gxf_isaac_segway/lib/gxf_jetpack60/libgxf_isaac_segway.so deleted file mode 100755 index 027f342..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_segway/lib/gxf_jetpack60/libgxf_isaac_segway.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f848f48756f2dd1f0dbb22727a2e9f5820f677a368471ec5cf46704d570826af -size 8173456 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_segway/lib/gxf_jetpack61/libgxf_isaac_segway.so b/isaac_ros_gxf_extensions/gxf_isaac_segway/lib/gxf_jetpack61/libgxf_isaac_segway.so new file mode 100755 index 0000000..60d7181 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_segway/lib/gxf_jetpack61/libgxf_isaac_segway.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aa1e6d39b5baf024ec6cd4eb1f57f47164973134274c0aa4f4b041826618c235 +size 8252304 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_segway/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_segway/package.xml index cc7839d..e01200d 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_segway/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_segway/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_segway - 3.1.0 + 3.2.0 GXF extension to interface with Segway chassis. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_sight/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_sight/CMakeLists.txt index c29d8d8..2dcb378 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_sight/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_sight/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_jetpack60/libgxf_isaac_sight.so b/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_jetpack60/libgxf_isaac_sight.so deleted file mode 100755 index cc2d91e..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_jetpack60/libgxf_isaac_sight.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:29677676f23ac04ee5c842160d48e71f8105e2e51982b428fa0fcf7d0e12b28d -size 4554608 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_jetpack61/libgxf_isaac_sight.so b/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_jetpack61/libgxf_isaac_sight.so new file mode 100755 index 0000000..ca67f84 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_jetpack61/libgxf_isaac_sight.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:f88e5a33e4e3eb04c73e0a0fb358b47a39889c674bb35f0428540ae2de89f8c6 +size 4569520 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_sight.so b/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_sight.so deleted file mode 100755 index f22fd04..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_sight.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:06c681e5a9507e635b5bf127418bffced97679c9aa420a4f099c44aeb572aa24 -size 4746336 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_sight.so b/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_sight.so new file mode 100755 index 0000000..4e4f443 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_sight/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_sight.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b192f2e73194fd135504f4647ac67d72ac4e9bb48bde19b1f26b8b7d84e00ec7 +size 4813976 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_sight/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_sight/package.xml index 0fc3d6c..6dd2887 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_sight/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_sight/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_sight - 3.1.0 + 3.2.0 Extension containing components for visualization with sight. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/CMakeLists.txt index c610f81..af8e2c5 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/CMakeLists.txt @@ -27,9 +27,9 @@ ament_auto_find_build_dependencies() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "${CMAKE_CURRENT_SOURCE_DIR}/lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -61,4 +61,10 @@ install(TARGETS ${PROJECT_NAME} RUNTIME DESTINATION bin) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) \ No newline at end of file diff --git a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_jetpack60/libgxf_isaac_timestamp_correlator.so b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_jetpack60/libgxf_isaac_timestamp_correlator.so deleted file mode 100755 index 4622562..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_jetpack60/libgxf_isaac_timestamp_correlator.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:85c8b4816680d31995723b008e96ee276b4a9e6d766c294584bd18a163c9558c -size 8257024 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_jetpack61/libgxf_isaac_timestamp_correlator.so b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_jetpack61/libgxf_isaac_timestamp_correlator.so new file mode 100755 index 0000000..9de9c1a --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_jetpack61/libgxf_isaac_timestamp_correlator.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ac804f262de84b87e3887e6f3e888f7cd8c3401abafce1c1fea31a722240f915 +size 8335240 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_timestamp_correlator.so b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_timestamp_correlator.so deleted file mode 100755 index e516c19..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_x86_64_cuda_12_2/libgxf_isaac_timestamp_correlator.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:9d91cd7e2aa185c3751b4047d85fb38fc6ece355c4e56bdbc8ff809cb791f882 -size 8620736 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_timestamp_correlator.so b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_timestamp_correlator.so new file mode 100755 index 0000000..c2b8ff4 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/lib/gxf_x86_64_cuda_12_6/libgxf_isaac_timestamp_correlator.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:fa6745d8541adf39b1799f311e0f61af2f56ff34e75e57d8c15ddcfbee2d1a2d +size 8731096 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/package.xml index a5fd3ae..da8220b 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_timestamp_correlator/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_timestamp_correlator - 3.1.0 + 3.2.0 Codelets to translate between TS, PHC, and system clocks. Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_isaac_utils/CMakeLists.txt b/isaac_ros_gxf_extensions/gxf_isaac_utils/CMakeLists.txt index 2603e47..3f9d91a 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_utils/CMakeLists.txt +++ b/isaac_ros_gxf_extensions/gxf_isaac_utils/CMakeLists.txt @@ -34,9 +34,9 @@ find_package(yaml-cpp) add_library(libgxf_utils SHARED IMPORTED) # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(GXF_EXT_LIB_PATH "lib/gxf_jetpack60") + set(GXF_EXT_LIB_PATH "lib/gxf_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(GXF_EXT_LIB_PATH "lib/gxf_x86_64_cuda_12_2") + set(GXF_EXT_LIB_PATH "lib/gxf_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -78,4 +78,10 @@ set_property(TARGET ${PROJECT_NAME} PROPERTY COMPILE_OPTIONS ${target_options}) # Install the binary file install(TARGETS ${PROJECT_NAME} DESTINATION share/${PROJECT_NAME}/gxf/lib) + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE) diff --git a/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_jetpack60/libgxf_utils.so b/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_jetpack60/libgxf_utils.so deleted file mode 100755 index abfd92b..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_jetpack60/libgxf_utils.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:1970ecad2cd5911a1dc711ccefa954ee0125ec2fd7dfe25806e9eb225ffaab94 -size 10634344 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_jetpack61/libgxf_utils.so b/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_jetpack61/libgxf_utils.so new file mode 100755 index 0000000..75ee840 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_jetpack61/libgxf_utils.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e5f959117405591878b5ee2940faf4a923498d87038c84643f9543b207aa0698 +size 10714208 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_x86_64_cuda_12_2/libgxf_utils.so b/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_x86_64_cuda_12_2/libgxf_utils.so deleted file mode 100755 index ec8363a..0000000 --- a/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_x86_64_cuda_12_2/libgxf_utils.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:582941cfb282f71eed61b31b349b7136afd8dffb45b950bc036c0796ba28d68d -size 11225880 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_x86_64_cuda_12_6/libgxf_utils.so b/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_x86_64_cuda_12_6/libgxf_utils.so new file mode 100755 index 0000000..d8038c2 --- /dev/null +++ b/isaac_ros_gxf_extensions/gxf_isaac_utils/lib/gxf_x86_64_cuda_12_6/libgxf_utils.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:0be53e86b45c8d200f84aed60260c2af025181fbbdb4535b90a9bd9fcfc9ca5d +size 11333608 diff --git a/isaac_ros_gxf_extensions/gxf_isaac_utils/package.xml b/isaac_ros_gxf_extensions/gxf_isaac_utils/package.xml index e97cb4c..bb249a4 100644 --- a/isaac_ros_gxf_extensions/gxf_isaac_utils/package.xml +++ b/isaac_ros_gxf_extensions/gxf_isaac_utils/package.xml @@ -21,7 +21,7 @@ SPDX-License-Identifier: Apache-2.0 gxf_isaac_utils - 3.1.0 + 3.2.0 NvIsaacUtilsExtension Isaac ROS Maintainers diff --git a/isaac_ros_gxf_extensions/gxf_optimizer/lib/gxf_jetpack60/libgxf_optimizer.so b/isaac_ros_gxf_extensions/gxf_optimizer/lib/gxf_jetpack60/libgxf_optimizer.so deleted file mode 100755 index a6a1f91..0000000 --- a/isaac_ros_gxf_extensions/gxf_optimizer/lib/gxf_jetpack60/libgxf_optimizer.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f42f8d430dcbf3c6cf172a3db623eebd6e3c22de52c985e5ff1930013738d06f -size 4472104 diff --git a/isaac_ros_gxf_extensions/gxf_optimizer/lib/gxf_x86_64_cuda_12_2/libgxf_optimizer.so b/isaac_ros_gxf_extensions/gxf_optimizer/lib/gxf_x86_64_cuda_12_2/libgxf_optimizer.so deleted file mode 100755 index 7f38588..0000000 --- a/isaac_ros_gxf_extensions/gxf_optimizer/lib/gxf_x86_64_cuda_12_2/libgxf_optimizer.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:6c285d4437681dab0511b401aa10a88081989d196df68c5ced260d3cdd09c6ba -size 4717416 diff --git a/isaac_ros_managed_nitros/CMakeLists.txt b/isaac_ros_managed_nitros/CMakeLists.txt index 7eb3bc5..1ac64cc 100644 --- a/isaac_ros_managed_nitros/CMakeLists.txt +++ b/isaac_ros_managed_nitros/CMakeLists.txt @@ -61,4 +61,10 @@ if(BUILD_TESTING) endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() \ No newline at end of file diff --git a/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_message_filters_subscriber.hpp b/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_message_filters_subscriber.hpp index 256db7b..2f42325 100644 --- a/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_message_filters_subscriber.hpp +++ b/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_message_filters_subscriber.hpp @@ -177,7 +177,7 @@ class Subscriber const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options, const std::string & compatible_data_format = "", - const NitrosStatisticsConfig & statistics_config = {}) + const NitrosDiagnosticsConfig & diagnostics_config = {}) { unsubscribe(); @@ -196,7 +196,7 @@ class Subscriber [this](const NitrosTypeViewT & nitrosViewMsg) { this->cb(EventType(std::make_shared(nitrosViewMsg.GetMessage()))); }, - statistics_config, + diagnostics_config, rclcpp_qos ); diff --git a/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_publisher.hpp b/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_publisher.hpp index 0973b88..e31a683 100644 --- a/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_publisher.hpp +++ b/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_publisher.hpp @@ -55,7 +55,7 @@ class ManagedNitrosPublisher rclcpp::Node * node, const std::string & topic, const std::string & format, - const NitrosStatisticsConfig & statistics_config = {}, + const NitrosDiagnosticsConfig & diagnostics_config = {}, const rclcpp::QoS qos = rclcpp::QoS(1)) : node_{node}, context_{GetTypeAdapterNitrosContext()}, @@ -75,7 +75,7 @@ class ManagedNitrosPublisher nitros_pub_ = std::make_shared( *node_, GetTypeAdapterNitrosContext().getContext(), nitros_type_manager_, - supported_data_formats, component_config, statistics_config); + supported_data_formats, component_config, diagnostics_config); nitros_pub_->start(); diff --git a/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_subscriber.hpp b/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_subscriber.hpp index 6997061..c312b6c 100644 --- a/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_subscriber.hpp +++ b/isaac_ros_managed_nitros/include/isaac_ros_managed_nitros/managed_nitros_subscriber.hpp @@ -44,7 +44,7 @@ class ManagedNitrosSubscriber const std::string & topic_name, const std::string & format, std::function callback = nullptr, - const NitrosStatisticsConfig & statistics_config = {}, + const NitrosDiagnosticsConfig & diagnostics_config = {}, const rclcpp::QoS qos = rclcpp::QoS(1)) : node_{node}, topic_{topic_name}, nitros_type_manager_{std::make_shared(node_)} @@ -67,7 +67,7 @@ class ManagedNitrosSubscriber nitros_sub_ = std::make_shared( *node_, GetTypeAdapterNitrosContext().getContext(), nitros_type_manager_, - supported_data_formats, component_config, statistics_config); + supported_data_formats, component_config, diagnostics_config); nitros_sub_->start(); diff --git a/isaac_ros_managed_nitros/package.xml b/isaac_ros_managed_nitros/package.xml index 809a89e..6bb34a5 100644 --- a/isaac_ros_managed_nitros/package.xml +++ b/isaac_ros_managed_nitros/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_managed_nitros - 3.1.0 + 3.2.0 Utilities for leveraging NITROS in custom ROS 2 nodes Isaac ROS Maintainers diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/CMakeLists.txt b/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/CMakeLists.txt index bdecd56..77cb31f 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/CMakeLists.txt +++ b/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/CMakeLists.txt @@ -50,4 +50,10 @@ if(BUILD_TESTING) add_launch_test(test/custom_nitros_dnn_image_encoder_pol.py TIMEOUT "600") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE launch) \ No newline at end of file diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/launch/custom_image_isaac_ros_dope_tensor_rt.launch.py b/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/launch/custom_image_isaac_ros_dope_tensor_rt.launch.py index c45835e..513a280 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/launch/custom_image_isaac_ros_dope_tensor_rt.launch.py +++ b/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/launch/custom_image_isaac_ros_dope_tensor_rt.launch.py @@ -157,7 +157,8 @@ def generate_launch_description(): 'object_name': object_name, }], remappings=[('belief_map_array', 'tensor_sub'), - ('dope/pose_array', 'poses')]) + ('dope/detections', 'detections'), + ('camera_info', '/dope_encoder/crop/info')]) container = ComposableNodeContainer( name='dope_container', diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/package.xml b/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/package.xml index ecd02e2..2b1bd0d 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/package.xml +++ b/isaac_ros_managed_nitros_examples/custom_nitros_dnn_image_encoder/package.xml @@ -21,7 +21,7 @@ custom_nitros_dnn_image_encoder - 3.1.0 + 3.2.0 Custom NITROS Image Encoding Isaac ROS Maintainers diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_image/CMakeLists.txt b/isaac_ros_managed_nitros_examples/custom_nitros_image/CMakeLists.txt index 808defa..1658899 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_image/CMakeLists.txt +++ b/isaac_ros_managed_nitros_examples/custom_nitros_image/CMakeLists.txt @@ -69,4 +69,10 @@ if(BUILD_TESTING) add_launch_test(test/test_nitros_image_switch_pol.py TIMEOUT "600") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_image/package.xml b/isaac_ros_managed_nitros_examples/custom_nitros_image/package.xml index 66be09f..2c29bc4 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_image/package.xml +++ b/isaac_ros_managed_nitros_examples/custom_nitros_image/package.xml @@ -21,7 +21,7 @@ custom_nitros_image - 3.1.0 + 3.2.0 Custom NITROS Image encoding and decoding Isaac ROS Maintainers diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_image/src/nitros_image_switch_node.cpp b/isaac_ros_managed_nitros_examples/custom_nitros_image/src/nitros_image_switch_node.cpp index 7623a63..5e0336c 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_image/src/nitros_image_switch_node.cpp +++ b/isaac_ros_managed_nitros_examples/custom_nitros_image/src/nitros_image_switch_node.cpp @@ -39,7 +39,7 @@ NitrosImageSwitchNode::NitrosImageSwitchNode(const rclcpp::NodeOptions options) nvidia::isaac_ros::nitros::NitrosImage>>( this, "switched_image", ::nvidia::isaac_ros::nitros::nitros_image_rgb8_t::supported_type_name, - nvidia::isaac_ros::nitros::NitrosStatisticsConfig{}, output_qos_)}, + nvidia::isaac_ros::nitros::NitrosDiagnosticsConfig{}, output_qos_)}, pub_camera_info_{create_publisher( "switched_camera_info", output_qos_)}, diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_message_filter/CMakeLists.txt b/isaac_ros_managed_nitros_examples/custom_nitros_message_filter/CMakeLists.txt index 2fc4440..8c96cbc 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_message_filter/CMakeLists.txt +++ b/isaac_ros_managed_nitros_examples/custom_nitros_message_filter/CMakeLists.txt @@ -47,4 +47,10 @@ if(BUILD_TESTING) add_launch_test(test/custom_nitros_message_filter_pol.py TIMEOUT "600") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_message_filter/package.xml b/isaac_ros_managed_nitros_examples/custom_nitros_message_filter/package.xml index 1c1420a..c2f7cc7 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_message_filter/package.xml +++ b/isaac_ros_managed_nitros_examples/custom_nitros_message_filter/package.xml @@ -21,7 +21,7 @@ custom_nitros_message_filter - 3.1.0 + 3.2.0 Synchronization of Camera Info and Custom NITROS Image using ROS 2 message_filters Isaac ROS Maintainers diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_message_filter_interfaces/CMakeLists.txt b/isaac_ros_managed_nitros_examples/custom_nitros_message_filter_interfaces/CMakeLists.txt index ce7dd0e..2491169 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_message_filter_interfaces/CMakeLists.txt +++ b/isaac_ros_managed_nitros_examples/custom_nitros_message_filter_interfaces/CMakeLists.txt @@ -43,4 +43,10 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_message_filter_interfaces/package.xml b/isaac_ros_managed_nitros_examples/custom_nitros_message_filter_interfaces/package.xml index 165bc27..0b37498 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_message_filter_interfaces/package.xml +++ b/isaac_ros_managed_nitros_examples/custom_nitros_message_filter_interfaces/package.xml @@ -21,7 +21,7 @@ custom_nitros_message_filter_interfaces - 3.1.0 + 3.2.0 Interfaces to validate the function of standard and custom message_filters Isaac ROS Maintainers diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_string/CMakeLists.txt b/isaac_ros_managed_nitros_examples/custom_nitros_string/CMakeLists.txt index c5007e5..0469b05 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_string/CMakeLists.txt +++ b/isaac_ros_managed_nitros_examples/custom_nitros_string/CMakeLists.txt @@ -59,4 +59,10 @@ if(BUILD_TESTING) add_launch_test(test/custom_nitros_string_encoder_pol.py TIMEOUT "600") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_managed_nitros_examples/custom_nitros_string/package.xml b/isaac_ros_managed_nitros_examples/custom_nitros_string/package.xml index 1c37384..2c4df76 100644 --- a/isaac_ros_managed_nitros_examples/custom_nitros_string/package.xml +++ b/isaac_ros_managed_nitros_examples/custom_nitros_string/package.xml @@ -21,7 +21,7 @@ custom_nitros_string - 3.1.0 + 3.2.0 Custom NITROS String encoding and decoding Isaac ROS Maintainers diff --git a/isaac_ros_nitros/CMakeLists.txt b/isaac_ros_nitros/CMakeLists.txt index 56caf75..11a2fa9 100644 --- a/isaac_ros_nitros/CMakeLists.txt +++ b/isaac_ros_nitros/CMakeLists.txt @@ -22,6 +22,8 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() +install(PROGRAMS scripts/diagnostic_viewer.py DESTINATION lib/${PROJECT_NAME}) + find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() @@ -37,11 +39,11 @@ endif() # Determine the architecture if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64") - set(CUVSLAM_LIB_PATH "lib/cuvslam/lib_aarch64_jetpack60") - set(CUAPRILTAGS_LIB_PATH "lib/cuapriltags/lib_aarch64_jetpack51") + set(CUVSLAM_LIB_PATH "lib/cuvslam/lib_aarch64_jetpack61") + set(CUAPRILTAGS_LIB_PATH "lib/cuapriltags/lib_aarch64_jetpack61") elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") - set(CUVSLAM_LIB_PATH "lib/cuvslam/lib_x86_64_cuda_12_2") - set(CUAPRILTAGS_LIB_PATH "lib/cuapriltags/lib_x86_64_cuda_11_8") + set(CUVSLAM_LIB_PATH "lib/cuvslam/lib_x86_64_cuda_12_6") + set(CUAPRILTAGS_LIB_PATH "lib/cuapriltags/lib_x86_64_cuda_12_6") else() message(FATAL_ERROR "Unsupported architecture: ${CMAKE_SYSTEM_PROCESSOR}") endif() @@ -49,7 +51,9 @@ endif() # Install exported libraries install(FILES ${CUAPRILTAGS_LIB_PATH}/libcuapriltags.a DESTINATION "${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/cuapriltags/lib") -install(FILES ${CUVSLAM_LIB_PATH}/libcuvslam.so +install(FILES + ${CUVSLAM_LIB_PATH}/libcuvslam.so + ${CUVSLAM_LIB_PATH}/cuvslam_api_launcher DESTINATION "${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/cuvslam/lib") # Install header files for cuvslam @@ -121,6 +125,13 @@ find_package(ament_lint_auto REQUIRED) find_package(launch_testing_ament_cmake REQUIRED) add_launch_test(test/isaac_ros_nitros_test_pol.py TIMEOUT "15") + add_launch_test(test/isaac_ros_nitros_diagnostics_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE config) diff --git a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_node.hpp b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_node.hpp index 0743e78..b387b37 100644 --- a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_node.hpp +++ b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_node.hpp @@ -240,8 +240,8 @@ class NitrosNode : public rclcpp::Node // Map for frame_id passthrough std::shared_ptr> frame_id_map_ptr_; - // Configurations for a Nitros statistics - std::shared_ptr statistics_config_; + // Configurations for a Nitros diagnostics + std::shared_ptr diagnostics_config_; // When enabled namespacing and the graph optimizer are ignored // In such a case, graph(s) will be loaded intact diff --git a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher.hpp b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher.hpp index b714777..c2f351f 100644 --- a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher.hpp +++ b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher.hpp @@ -113,7 +113,7 @@ class NitrosPublisher : public NitrosPublisherSubscriberBase const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config, const negotiated::NegotiatedPublisherOptions & negotiated_pub_options, - const NitrosStatisticsConfig & statistics_config); + const NitrosDiagnosticsConfig & diagnostics_config); // Constructor for creating a publisher without an associated gxf egress port NitrosPublisher( @@ -122,7 +122,7 @@ class NitrosPublisher : public NitrosPublisherSubscriberBase std::shared_ptr nitros_type_manager, const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config, - const NitrosStatisticsConfig & statistics_config); + const NitrosDiagnosticsConfig & diagnostics_config); // Getter for the negotiated_pub_ std::shared_ptr getNegotiatedPublisher(); diff --git a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher_subscriber_base.hpp b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher_subscriber_base.hpp index ff58a6c..07ed430 100644 --- a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher_subscriber_base.hpp +++ b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher_subscriber_base.hpp @@ -34,10 +34,10 @@ #include "isaac_ros_nitros/types/nitros_type_base.hpp" #include "isaac_ros_nitros/types/nitros_type_manager.hpp" -#include "isaac_ros_nitros_interfaces/msg/topic_statistics.hpp" +#include "diagnostic_msgs/msg/diagnostic_array.hpp" +#include "diagnostic_msgs/msg/key_value.hpp" #include "rclcpp/rclcpp.hpp" - namespace nvidia { namespace isaac_ros @@ -49,7 +49,9 @@ namespace { constexpr float const kSecondsToMicroseconds = 1000000; constexpr uint64_t const kMicrosecondsToNanoseconds = 1000; -} +const char * const nvidiaID = "nvidia"; +constexpr int64_t const kDropWarnTimeoutSeconds = 5; +} // namespace // Enum for specifying vairous types of Nitros publishers/subscribers enum NitrosPublisherSubscriberType @@ -72,8 +74,8 @@ struct NitrosPublisherSubscriberConfig // Enable NitrosNode to adjust the compatible format after an unsuccessful // negotiation. The compatible format is adjusted if the existing compatible - // format, together with other selected data formats in the same pub/sub group, - // cannot form a valid data format combination. + // format, together with other selected data formats in the same pub/sub + // group, cannot form a valid data format combination. bool use_flexible_compatible_format{true}; // ComponentKey whose frame_id this pub/sub should refer to @@ -83,23 +85,29 @@ struct NitrosPublisherSubscriberConfig std::function callback{nullptr}; }; -// Configurations for a Nitros statistics -struct NitrosStatisticsConfig +// Configurations for a Nitros diagnostics +struct NitrosDiagnosticsConfig { - // Statistics toggle - bool enable_statistics{false}; - bool enable_all_statistics{false}; - bool enable_node_time_statistics{false}; - bool enable_msg_time_statistics{false}; - bool enable_increasing_msg_time_statistics{false}; + // diagnostics toggle + bool enable_diagnostics{false}; + + // corresponds to launch arguments + bool enable_all_diagnostics{false}; + bool enable_node_time_diagnostics{false}; + bool enable_msg_time_diagnostics{false}; + bool enable_increasing_msg_time_diagnostics{false}; + + // enable basic diagnostics for all topics, triggered by an environment variable + bool enable_all_topic_diagnostics{false}; - // Rate (Hz) at which to publish statistics to a ROS topic - float statistics_publish_rate{1.0}; + // Rate (Hz) at which to publish diagnostics to a ROS topic + float diagnostics_publish_rate{1.0}; // Window size of the mean filter in terms of number of messages received int filter_window_size{100}; - // Map of topic name and corresponding expected time difference between messages in microseconds + // Map of topic name and corresponding expected time difference between + // messages in microseconds std::map topic_name_expected_dt_map; // Tolerance for jitter from expected frame rate in microseconds @@ -120,30 +128,22 @@ class NitrosPublisherSubscriberBase const gxf::optimizer::ComponentInfo & gxf_component_info, const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config) - : node_(node), - nitros_type_manager_(nitros_type_manager), + : node_(node), nitros_type_manager_(nitros_type_manager), gxf_component_info_(gxf_component_info), - supported_data_formats_(supported_data_formats), - config_(config) {} + supported_data_formats_(supported_data_formats), config_(config) {} NitrosPublisherSubscriberBase( - rclcpp::Node & node, - const gxf_context_t context, + rclcpp::Node & node, const gxf_context_t context, std::shared_ptr nitros_type_manager, const gxf::optimizer::ComponentInfo & gxf_component_info, const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config) - : node_(node), - context_(context), + : node_(node), context_(context), nitros_type_manager_(nitros_type_manager), gxf_component_info_(gxf_component_info), - supported_data_formats_(supported_data_formats), - config_(config) {} + supported_data_formats_(supported_data_formats), config_(config) {} - const NitrosPublisherSubscriberConfig getConfig() const - { - return config_; - } + const NitrosPublisherSubscriberConfig getConfig() const {return config_;} // Getter for the GXF component info gxf::optimizer::ComponentInfo getComponentInfo() @@ -169,7 +169,8 @@ class NitrosPublisherSubscriberBase config_.compatible_data_format = compatible_data_format; } - // Get the negotiated data format or the compatible format if negotiation failed + // Get the negotiated data format or the compatible format if negotiation + // failed std::string getFinalDataFormat() const { if (negotiated_data_format_.empty()) { @@ -179,20 +180,15 @@ class NitrosPublisherSubscriberBase } // Getter for the GXF context - gxf_context_t getContext() - { - return context_; - } + gxf_context_t getContext() {return context_;} // Setter for the parent GXF context - void setContext(const gxf_context_t context) - { - context_ = context; - } + void setContext(const gxf_context_t context) {context_ = context;} // Setter for the frame_id passthrough map void setFrameIdMap( - std::shared_ptr> frame_id_map_ptr) + std::shared_ptr> + frame_id_map_ptr) { frame_id_map_ptr_ = frame_id_map_ptr; } @@ -208,7 +204,8 @@ class NitrosPublisherSubscriberBase } else { RCLCPP_FATAL( node_.get_logger(), - "[NitrosPublisherSubscriberBase] Failed to resolve entity (eid=%ld) (error=%s)", + "[NitrosPublisherSubscriberBase] Failed to resolve entity " + "(eid=%ld) (error=%s)", base_msg.handle, GxfResultStr(msg_entity.error())); return 0; } @@ -230,15 +227,15 @@ class NitrosPublisherSubscriberBase void throwOnUnsupportedCompatibleDataFormat() { if (std::find( - supported_data_formats_.begin(), - supported_data_formats_.end(), + supported_data_formats_.begin(), supported_data_formats_.end(), config_.compatible_data_format) == supported_data_formats_.end()) { std::stringstream error_msg; - error_msg << - "[NitrosPublisherSubscriberBase] Specified compatible format " << - "\"" << config_.compatible_data_format.c_str() << "\" was not listed in " << - "the supported format list: ["; + error_msg + << "[NitrosPublisherSubscriberBase] Specified compatible format " + << "\"" << config_.compatible_data_format.c_str() + << "\" was not listed in " + << "the supported format list: ["; for (size_t i = 0; i < supported_data_formats_.size(); i++) { if (i > 0) { error_msg << ", "; @@ -246,185 +243,326 @@ class NitrosPublisherSubscriberBase error_msg << supported_data_formats_[i].c_str(); } error_msg << "]"; - RCLCPP_ERROR( - node_.get_logger(), error_msg.str().c_str()); + RCLCPP_ERROR(node_.get_logger(), error_msg.str().c_str()); throw std::runtime_error(error_msg.str().c_str()); } } - // Update statistics numbers. To be called in nitros Subscriber and Publisher - void updateStatistics(uint64_t msg_timestamp_ns) + // update node (pub/sub) time queue which is used for frame rate calculation + void updateNodeTimeQueue(const int64_t timestamp_diff_node_us) { - // Mutex lock to prevent simultaneous access of common parameters - // used by updateStatistics() and publishNitrosStatistics() - const std::lock_guard lock(nitros_statistics_mutex_); - // NITROS statistics checks message intervals both using the node clock - // and the message timestamp. - // All variables name _node refers to the node timestamp checks. - // All variables name _msg refers to the message timestamp checks. - std::chrono::time_point current_timestamp_node = clock_.now(); - // Convert nanoseconds to microseconds - uint64_t current_timestamp_msg_us = msg_timestamp_ns / kMicrosecondsToNanoseconds; + interarrival_time_queue_node_.push(timestamp_diff_node_us); + sum_interarrival_time_node_ += timestamp_diff_node_us; + if (static_cast(interarrival_time_queue_node_.size()) > + diagnostics_config_.filter_window_size) + { + sum_interarrival_time_node_ -= interarrival_time_queue_node_.front(); + interarrival_time_queue_node_.pop(); + } + } - // we can only calculate frame rate after 2 messages have been received - if (prev_timestamp_node_ != std::chrono::steady_clock::time_point::min() && - statistics_config_.enable_node_time_statistics) + // Update node (pub/sub) time diagnostics + bool updateNodeTimeDiagnostics(const int64_t timestamp_diff_node_us) + { + bool error_found = false; + // calculate difference between time between msgs(using node clock) + // and expected time between msgs + int abs_jitter_node = + std::abs( + timestamp_diff_node_us - + diagnostics_config_.topic_name_expected_dt_map[topic_name_]); + if (abs_jitter_node > diagnostics_config_.jitter_tolerance_us) { + // Increment jitter outlier count + num_jitter_outliers_node_++; + RCLCPP_DEBUG( + node_.get_logger(), + "[NitrosDiagnostics Node Time]" + " Difference of time between messages(%li) and expected time between" + " messages(%i) is out of tolerance(%i) by %i for topic %s. Units " + "are microseconds.", + timestamp_diff_node_us, + diagnostics_config_.topic_name_expected_dt_map[topic_name_], + diagnostics_config_.jitter_tolerance_us, + abs_jitter_node, topic_name_.c_str()); + } + // Update max abs jitter + max_abs_jitter_node_ = std::max(max_abs_jitter_node_, abs_jitter_node); + + jitter_queue_node_.push(abs_jitter_node); + sum_jitter_node_ += abs_jitter_node; + if (static_cast(jitter_queue_node_.size()) > + diagnostics_config_.filter_window_size) { - int microseconds_node = std::chrono::duration_cast( - current_timestamp_node - prev_timestamp_node_).count(); - // calculate difference between time between msgs(using node clock) - // and expected time between msgs - int abs_jitter_node = std::abs( - microseconds_node - - statistics_config_.topic_name_expected_dt_map[statistics_msg_.topic_name]); - if (abs_jitter_node > statistics_config_.jitter_tolerance_us) { - // Increment jitter outlier count - num_jitter_outliers_node_++; - RCLCPP_WARN( - node_.get_logger(), - "[NitrosStatistics Node Time]" - " Difference of time between messages(%i) and expected time between" - " messages(%i) is out of tolerance(%i) by %i for topic %s. Units are microseconds.", - microseconds_node, - statistics_config_.topic_name_expected_dt_map[statistics_msg_.topic_name], - statistics_config_.jitter_tolerance_us, - abs_jitter_node, statistics_msg_.topic_name.c_str()); - } - // Update max abs jitter - max_abs_jitter_node_ = std::max(max_abs_jitter_node_, abs_jitter_node); - jitter_queue_node_.push(abs_jitter_node); - interarrival_time_queue_node_.push(microseconds_node); - - // add and subtract weighted datapoints to prevent summation of entire queue at - // each run of this function. Also, support mean filter when the filter size - // has not reached the maximum limit of config_.filter_window_size - sum_jitter_node_ += abs_jitter_node; - sum_interarrival_time_node_ += microseconds_node; - if (static_cast(interarrival_time_queue_node_.size()) > - statistics_config_.filter_window_size) - { - sum_jitter_node_ -= jitter_queue_node_.front(); - sum_interarrival_time_node_ -= interarrival_time_queue_node_.front(); - jitter_queue_node_.pop(); - interarrival_time_queue_node_.pop(); - } + sum_jitter_node_ -= jitter_queue_node_.front(); + jitter_queue_node_.pop(); } + return error_found; + } - // Do the same checks as above, but for message timestamp - if (prev_timestamp_msg_ != std::numeric_limits::min() && - statistics_config_.enable_msg_time_statistics) + void updateMsgTimeQueue(const int64_t timestamp_diff_msg_us) + { + interarrival_time_queue_msg_.push(timestamp_diff_msg_us); + sum_interarrival_time_msg_ += timestamp_diff_msg_us; + if (static_cast(interarrival_time_queue_msg_.size()) > + diagnostics_config_.filter_window_size) { - uint64_t microseconds_msg = current_timestamp_msg_us - prev_timestamp_msg_; - // calculate difference between time between msgs(using msgtem clock) - // and expected time between msgs - int abs_jitter_msg = std::abs( - static_cast(microseconds_msg) - - statistics_config_.topic_name_expected_dt_map[statistics_msg_.topic_name]); - if (abs_jitter_msg > statistics_config_.jitter_tolerance_us) { - // Increment jitter outlier count - num_jitter_outliers_msg_++; - RCLCPP_WARN( - node_.get_logger(), - "[NitrosStatistics Message Timestamp]" - " Difference of time between messages(%lu) and expected time between" - " messages(%i) is out of tolerance(%i) by %i for topic %s. Units are microseconds.", - microseconds_msg, - statistics_config_.topic_name_expected_dt_map[statistics_msg_.topic_name], - statistics_config_.jitter_tolerance_us, - abs_jitter_msg, statistics_msg_.topic_name.c_str()); - } - // Update max abs jitter - max_abs_jitter_msg_ = std::max(max_abs_jitter_msg_, abs_jitter_msg); - jitter_queue_msg_.push(abs_jitter_msg); - interarrival_time_queue_msg_.push(microseconds_msg); - - // add and subtract weighted datapoints to prevent summation of entire queue at - // each run of this function. Also, support mean filter when the filter size - // has not reached the maximum limit of config_.filter_window_size - sum_jitter_msg_ += abs_jitter_msg; - sum_interarrival_time_msg_ += microseconds_msg; - if (static_cast(interarrival_time_queue_msg_.size()) > - statistics_config_.filter_window_size) - { - sum_jitter_msg_ -= jitter_queue_msg_.front(); - sum_interarrival_time_msg_ -= interarrival_time_queue_msg_.front(); - jitter_queue_msg_.pop(); - interarrival_time_queue_msg_.pop(); - } + sum_interarrival_time_msg_ -= interarrival_time_queue_msg_.front(); + interarrival_time_queue_msg_.pop(); } + } - if (prev_timestamp_msg_ != std::numeric_limits::min() && - statistics_config_.enable_increasing_msg_time_statistics) + bool updateMsgTimeDiagnostics(const int64_t timestamp_diff_msg_us) + { + bool error_found = false; + // calculate difference between time between msgs(using msg clock) + // and expected time between msgs + int abs_jitter_msg = + std::abs( + static_cast(timestamp_diff_msg_us) - + diagnostics_config_.topic_name_expected_dt_map[topic_name_]); + if (abs_jitter_msg > diagnostics_config_.jitter_tolerance_us) { + // Increment jitter outlier count + num_jitter_outliers_msg_++; + frames_dropped_since_last_pub_++; + prev_drop_ts_ = clock_.now(); + RCLCPP_DEBUG( + node_.get_logger(), + "[NitrosDiagnostics Message Timestamp]" + " Difference of time between messages(%lu) and expected " + "time between" + " messages(%i) is out of tolerance(%i) by %i for topic %s. " + "Units are microseconds.", + timestamp_diff_msg_us, + diagnostics_config_.topic_name_expected_dt_map[topic_name_], + diagnostics_config_.jitter_tolerance_us, + abs_jitter_msg, topic_name_.c_str()); + } + + // Update max abs jitter + max_abs_jitter_msg_ = std::max(max_abs_jitter_msg_, abs_jitter_msg); + jitter_queue_msg_.push(abs_jitter_msg); + + sum_jitter_msg_ += abs_jitter_msg; + if (static_cast(jitter_queue_msg_.size()) > + diagnostics_config_.filter_window_size) { - // Check if message timestamp is increasing - if (current_timestamp_msg_us < prev_timestamp_msg_) { - // Increment non increasing message count - num_non_increasing_msg_++; - RCLCPP_WARN( - node_.get_logger(), - "[NitrosStatistics Message Timestamp Non Increasing]" - " Message timestamp is not increasing. Current timestamp: %lu, Previous timestamp: %lu" - " for topic %s. Units are microseconds.", - current_timestamp_msg_us, prev_timestamp_msg_, statistics_msg_.topic_name.c_str()); + sum_jitter_msg_ -= jitter_queue_msg_.front(); + jitter_queue_msg_.pop(); + } + + if (prev_drop_ts_ != std::chrono::steady_clock::time_point::min()) { + auto time_since_drop = + std::chrono::duration_cast(clock_.now() - prev_drop_ts_); + if (time_since_drop.count() < kDropWarnTimeoutSeconds) { + error_found = true; + status_vec_[0].level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + frames_dropped_since_last_pub_ = 0; + update_status_message(status_vec_[0], "FRAME DROP DETECTED"); } } + return error_found; + } - prev_timestamp_node_ = current_timestamp_node; - prev_timestamp_msg_ = current_timestamp_msg_us; + bool updateIncreasingMsgTimeDiagnostics(const uint64_t current_timestamp_msg_us) + { + bool error_found = false; + // Check if message timestamp is increasing + if (current_timestamp_msg_us <= prev_timestamp_msg_us_) { + // Increment non increasing message count + num_non_increasing_msg_++; + prev_noninc_msg_ts_ = clock_.now(); + RCLCPP_WARN( + node_.get_logger(), + "[NitrosDiagnostics Message Timestamp Non Increasing]" + " Message timestamp is not increasing. Current timestamp: " + "%lu, Previous timestamp: %lu" + " for topic %s. Units are microseconds.", + current_timestamp_msg_us, prev_timestamp_msg_us_, topic_name_.c_str()); + } + if (prev_noninc_msg_ts_ != std::chrono::steady_clock::time_point::min()) { + auto time_since_noninc = + std::chrono::duration_cast(clock_.now() - prev_noninc_msg_ts_); + if (time_since_noninc.count() < kDropWarnTimeoutSeconds) { + error_found = true; + status_vec_[0].level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + frames_dropped_since_last_pub_ = 0; + update_status_message(status_vec_[0], "NONINCREASING TIMESTAMP"); + } + } + return error_found; } - // Function to publish statistics to a ROS topic - void publishNitrosStatistics() + +// Update diagnostics numbers. To be called in nitros Subscriber and Publisher + void updateDiagnostics(uint64_t msg_timestamp_ns) { // Mutex lock to prevent simultaneous access of common parameters - // used by updateStatistics() and publishNitrosStatistics() - const std::lock_guard lock(nitros_statistics_mutex_); - // publish zero until atleast one message has been received + // used by updateDiagnostics() and publishDiagnostics() + const std::lock_guard lock(nitros_diagnostics_mutex_); + // NITROS diagnostics checks message intervals both using the node clock + // and the message timestamp. + // All variables name _node refers to the node timestamp checks. + // All variables name _msg refers to the message timestamp checks. + status_vec_[0].message = ""; + bool error_found = false; + + // Get the current timestamps in microseconds + uint64_t current_timestamp_msg_us = + msg_timestamp_ns / kMicrosecondsToNanoseconds; + uint64_t current_timestamp_node_us = std::chrono::duration_cast( + clock_.now().time_since_epoch()).count(); + + // we can only calculate frame rate after 2 messages have been received + if (prev_timestamp_node_us_ != std::numeric_limits::min()) { + const int64_t timestamp_diff_node_us = current_timestamp_node_us - prev_timestamp_node_us_; + updateNodeTimeQueue(timestamp_diff_node_us); + if (diagnostics_config_.enable_node_time_diagnostics) { + error_found |= updateNodeTimeDiagnostics(timestamp_diff_node_us); + } + } + + if (prev_timestamp_msg_us_ != std::numeric_limits::min()) { + const int64_t timestamp_diff_msg_us = current_timestamp_msg_us - prev_timestamp_msg_us_; + updateMsgTimeQueue(timestamp_diff_msg_us); + // Do the same checks as above, but for message timestamp + if (diagnostics_config_.enable_msg_time_diagnostics) { + error_found |= updateMsgTimeDiagnostics(timestamp_diff_msg_us); + } + if (diagnostics_config_.enable_increasing_msg_time_diagnostics) { + error_found |= updateIncreasingMsgTimeDiagnostics(current_timestamp_msg_us); + } + } + + prev_timestamp_node_us_ = current_timestamp_node_us; + prev_timestamp_msg_us_ = current_timestamp_msg_us; + + // calculate key values for diagnsotics status if (sum_interarrival_time_node_ != 0) { - statistics_msg_.frame_rate_node = kSecondsToMicroseconds / - (static_cast(sum_interarrival_time_node_) / interarrival_time_queue_node_.size()); - statistics_msg_.mean_abs_jitter_node = sum_jitter_node_ / jitter_queue_node_.size(); - statistics_msg_.num_jitter_outliers_node = num_jitter_outliers_node_; + frame_rate_node_ = kSecondsToMicroseconds / + (static_cast(sum_interarrival_time_node_) / + interarrival_time_queue_node_.size()); + mean_abs_jitter_node_ = sum_jitter_node_ / jitter_queue_node_.size(); } else { - statistics_msg_.frame_rate_node = 0.0; - statistics_msg_.mean_abs_jitter_node = 0; - statistics_msg_.num_jitter_outliers_node = 0; + frame_rate_node_ = 0.0; + mean_abs_jitter_node_ = 0; } if (sum_interarrival_time_msg_ != 0) { - statistics_msg_.frame_rate_msg = kSecondsToMicroseconds / - (static_cast(sum_interarrival_time_msg_) / interarrival_time_queue_msg_.size()); - statistics_msg_.mean_abs_jitter_msg = sum_jitter_msg_ / jitter_queue_msg_.size(); - statistics_msg_.num_jitter_outliers_msg = num_jitter_outliers_msg_; + frame_rate_msg_ = kSecondsToMicroseconds / + (static_cast(sum_interarrival_time_msg_) / + interarrival_time_queue_msg_.size()); + mean_abs_jitter_msg_ = sum_jitter_msg_ / jitter_queue_msg_.size(); } else { - statistics_msg_.frame_rate_msg = 0.0; - statistics_msg_.mean_abs_jitter_msg = 0; - statistics_msg_.num_jitter_outliers_msg = 0; + frame_rate_msg_ = 0.0; + mean_abs_jitter_msg_ = 0; + } + // frame dropping warnings + if (!error_found) { + status_vec_[0].level = diagnostic_msgs::msg::DiagnosticStatus::OK; + status_vec_[0].message = "OK"; } - statistics_msg_.max_abs_jitter_node = max_abs_jitter_node_; - statistics_msg_.max_abs_jitter_msg = max_abs_jitter_msg_; - statistics_msg_.num_non_increasing_msg = num_non_increasing_msg_; - statistics_publisher_->publish(statistics_msg_); + outdated_msg_ = false; } - // Initialize statistics variables - void initStatistics() + // Function to publish diagnostics to a ROS topic + void publishDiagnostics() { - statistics_msg_.node_name = node_.get_name(); - statistics_msg_.node_namespace = node_.get_namespace(); - statistics_msg_.topic_name = config_.topic_name; - - // Check if expected topic name is present in topic_name_expected_dt_map - if (!statistics_config_.topic_name_expected_dt_map.count(statistics_msg_.topic_name)) { - std::stringstream error_msg; - error_msg << "[NitrosNode]" << statistics_msg_.topic_name << - " topic name not found in topics_list ROS param"; - RCLCPP_ERROR(node_.get_logger(), error_msg.str().c_str()); - throw std::runtime_error(error_msg.str().c_str()); + // Mutex lock to prevent simultaneous access of common parameters + // used by updateDiagnostics() and publishDiagnostics() + const std::lock_guard lock(nitros_diagnostics_mutex_); + + std::vector values; + // publish diagnostics stale if message has not been updated since the last call + if (outdated_msg_) { + status_vec_[0].level = diagnostic_msgs::msg::DiagnosticStatus::STALE; + status_vec_[0].message = "DIAGNOSTICS STALE"; + } else { + values.push_back( + diagnostic_msgs::build() + .key("num_non_increasing_msg") + .value(std::to_string(num_non_increasing_msg_))); + values.push_back( + diagnostic_msgs::build() + .key("num_jitter_outliers_msg") + .value(std::to_string(num_jitter_outliers_msg_))); + values.push_back( + diagnostic_msgs::build() + .key("num_jitter_outliers_node") + .value(std::to_string(num_jitter_outliers_node_))); + values.push_back( + diagnostic_msgs::build() + .key("max_abs_jitter_msg") + .value(std::to_string(max_abs_jitter_msg_))); + values.push_back( + diagnostic_msgs::build() + .key("max_abs_jitter_node") + .value(std::to_string(max_abs_jitter_node_))); + values.push_back( + diagnostic_msgs::build() + .key("mean_abs_jitter_msg") + .value(std::to_string(mean_abs_jitter_msg_))); + values.push_back( + diagnostic_msgs::build() + .key("mean_abs_jitter_node") + .value(std::to_string(mean_abs_jitter_node_))); + values.push_back( + diagnostic_msgs::build() + .key("frame_rate_msg") + .value(std::to_string(frame_rate_msg_))); + values.push_back( + diagnostic_msgs::build() + .key("frame_rate_node") + .value(std::to_string(frame_rate_node_))); + values.push_back( + diagnostic_msgs::build() + .key("total_dropped_frames") + .value(std::to_string(num_jitter_outliers_msg_))); } + status_vec_[0].values = values; + + // timestamp from std::chrono + uint64_t time = std::chrono::duration_cast( + clock_.now() - t_start_) + .count(); + uint32_t time_seconds = + time / (kSecondsToMicroseconds * kMicrosecondsToNanoseconds); + uint32_t time_ns = time - time_seconds; + + diagnostic_msgs::msg::DiagnosticArray diagnostic_msg; + std_msgs::msg::Header header; + builtin_interfaces::msg::Time timestamp; + timestamp.sec = time_seconds; + timestamp.nanosec = time_ns; + header.stamp = timestamp; + diagnostic_msg.header = header; + diagnostic_msg.status = status_vec_; + + diagnostic_publisher_->publish(diagnostic_msg); + outdated_msg_ = true; + } - // Initialize varibles to min and zero as a flag to detect no messages have been received - prev_timestamp_node_ = std::chrono::steady_clock::time_point::min(); - prev_timestamp_msg_ = std::numeric_limits::min(); + // Initialize diagnostics variables + void initDiagnostics() + { + topic_name_ = config_.topic_name; + diagnostic_msgs::msg::DiagnosticStatus topic_status; + topic_status.name = node_.get_name(); + topic_status.name.append(node_.get_namespace()); + topic_status.name.append("/"); + topic_status.name.append(config_.topic_name); + topic_status.hardware_id = nvidiaID; + topic_status.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + topic_status.message = "UNDEFINED STATE"; + status_vec_.push_back(topic_status); + frames_dropped_since_last_pub_ = 0; + + t_start_ = clock_.now(); + + // Initialize varibles to min and zero as a flag to detect no messages have + // been received + prev_drop_ts_ = std::chrono::steady_clock::time_point::min(); + prev_noninc_msg_ts_ = std::chrono::steady_clock::time_point::min(); + prev_timestamp_node_us_ = std::numeric_limits::min(); + prev_timestamp_msg_us_ = std::numeric_limits::min(); sum_interarrival_time_node_ = 0; sum_interarrival_time_msg_ = 0; sum_jitter_node_ = 0; @@ -434,17 +572,16 @@ class NitrosPublisherSubscriberBase num_jitter_outliers_node_ = 0; num_jitter_outliers_msg_ = 0; num_non_increasing_msg_ = 0; + outdated_msg_ = true; - // Initialize statistics publisher and start a timer callback to publish at a fixed rate - statistics_publisher_ = - node_.create_publisher( - "/nitros_statistics", 10); - statistics_publisher_timer_ = node_.create_wall_timer( + diagnostic_publisher_ = + node_.create_publisher( + "/diagnostics", 10); + diagnostics_publisher_timer_ = node_.create_wall_timer( std::chrono::milliseconds( - static_cast(1000 / statistics_config_.statistics_publish_rate)), - [this]() -> void { - publishNitrosStatistics(); - }); + static_cast( + 1000 / diagnostics_config_.diagnostics_publish_rate)), + [this]() -> void {publishDiagnostics();}); } protected: @@ -457,7 +594,8 @@ class NitrosPublisherSubscriberBase // Nitros type manager std::shared_ptr nitros_type_manager_; - // The info of the GXF component that's associated to this Nitros publisher/subscriber + // The info of the GXF component that's associated to this Nitros + // publisher/subscriber gxf::optimizer::ComponentInfo gxf_component_info_; // Supported data formats @@ -470,25 +608,26 @@ class NitrosPublisherSubscriberBase std::string negotiated_data_format_; // Frame ID map - std::shared_ptr> frame_id_map_ptr_; + std::shared_ptr> + frame_id_map_ptr_; // Mutex lock to prevent simultaneous access of common parameters - // used by updateStatistics() and publishNitrosStatistics() - std::mutex nitros_statistics_mutex_; + // used by updateDiagnostics() and publishDiagnostics() + std::mutex nitros_diagnostics_mutex_; - // NITROS statistics variables - // Configurations for a Nitros statistics - NitrosStatisticsConfig statistics_config_; + // NITROS diagnostics variables + // Configurations for a Nitros diagnostics + NitrosDiagnosticsConfig diagnostics_config_; - // Statistics Data publisher - rclcpp::Publisher::SharedPtr - statistics_publisher_; + rclcpp::Publisher::SharedPtr + diagnostic_publisher_; - // Satistics ROS msg - isaac_ros_nitros_interfaces::msg::TopicStatistics statistics_msg_; + // diagnostics message elements + std::vector status_vec_; // Clock object used to retrived current timestamps std::chrono::steady_clock clock_; + std::chrono::steady_clock::time_point t_start_; // Queue to store time between messages to implement windowed mean filter std::queue interarrival_time_queue_node_; @@ -496,12 +635,14 @@ class NitrosPublisherSubscriberBase // Queue to store message jitter to implement windowed mean filter // Jitter is the difference between the time between msgs(dt) - // calculated from fps specified in NITROS statistics ROS param + // calculated from fps specified in NITROS diagnostics ROS param // and measured using node clock std::queue jitter_queue_node_; std::queue jitter_queue_msg_; - // Sum of the message interarrival times received on this topic within the configured window + + // Sum of the message interarrival times received on this topic within the + // configured window int64_t sum_interarrival_time_node_; uint64_t sum_interarrival_time_msg_; @@ -520,14 +661,33 @@ class NitrosPublisherSubscriberBase // Number of non-increasing messages uint64_t num_non_increasing_msg_; + // Number of dropped frames without error warnings + // idk if we need a full 64 bit integer here? + uint64_t frames_dropped_since_last_pub_; + // Prev timestamp stored for calculating frame rate // Prev node timstamp - std::chrono::time_point prev_timestamp_node_; + std::chrono::time_point prev_drop_ts_, prev_noninc_msg_ts_; // Prev message timestamp in microseconds - uint64_t prev_timestamp_msg_; + uint64_t prev_timestamp_msg_us_, prev_timestamp_node_us_; + + // NITROS diagnostics publisher timer + rclcpp::TimerBase::SharedPtr diagnostics_publisher_timer_; + + // data tracking variables for diagnostics + std::string topic_name_; + double frame_rate_node_, frame_rate_msg_; + int32_t mean_abs_jitter_node_, mean_abs_jitter_msg_; + bool outdated_msg_; - // NITROS statistics publisher timer - rclcpp::TimerBase::SharedPtr statistics_publisher_timer_; + void update_status_message(diagnostic_msgs::msg::DiagnosticStatus & status, std::string update) + { + if (status.message.empty()) { + status.message = update; + } else { + status.message.append(", ").append(update); + } + } }; } // namespace nitros diff --git a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher_subscriber_group.hpp b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher_subscriber_group.hpp index 751afea..04e1a0b 100644 --- a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher_subscriber_group.hpp +++ b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_publisher_subscriber_group.hpp @@ -53,7 +53,7 @@ class NitrosPublisherSubscriberGroup const gxf::optimizer::GraphIOGroupSupportedDataTypesInfo & gxf_io_supported_data_formats_info, const NitrosPublisherSubscriberConfigMap & nitros_pub_sub_configs, const std::shared_ptr> frame_id_map_ptr, - const NitrosStatisticsConfig & statistics_config); + const NitrosDiagnosticsConfig & diagnostics_config); // Find the corresponding Nitros publisher of the given component std::shared_ptr findNitrosPublisher( @@ -172,8 +172,8 @@ class NitrosPublisherSubscriberGroup // Frame ID map std::shared_ptr> frame_id_map_ptr_; - // Configurations for a Nitros statistics - NitrosStatisticsConfig statistics_config_; + // Configurations for a Nitros diagnostics + NitrosDiagnosticsConfig diagnostics_config_; }; diff --git a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_subscriber.hpp b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_subscriber.hpp index a02fac0..9c7a1f3 100644 --- a/isaac_ros_nitros/include/isaac_ros_nitros/nitros_subscriber.hpp +++ b/isaac_ros_nitros/include/isaac_ros_nitros/nitros_subscriber.hpp @@ -52,7 +52,7 @@ class NitrosSubscriber : public NitrosPublisherSubscriberBase const gxf::optimizer::ComponentInfo & gxf_component_info, const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config, - const NitrosStatisticsConfig & statistics_config, + const NitrosDiagnosticsConfig & diagnostics_config, const bool use_callback_group = false); NitrosSubscriber( @@ -70,7 +70,7 @@ class NitrosSubscriber : public NitrosPublisherSubscriberBase std::shared_ptr nitros_type_manager, const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config, - const NitrosStatisticsConfig & statistics_config); + const NitrosDiagnosticsConfig & diagnostics_config); // Getter for the negotiated_sub_ std::shared_ptr getNegotiatedSubscriber(); @@ -94,6 +94,12 @@ class NitrosSubscriber : public NitrosPublisherSubscriberBase // Set the gxf_receiver_ptr_ pointing to a receiver component in the running graph void setReceiverPointer(void * gxf_receiver_ptr); + // Set the frame drop policy for the underlying GXF receiver + void setReceiverPolicy(const size_t policy); + + // Set the capacity for the underlying GXF receiver + void setReceiverCapacity(const size_t capacity); + // Push an entity into the corresponding receiver in the underlying graph bool pushEntity(const int64_t eid, bool should_block = false); diff --git a/isaac_ros_nitros/include/isaac_ros_nitros/types/type_utility.hpp b/isaac_ros_nitros/include/isaac_ros_nitros/types/type_utility.hpp index 6e462d4..a71fd87 100644 --- a/isaac_ros_nitros/include/isaac_ros_nitros/types/type_utility.hpp +++ b/isaac_ros_nitros/include/isaac_ros_nitros/types/type_utility.hpp @@ -20,7 +20,7 @@ #include #if defined(USE_NVTX) - #include "nvToolsExt.h" + #include #endif namespace nvidia diff --git a/isaac_ros_nitros/lib/cuapriltags/lib_x86_64_cuda_11_8/libcuapriltags.a b/isaac_ros_nitros/lib/cuapriltags/lib_x86_64_cuda_11_8/libcuapriltags.a deleted file mode 100644 index 0bd3361..0000000 --- a/isaac_ros_nitros/lib/cuapriltags/lib_x86_64_cuda_11_8/libcuapriltags.a +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:09d6a0047fb2f5abb456ab02a100057eaab6184831d94a4a0fa008630d877e60 -size 1571582 diff --git a/isaac_ros_nitros/lib/cuvslam/.gitattributes b/isaac_ros_nitros/lib/cuvslam/.gitattributes new file mode 100644 index 0000000..a8d3eed --- /dev/null +++ b/isaac_ros_nitros/lib/cuvslam/.gitattributes @@ -0,0 +1,2 @@ +# Binaries +cuvslam_api_launcher filter=lfs diff=lfs merge=lfs -text diff --git a/isaac_ros_nitros/lib/cuvslam/include/cuvslam.h b/isaac_ros_nitros/lib/cuvslam/include/cuvslam.h index 408610c..0bf8dee 100644 --- a/isaac_ros_nitros/lib/cuvslam/include/cuvslam.h +++ b/isaac_ros_nitros/lib/cuvslam/include/cuvslam.h @@ -1,19 +1,13 @@ -// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// SPDX-License-Identifier: Apache-2.0 +/** + * @file cuvslam.h + + * @copyright Copyright (c) 2023, NVIDIA CORPORATION. All rights reserved.\n\n + * NVIDIA CORPORATION and its licensors retain all intellectual property + * and proprietary rights in and to this software, related documentation + * and any modifications thereto. Any use, reproduction, disclosure or + * distribution of this software and related documentation without an express + * license agreement from NVIDIA CORPORATION is strictly prohibited. + */ #pragma once @@ -49,7 +43,7 @@ extern "C" { #define CUVSLAM_API_VERSION_MAJOR 12 /// Minor version -#define CUVSLAM_API_VERSION_MINOR 2 +#define CUVSLAM_API_VERSION_MINOR 6 /** * @name Error codes @@ -232,6 +226,26 @@ struct CUVSLAM_CameraRig { int32_t num_cameras; ///< number of cameras (should be 2 for stereo) }; +/** +* Localization settings +*/ +struct CUVSLAM_LocalizationSettings { + float horizontal_search_radius; ///< horizontal search radius in meters + float vertical_search_radius; ///< vertical search radius in meters + + float horizontal_step; ///< horizontal step in meters + float vertical_step; ///< vertical step in meters + float angular_step_rads; ///< angular step around vertical axis in radians +}; + + /** + * List of cameras available for SLAM + */ + struct CUVSLAM_SlamCameras { + uint32_t num; ///< number of filled elements in camera list + int32_t* camera_list; ///< cameras + }; + /** * Configuration parameters that affect the whole tracking session */ @@ -290,6 +304,9 @@ struct CUVSLAM_Configuration { */ int32_t slam_sync_mode; + // List of cameras available for SLAM + struct CUVSLAM_SlamCameras slam_cameras; + /** * Enable reading internal data from SLAM * CUVSLAM_EnableReadingDataLayer(), CUVSLAM_DisableReadingDataLayer() @@ -353,12 +370,25 @@ struct CUVSLAM_Configuration { */ int32_t slam_max_map_size; + /** Minimum time interval between loop closure events. + * 1000 is suitable for real-time mapping. + * Requirements: + * enable_localization_n_mapping = true + * Default is 0 + */ + uint64_t slam_throttling_time_ms; + /** * Multicamera mode: moderate (0), performance (1) or precision (2). * Multicamera odometry settings will be adjusted depending on a chosen strategy. * Default is moderate (0). */ int32_t multicam_mode; + + /** + * Localization Settings + */ + struct CUVSLAM_LocalizationSettings localization_settings; }; /** @@ -381,7 +411,7 @@ struct CUVSLAM_Image { int32_t height; ///< image height must match what was provided in CUVSLAM_Camera int32_t camera_index; ///< index of the camera in the rig int32_t pitch; ///< bytes per image row including padding for GPU memory images - enum CUVSLAM_ImageEncoding image_encoding; ///< + enum CUVSLAM_ImageEncoding image_encoding; ///< grayscale (8 bit) and RGB (8 bit) are supported now }; /** @@ -559,6 +589,22 @@ struct CUVSLAM_PoseStamped { struct CUVSLAM_Pose pose; ///< }; +/** Pose graph nodes */ +struct CUVSLAM_PoseGraphNodeVector +{ + uint32_t num; ///< number of filled elements in array + uint32_t max; ///< size of pre-allocated array + struct CUVSLAM_PoseStamped *nodes; ///< nodes array +}; + +/** Pose graph edges */ +struct CUVSLAM_PoseGraphEdgeVector +{ + uint32_t num; ///< number of filled elements in array + uint32_t max; ///< size of pre-allocated array + struct CUVSLAM_PoseGraphEdge* edges;///< edges array +}; + /** * Asynchronous response for CUVSLAM_SaveToSlamDb() * @param[in] response_context - context @@ -614,6 +660,12 @@ void CUVSLAM_WarmUpGPU(); CUVSLAM_API void CUVSLAM_InitDefaultConfiguration(struct CUVSLAM_Configuration *cfg); +/** + * Get the default configuration + */ +CUVSLAM_API +struct CUVSLAM_Configuration CUVSLAM_GetDefaultConfiguration(); + /** * Use this to initialize cuVSLAM * CUVSLAM_TrackerHandle will remember number of cameras @@ -742,7 +794,7 @@ CUVSLAM_Status CUVSLAM_SetSlamPose(CUVSLAM_TrackerHandle tracker, const struct C * enable_localization_n_mapping = true */ CUVSLAM_API -uint32_t CUVSLAM_GetAllSLAMPoses(CUVSLAM_TrackerHandle tracker, uint32_t max_poses_stamped_count, +uint32_t CUVSLAM_GetAllSlamPoses(CUVSLAM_TrackerHandle tracker, uint32_t max_poses_stamped_count, struct CUVSLAM_PoseStamped *poses_stamped); /** @@ -781,7 +833,7 @@ CUVSLAM_Status CUVSLAM_SaveToSlamDb(CUVSLAM_TrackerHandle tracker, const char *f */ CUVSLAM_API CUVSLAM_Status CUVSLAM_LocalizeInExistDb(CUVSLAM_TrackerHandle tracker, const char *folder_name, - const struct CUVSLAM_Pose *guess_pose, float radius CUVSLAM_DEFAULT(0), + const struct CUVSLAM_Pose *guess_pose, const struct CUVSLAM_Image *images CUVSLAM_DEFAULT(nullptr), size_t images_size CUVSLAM_DEFAULT(2), CUVSLAM_LocalizeInExistDbResponse response CUVSLAM_DEFAULT(nullptr), @@ -815,6 +867,21 @@ CUVSLAM_Status CUVSLAM_GetLastLandmarks(CUVSLAM_TrackerHandle tracker, struct CU CUVSLAM_API CUVSLAM_Status CUVSLAM_GetLastGravity(CUVSLAM_TrackerHandle tracker, struct CUVSLAM_Gravity *gravity); +/** + * Get pose graph. + * [DEPRECATED] use CUVSLAM_StartReadingPoseGraph/CUVSLAM_FinishReadingPoseGraph instead. + * This function should not be used except on recordings after the replay. + * It additionally returns timestamps for graph nodes. + * @param[in] tracker tracker handle + * @param[out] nodes pose graph nodes array + * @param[out] edges pose graph edges array + * @return result status (error code) + */ +CUVSLAM_API +CUVSLAM_Status CUVSLAM_GetPoseGraph(CUVSLAM_TrackerHandle tracker, + struct CUVSLAM_PoseGraphNodeVector *nodes, + struct CUVSLAM_PoseGraphEdgeVector *edges); + /** * Get slam metrics * @param[in] tracker tracker handle diff --git a/isaac_ros_nitros/lib/cuvslam/include/debug_dump.h b/isaac_ros_nitros/lib/cuvslam/include/debug_dump.h index b658148..9297978 100644 --- a/isaac_ros_nitros/lib/cuvslam/include/debug_dump.h +++ b/isaac_ros_nitros/lib/cuvslam/include/debug_dump.h @@ -1,19 +1,3 @@ -// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// SPDX-License-Identifier: Apache-2.0 #pragma once #include "cuvslam.h" diff --git a/isaac_ros_nitros/lib/cuvslam/include/ground_constraint.h b/isaac_ros_nitros/lib/cuvslam/include/ground_constraint.h index db92003..8fa2f7b 100644 --- a/isaac_ros_nitros/lib/cuvslam/include/ground_constraint.h +++ b/isaac_ros_nitros/lib/cuvslam/include/ground_constraint.h @@ -1,19 +1,13 @@ -// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// SPDX-License-Identifier: Apache-2.0 +/** + * @file ground_constraint.h + + * @copyright Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved.\n\n + * NVIDIA CORPORATION and its licensors retain all intellectual property + * and proprietary rights in and to this software, related documentation + * and any modifications thereto. Any use, reproduction, disclosure or + * distribution of this software and related documentation without an express + * license agreement from NVIDIA CORPORATION is strictly prohibited. + */ #pragma once #include "cuvslam.h" diff --git a/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack60/libcuvslam.so b/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack60/libcuvslam.so deleted file mode 100755 index b55621b..0000000 --- a/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack60/libcuvslam.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:7f248ede1d5fc8f3c309c8953164a30bce8dde76eadf47bc1460b03f4ef9c19e -size 4548632 diff --git a/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack61/cuvslam_api_launcher b/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack61/cuvslam_api_launcher new file mode 100755 index 0000000..0623305 --- /dev/null +++ b/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack61/cuvslam_api_launcher @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a0d88d4e3447d8b085c68cb77b512c330605f4b0a9faba05283d2fdf5d2ffffb +size 391312 diff --git a/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack61/libcuvslam.so b/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack61/libcuvslam.so new file mode 100755 index 0000000..ff1cc3f --- /dev/null +++ b/isaac_ros_nitros/lib/cuvslam/lib_aarch64_jetpack61/libcuvslam.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:b57afc3c01b9a0e8bb0d3502102cbae2616fb5fd7000b452add43b2030172e27 +size 4689136 diff --git a/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_2/libcuvslam.so b/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_2/libcuvslam.so deleted file mode 100755 index 6f5088c..0000000 --- a/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_2/libcuvslam.so +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f2a75d3e2ad6cbf4ef7db0cd4ef884209c4c1764a91fe0267407fbe8230e454a -size 5093520 diff --git a/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_6/cuvslam_api_launcher b/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_6/cuvslam_api_launcher new file mode 100755 index 0000000..0d6034c --- /dev/null +++ b/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_6/cuvslam_api_launcher @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ebad5e501a66ba6afe1e2a827358aac2a09689615044c4bec94e2fe57fbb50bc +size 457072 diff --git a/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_6/libcuvslam.so b/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_6/libcuvslam.so new file mode 100755 index 0000000..814aa38 --- /dev/null +++ b/isaac_ros_nitros/lib/cuvslam/lib_x86_64_cuda_12_6/libcuvslam.so @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:32d28fec3d89e1a90a71dbd1b2b93cf96eb0d7a23dc5dbf29cbf710d0bf898a1 +size 5213520 diff --git a/isaac_ros_nitros/package.xml b/isaac_ros_nitros/package.xml index d3ee1d3..b9dea95 100644 --- a/isaac_ros_nitros/package.xml +++ b/isaac_ros_nitros/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros - 3.1.0 + 3.2.0 Isaac ROS Nitros Isaac ROS Maintainers @@ -28,7 +28,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. rclcpp rclcpp_components std_msgs - isaac_ros_nitros_interfaces + diagnostic_msgs isaac_ros_gxf gxf_isaac_optimizer gxf_isaac_message_compositor diff --git a/isaac_ros_nitros/scripts/diagnostic_viewer.py b/isaac_ros_nitros/scripts/diagnostic_viewer.py new file mode 100644 index 0000000..2702a93 --- /dev/null +++ b/isaac_ros_nitros/scripts/diagnostic_viewer.py @@ -0,0 +1,189 @@ +#!/usr/bin/env python3 + +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import curses +import threading +import time + +from diagnostic_msgs.msg import DiagnosticArray +import rclpy +from rclpy.node import Node + + +""" +Utility for viewing the nitros diagnostics in a terminal interface. + +You can either use diagnostics that are built into applications, for example the +isaac_ros_data_recorder, or you can export ENABLE_GLOBAL_DIAGNOSTICS=1 and view much more +""" + + +class DiagnosticsDisplay(Node): + + def __init__(self): + super().__init__('diagnostics_display') + self.subscription = self.create_subscription( + DiagnosticArray, + '/diagnostics', + self.listener_callback, + 10) + self.subscription + + # Thread-safe storage for diagnostic data + self.data_lock = threading.Lock() + self.status_data = {} + + def listener_callback(self, msg): + with self.data_lock: + for status in msg.status: + self.status_data[status.name] = status + + +def curses_main(stdscr, node): + stdscr.nodelay(True) + curses.curs_set(0) + stdscr.keypad(True) # Enable keypad mode to capture special keys + + start_idx = 0 + key = -1 + + while rclpy.ok(): + stdscr.clear() + # Get terminal dimensions + height, width = stdscr.getmaxyx() + + MAX_NAME_WIDTH = 100 + FRAME_RATE_WIDTH = 15 + + # Adjust column widths if terminal is too narrow + total_width_needed = MAX_NAME_WIDTH + 2 * FRAME_RATE_WIDTH + 2 # +2 for spaces + if total_width_needed > width: + # Reduce the widths proportionally + scaling_factor = width / total_width_needed + MAX_NAME_WIDTH = int(MAX_NAME_WIDTH * scaling_factor) + FRAME_RATE_WIDTH = int(FRAME_RATE_WIDTH * scaling_factor) + + header = (f"{'Topic Name':<{MAX_NAME_WIDTH}} {'frame_rate_msg':<{FRAME_RATE_WIDTH}}" + f"{'frame_rate_node':<{FRAME_RATE_WIDTH}}") + separator = '-' * min(width, MAX_NAME_WIDTH + 2 * FRAME_RATE_WIDTH + 2) + + try: + stdscr.addstr(0, 0, header[:width - 1]) + stdscr.addstr(1, 0, separator) + except curses.error: + pass # Ignore if cannot write header (terminal too small) + + with node.data_lock: + status_list = list(node.status_data.values()) + + # Handle key presses + try: + key = stdscr.getch() + except Exception: + key = -1 + + # Up and down arrow keys to scroll + if key == curses.KEY_UP: + start_idx = max(0, start_idx - 1) + elif key == curses.KEY_DOWN: + start_idx = min(len(status_list) - (height - 5), start_idx + 1) + elif key == curses.KEY_PPAGE: # Page Up + start_idx = max(0, start_idx - (height - 5)) + elif key == curses.KEY_NPAGE: # Page Down + start_idx = min(len(status_list) - (height - 5), start_idx + (height - 5)) + elif key == ord('q') or key == ord('Q'): # Quit on 'q' or 'Q' + break + + # Ensure start_idx is within valid range + if start_idx < 0: + start_idx = 0 + max_start_idx = max(0, len(status_list) - (height - 5)) + if start_idx > max_start_idx: + start_idx = max_start_idx + + visible_height = height - 5 # Adjusted for header, footer, and indicators + + visible_status_list = status_list[start_idx:start_idx + visible_height] + + for idx, status in enumerate(visible_status_list): + name = status.name + frame_rate_msg = '' + frame_rate_node = '' + # Extract frame rates from key-value pairs + for kv in status.values: + if kv.key == 'frame_rate_msg': + frame_rate_msg = kv.value + if kv.key == 'frame_rate_node': + frame_rate_node = kv.value + + # No need to truncate the name since MAX_NAME_WIDTH is large + name_display = name.ljust(MAX_NAME_WIDTH) + + # Format the data + frame_rate_msg_display = frame_rate_msg.ljust(FRAME_RATE_WIDTH) + frame_rate_node_display = frame_rate_node.ljust(FRAME_RATE_WIDTH) + line = f'{name_display} {frame_rate_msg_display} {frame_rate_node_display}' + + # Truncate the line if necessary + line = line[:width - 1] # Reserve last character for cursor + + try: + stdscr.addstr(idx + 2, 0, line) + except curses.error: + pass # Ignore if cannot write line (terminal too small) + + # Add indicators if there's more data above or below + try: + if start_idx > 0: + stdscr.addstr(2, width - 2, '↑') + if start_idx + visible_height < len(status_list): + stdscr.addstr(height - 3, width - 2, '↓') + except curses.error: + pass + + # Add a footer with status information + status_line = (f'Showing {start_idx + 1} - {start_idx + len(visible_status_list)} of ' + f'{len(status_list)} topics. Press "q" to quit.') + + try: + stdscr.addstr(height - 2, 0, status_line[:width - 1]) + except curses.error: + pass + + stdscr.refresh() + time.sleep(0.1) + + +def main(args=None): + rclpy.init(args=args) + node = DiagnosticsDisplay() + + try: + thread = threading.Thread(target=rclpy.spin, args=(node,), daemon=True) + thread.start() + curses.wrapper(curses_main, node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/isaac_ros_nitros/src/nitros_context.cpp b/isaac_ros_nitros/src/nitros_context.cpp index a6b87d0..953bc9f 100644 --- a/isaac_ros_nitros/src/nitros_context.cpp +++ b/isaac_ros_nitros/src/nitros_context.cpp @@ -37,6 +37,7 @@ namespace nitros { constexpr uint64_t kDefaultCUDAMemoryPoolSize = 2048ULL * 1024 * 1024; +constexpr char kDisableCUDAMemPoolEnv[] = "DISABLE_NITROS_CUDA_MEM_POOL"; gxf_context_t NitrosContext::main_context_ = nullptr; gxf_context_t NitrosContext::shared_context_ = nullptr; @@ -76,6 +77,19 @@ std::vector ToCStringArray(const std::vector & strings) return cstrings; } +bool IsCUDAMemPoolDisabledFromEnv(const char * env_name) +{ + const char * disable_cuda_mem_pool_env = std::getenv(env_name); + bool disable_cuda_mem_pool = false; + if (disable_cuda_mem_pool_env != nullptr) { + auto disable_cuda_mem_pool_str = std::string(disable_cuda_mem_pool_env); + if (disable_cuda_mem_pool_str == "1" || disable_cuda_mem_pool_str == "true") { + disable_cuda_mem_pool = true; + } + } + return disable_cuda_mem_pool; +} + NitrosContext::NitrosContext() { // Mutex: shared_context_mutex_ @@ -96,6 +110,16 @@ NitrosContext::NitrosContext() "[NitrosContext] GxfGetSharedContext Error: %s", GxfResultStr(code)); return; } + if (!IsCUDAMemPoolDisabledFromEnv(kDisableCUDAMemPoolEnv)) { + RCLCPP_DEBUG(get_logger(), "[NitrosContext] CUDA Memory Pool is enabled"); + code = setCUDAMemoryPoolSize(kDefaultCUDAMemoryPoolSize); + if (code != GXF_SUCCESS) { + RCLCPP_ERROR( + get_logger(), + "[NitrosContext] setCUDAMemoryPoolSize Error: %s", GxfResultStr(code)); + return; + } + } } code = GxfContextCreateShared(NitrosContext::shared_context_, &context_); @@ -171,14 +195,6 @@ gxf_result_t NitrosContext::getComponentPointer( return code; } - code = setCUDAMemoryPoolSize(kDefaultCUDAMemoryPoolSize); - if (code != GXF_SUCCESS) { - RCLCPP_ERROR( - get_logger(), - "[NitrosContext] setCUDAMemoryPoolSize Error: %s", GxfResultStr(code)); - return code; - } - return GXF_SUCCESS; // End Mutex: shared_context_mutex_ } diff --git a/isaac_ros_nitros/src/nitros_node.cpp b/isaac_ros_nitros/src/nitros_node.cpp index e484ba2..468f44c 100644 --- a/isaac_ros_nitros/src/nitros_node.cpp +++ b/isaac_ros_nitros/src/nitros_node.cpp @@ -209,33 +209,53 @@ NitrosNode::NitrosNode( nitros_context_ptr_->setNode(this); // Create an NITROS type manager for the node - statistics_config_ = std::make_shared(); - - // Setup ROS parameters for NITROS statistics - statistics_config_->enable_node_time_statistics = declare_parameter( - "enable_node_time_statistics", false); - statistics_config_->enable_msg_time_statistics = declare_parameter( - "enable_msg_time_statistics", false); - statistics_config_->enable_increasing_msg_time_statistics = declare_parameter( - "enable_increasing_msg_time_statistics", false); - statistics_config_->enable_all_statistics = declare_parameter( - "enable_all_statistics", false); - if (statistics_config_->enable_all_statistics) { - this->set_parameter(rclcpp::Parameter("enable_node_time_statistics", true)); - this->set_parameter(rclcpp::Parameter("enable_msg_time_statistics", true)); - this->set_parameter(rclcpp::Parameter("enable_increasing_msg_time_statistics", true)); - } - if (statistics_config_->enable_node_time_statistics || - statistics_config_->enable_msg_time_statistics || - statistics_config_->enable_increasing_msg_time_statistics) + diagnostics_config_ = std::make_shared(); + + // Setup ROS parameters for NITROS diagnostics + diagnostics_config_->enable_node_time_diagnostics = declare_parameter( + "enable_node_time_diagnostics", false); + diagnostics_config_->enable_msg_time_diagnostics = declare_parameter( + "enable_msg_time_diagnostics", false); + diagnostics_config_->enable_increasing_msg_time_diagnostics = declare_parameter( + "enable_increasing_msg_time_diagnostics", false); + diagnostics_config_->enable_all_diagnostics = declare_parameter( + "enable_all_diagnostics", false); + if (diagnostics_config_->enable_all_diagnostics) { + diagnostics_config_->enable_node_time_diagnostics = true; + diagnostics_config_->enable_msg_time_diagnostics = true; + diagnostics_config_->enable_increasing_msg_time_diagnostics = true; + } + + const char * enable_global_diagnostics = std::getenv("ENABLE_GLOBAL_NITROS_DIAGNOSTICS"); + std::string global_env_value; + + if (enable_global_diagnostics != nullptr) { + global_env_value = std::string(enable_global_diagnostics); + } else { + global_env_value = ""; + } + + if (global_env_value == "True" || + global_env_value == "TRUE" || + global_env_value == "true" || + global_env_value == "1") { - statistics_config_->enable_statistics = true; - statistics_config_->statistics_publish_rate = declare_parameter( - "statistics_publish_rate", + diagnostics_config_->enable_all_topic_diagnostics = true; + } + + if ( + diagnostics_config_->enable_all_topic_diagnostics || + diagnostics_config_->enable_node_time_diagnostics || + diagnostics_config_->enable_msg_time_diagnostics || + diagnostics_config_->enable_increasing_msg_time_diagnostics) + { + diagnostics_config_->enable_diagnostics = true; + diagnostics_config_->diagnostics_publish_rate = declare_parameter( + "diagnostics_publish_rate", 1.0); - statistics_config_->filter_window_size = + diagnostics_config_->filter_window_size = declare_parameter("filter_window_size", 100); - statistics_config_->jitter_tolerance_us = + diagnostics_config_->jitter_tolerance_us = declare_parameter("jitter_tolerance_us", 5000.0); // List of expected topic names std::vector topics_name_list = @@ -253,7 +273,7 @@ NitrosNode::NitrosNode( } // Populate the topic_name -> expected time difference for (size_t i = 0; i < topics_name_list.size(); i++) { - statistics_config_->topic_name_expected_dt_map[topics_name_list[i]] = 1000000 / + diagnostics_config_->topic_name_expected_dt_map[topics_name_list[i]] = 1000000 / expected_fps_list[i]; } } @@ -515,7 +535,7 @@ void NitrosNode::startNitrosNode() nitros_pub_sub_groups_.emplace_back( std::make_shared( *this, nitros_context_ptr_->getContext(), - nitros_type_manager_, gxf_io_group, config_map_, frame_id_map_ptr_, *statistics_config_)); + nitros_type_manager_, gxf_io_group, config_map_, frame_id_map_ptr_, *diagnostics_config_)); } // Start negotiation @@ -615,8 +635,16 @@ void NitrosNode::postNegotiationCallback() RCLCPP_ERROR(get_logger(), error_msg.str().c_str()); throw std::runtime_error(error_msg.str().c_str()); } + RCLCPP_DEBUG( + get_logger(), + "[NitrosNode] Setting up a subscriber's underyling receiver (pointer=%p)", pointer); sub_ptr->setReceiverPointer(pointer); - RCLCPP_DEBUG(get_logger(), "[NitrosNode] Setting a subscriber's pointer: %p", pointer); + sub_ptr->setReceiverPolicy(0); + const std::string topic_qos_parameter_name = sub_ptr->getConfig().topic_name + "_qos_depth"; + const int custom_sub_qos_depth = get_parameter(topic_qos_parameter_name).as_int(); + if (custom_sub_qos_depth > 0) { + sub_ptr->setReceiverCapacity(custom_sub_qos_depth); + } if (heartbeat_eid_ == -1) { nitros_context_ptr_->getEid(comp_info.entity_name, heartbeat_eid_); } diff --git a/isaac_ros_nitros/src/nitros_publisher.cpp b/isaac_ros_nitros/src/nitros_publisher.cpp index dd75e24..70e2782 100644 --- a/isaac_ros_nitros/src/nitros_publisher.cpp +++ b/isaac_ros_nitros/src/nitros_publisher.cpp @@ -176,20 +176,20 @@ NitrosPublisher::NitrosPublisher( const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config, const negotiated::NegotiatedPublisherOptions & negotiated_pub_options, - const NitrosStatisticsConfig & statistics_config) + const NitrosDiagnosticsConfig & diagnostics_config) : NitrosPublisher( node, context, nitros_type_manager, gxf_component_info, supported_data_formats, config, negotiated_pub_options) { - statistics_config_ = statistics_config; + diagnostics_config_ = diagnostics_config; - if (statistics_config_.enable_statistics && - statistics_config_.topic_name_expected_dt_map.find(config_.topic_name) != - statistics_config_.topic_name_expected_dt_map.end()) + if (diagnostics_config_.enable_all_topic_diagnostics || + (diagnostics_config_.enable_diagnostics && + diagnostics_config_.topic_name_expected_dt_map.find(config_.topic_name) != + diagnostics_config_.topic_name_expected_dt_map.end())) { // Initialize statistics variables and message fields - statistics_msg_.is_subscriber = false; - initStatistics(); + initDiagnostics(); } } @@ -199,10 +199,10 @@ NitrosPublisher::NitrosPublisher( std::shared_ptr nitros_type_manager, const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config, - const NitrosStatisticsConfig & statistics_config) + const NitrosDiagnosticsConfig & diagnostics_config) : NitrosPublisher( node, context, nitros_type_manager, {}, supported_data_formats, config, - {}, statistics_config) + {}, diagnostics_config) {} std::shared_ptr NitrosPublisher::getNegotiatedPublisher() @@ -552,11 +552,12 @@ void NitrosPublisher::publish(NitrosTypeBase & base_msg) base_msg); } - if (statistics_config_.enable_statistics && - statistics_config_.topic_name_expected_dt_map.find(config_.topic_name) != - statistics_config_.topic_name_expected_dt_map.end()) + if (diagnostics_config_.enable_all_topic_diagnostics || + (diagnostics_config_.enable_diagnostics && + diagnostics_config_.topic_name_expected_dt_map.find(config_.topic_name) != + diagnostics_config_.topic_name_expected_dt_map.end())) { - updateStatistics(getTimestamp(base_msg)); + updateDiagnostics(getTimestamp(base_msg)); } nvtxRangePopWrapper(); diff --git a/isaac_ros_nitros/src/nitros_publisher_subscriber_group.cpp b/isaac_ros_nitros/src/nitros_publisher_subscriber_group.cpp index 1bdada9..46d1817 100644 --- a/isaac_ros_nitros/src/nitros_publisher_subscriber_group.cpp +++ b/isaac_ros_nitros/src/nitros_publisher_subscriber_group.cpp @@ -37,14 +37,14 @@ NitrosPublisherSubscriberGroup::NitrosPublisherSubscriberGroup( const gxf::optimizer::GraphIOGroupSupportedDataTypesInfo & gxf_io_supported_data_formats_info, const NitrosPublisherSubscriberConfigMap & nitros_pub_sub_configs, const std::shared_ptr> frame_id_map_ptr, - const NitrosStatisticsConfig & statistics_config) + const NitrosDiagnosticsConfig & diagnostics_config) : node_(node), context_(context), nitros_type_manager_(nitros_type_manager), gxf_io_supported_data_formats_info_(gxf_io_supported_data_formats_info), nitros_pub_sub_configs_(nitros_pub_sub_configs), frame_id_map_ptr_(frame_id_map_ptr), - statistics_config_(statistics_config) + diagnostics_config_(diagnostics_config) { // Expand data formats if all ports in this IO group support "any" data formats expandAnyDataFormats(); @@ -368,7 +368,7 @@ void NitrosPublisherSubscriberGroup::createNitrosSubscribers() ingress_comp_info, supported_data_formats, component_config, - statistics_config_, + diagnostics_config_, true); nitros_sub->setFrameIdMap(frame_id_map_ptr_); @@ -427,7 +427,7 @@ void NitrosPublisherSubscriberGroup::createNitrosPublishers() supported_data_formats, component_config, negotiated_pub_options, - statistics_config_); + diagnostics_config_); nitros_pub->setFrameIdMap(frame_id_map_ptr_); diff --git a/isaac_ros_nitros/src/nitros_subscriber.cpp b/isaac_ros_nitros/src/nitros_subscriber.cpp index cbae7bd..d1f99ca 100644 --- a/isaac_ros_nitros/src/nitros_subscriber.cpp +++ b/isaac_ros_nitros/src/nitros_subscriber.cpp @@ -41,7 +41,7 @@ NitrosSubscriber::NitrosSubscriber( const gxf::optimizer::ComponentInfo & gxf_component_info, const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config, - const NitrosStatisticsConfig & statistics_config, + const NitrosDiagnosticsConfig & diagnostics_config, const bool use_callback_group) : NitrosPublisherSubscriberBase( node, context, nitros_type_manager, gxf_component_info, supported_data_formats, config), @@ -51,14 +51,14 @@ NitrosSubscriber::NitrosSubscriber( return; } - statistics_config_ = statistics_config; - if (statistics_config_.enable_statistics && - statistics_config_.topic_name_expected_dt_map.find(config_.topic_name) != - statistics_config_.topic_name_expected_dt_map.end()) + diagnostics_config_ = diagnostics_config; + if (diagnostics_config_.enable_all_topic_diagnostics || + (diagnostics_config_.enable_diagnostics && + diagnostics_config_.topic_name_expected_dt_map.find(config_.topic_name) != + diagnostics_config_.topic_name_expected_dt_map.end())) { - // Initialize statistics variables and message fields - statistics_msg_.is_subscriber = true; - initStatistics(); + // Initialize diagnostics variables and message fields + initDiagnostics(); } if (use_callback_group_) { @@ -111,9 +111,9 @@ NitrosSubscriber::NitrosSubscriber( std::shared_ptr nitros_type_manager, const std::vector & supported_data_formats, const NitrosPublisherSubscriberConfig & config, - const NitrosStatisticsConfig & statistics_config) + const NitrosDiagnosticsConfig & diagnostics_config) : NitrosSubscriber( - node, context, nitros_type_manager, {}, supported_data_formats, config, statistics_config) + node, context, nitros_type_manager, {}, supported_data_formats, config, diagnostics_config) { use_gxf_receiver_ = false; } @@ -279,6 +279,61 @@ void NitrosSubscriber::setReceiverPointer(void * gxf_receiver_ptr) gxf_receiver_ptr_ = reinterpret_cast(gxf_receiver_ptr); } +void NitrosSubscriber::setReceiverPolicy(const size_t policy) +{ + if (gxf_receiver_ptr_ == nullptr) { + RCLCPP_ERROR( + node_.get_logger().get_child(LOGGER_SUFFIX), + "The underlying receiver pointer (\"%s\") is not set when setting its policy.", + GenerateComponentKey(gxf_component_info_).c_str()); + return; + } + + gxf_result_t code; + code = GxfParameterSetUInt64(context_, gxf_receiver_ptr_->cid(), "policy", policy); + if (code != GXF_SUCCESS) { + RCLCPP_ERROR( + node_.get_logger().get_child(LOGGER_SUFFIX), + "Failed to set policy for the underlying receiver (\"%s\"): %s", + GenerateComponentKey(gxf_component_info_).c_str(), + GxfResultStr(code)); + return; + } + + RCLCPP_DEBUG( + node_.get_logger().get_child(LOGGER_SUFFIX), + "Set policy to %zu for the underlying receiver (\"%s\")", + policy, GenerateComponentKey(gxf_component_info_).c_str()); +} + +// Set the capacity for the underlying GXF receiver +void NitrosSubscriber::setReceiverCapacity(const size_t capacity) +{ + if (gxf_receiver_ptr_ == nullptr) { + RCLCPP_ERROR( + node_.get_logger().get_child(LOGGER_SUFFIX), + "The underlying receiver pointer (\"%s\") is not set when setting its capacity.", + GenerateComponentKey(gxf_component_info_).c_str()); + return; + } + + gxf_result_t code; + code = GxfParameterSetUInt64(context_, gxf_receiver_ptr_->cid(), "capacity", capacity); + if (code != GXF_SUCCESS) { + RCLCPP_ERROR( + node_.get_logger().get_child(LOGGER_SUFFIX), + "Failed to set capacity for the underlying receiver (\"%s\"): %s", + GenerateComponentKey(gxf_component_info_).c_str(), + GxfResultStr(code)); + return; + } + + RCLCPP_DEBUG( + node_.get_logger().get_child(LOGGER_SUFFIX), + "Set capacity to %zu for the underlying receiver (\"%s\")", + capacity, GenerateComponentKey(gxf_component_info_).c_str()); +} + bool NitrosSubscriber::pushEntity(const int64_t eid, bool should_block) { gxf_entity_status_t entity_status; @@ -334,13 +389,14 @@ void NitrosSubscriber::subscriberCallback( getTimestamp(msg_base) << ")"; nvtxRangePushWrapper(nvtx_tag_name.str().c_str(), CLR_PURPLE); - // Only enable statistics if the ROS parameter flag is enabled and + // Only enable diagnostics if the ROS parameter flag is enabled and // the topic has been specified in the topics_list ROS parameter - if (statistics_config_.enable_statistics && - statistics_config_.topic_name_expected_dt_map.find(config_.topic_name) != - statistics_config_.topic_name_expected_dt_map.end()) + if (diagnostics_config_.enable_all_topic_diagnostics || + (diagnostics_config_.enable_diagnostics && + diagnostics_config_.topic_name_expected_dt_map.find(config_.topic_name) != + diagnostics_config_.topic_name_expected_dt_map.end())) { - updateStatistics(getTimestamp(msg_base)); + updateDiagnostics(getTimestamp(msg_base)); } RCLCPP_DEBUG(node_.get_logger(), "[NitrosSubscriber] Received a Nitros-typed messgae"); @@ -385,7 +441,7 @@ void NitrosSubscriber::subscriberCallback( if (use_gxf_receiver_ && gxf_receiver_ptr_ != nullptr && is_gxf_running_) { // Push the message to the associated gxf receiver if existed - pushEntity(msg_base.handle, true); + pushEntity(msg_base.handle, false); } nvtxRangePopWrapper(); diff --git a/isaac_ros_nitros/test/isaac_ros_nitros_statistics_test_pol.py b/isaac_ros_nitros/test/isaac_ros_nitros_diagnostics_test_pol.py similarity index 52% rename from isaac_ros_nitros/test/isaac_ros_nitros_statistics_test_pol.py rename to isaac_ros_nitros/test/isaac_ros_nitros_diagnostics_test_pol.py index df181d2..2289c1f 100644 --- a/isaac_ros_nitros/test/isaac_ros_nitros_statistics_test_pol.py +++ b/isaac_ros_nitros/test/isaac_ros_nitros_diagnostics_test_pol.py @@ -17,7 +17,7 @@ import time -from isaac_ros_nitros_interfaces.msg import TopicStatistics +from diagnostic_msgs.msg import DiagnosticArray from isaac_ros_test import IsaacROSBaseTest import launch from launch_ros.actions import ComposableNodeContainer @@ -45,29 +45,28 @@ def generate_test_description(): namespace=test_ns, parameters=[{ 'compatible_format': 'nitros_empty', - 'enable_node_time_statistics': True, - 'statistics_publish_rate': 2.0, - 'filter_window_size': 7, + 'enable_all_diagnostics': True, + 'diagnostics_publish_rate': 5.0, + 'filter_window_size': 10, 'topics_list': ['topic_forward_output'], - 'expected_fps_list': [5.0] + 'jitter_tolerance_us': 100, + 'expected_fps_list': [50.0] }] ), ComposableNode( package='isaac_ros_nitros', plugin='nvidia::isaac_ros::nitros::NitrosEmptyForwardNode', name='isaac_ros_nitros', - namespace=test_ns+'/mid1', + namespace=test_ns + '/mid1', parameters=[{ 'compatible_format': 'nitros_empty', - 'enable_node_time_statistics': True, - 'statistics_publish_rate': 3.0, - 'filter_window_size': 12 + 'enable_all_diagnostics': False, }], remappings=[ - (test_ns+'/mid1/topic_forward_input', - test_ns+'/topic_forward_output'), - (test_ns+'/mid1/topic_forward_output', - test_ns+'/final/topic_forward_output'), + (test_ns + '/mid1/topic_forward_input', + test_ns + '/topic_forward_output'), + (test_ns + '/mid1/topic_forward_output', + test_ns + '/final/topic_forward_output'), ] ) ], @@ -98,7 +97,7 @@ def test_forward_node(self) -> None: received_messages = {} test_subscribers = [ - ('/nitros_statistics', TopicStatistics) + ('/diagnostics', DiagnosticArray) ] subs = self.create_logging_subscribers( @@ -120,32 +119,78 @@ def test_forward_node(self) -> None: msg = Empty() # Testing frame rate - test_frame_rate = 5 + test_frame_rate = 50 # Start sending messages self.node.get_logger().info('Start publishing messages') # Publish messages at a fixed frame rate set by test_frame_rate + start_time = time.time() end_time = time.time() + 2 sent_count = 0 while time.time() < end_time: sent_count += 1 pub.publish(msg) - time.sleep(1/test_frame_rate) - - # Run the queued ROS subscriber callbacks - rclpy.spin_once(self.node, timeout_sec=0.1) + # Run the queued ROS subscriber callbacks + rclpy.spin_once(self.node, timeout_sec=0) + time.sleep(1 / test_frame_rate) + if sent_count == 10: + # add a dropped frame be delaying here + time.sleep(.5) + + measured_frame_rate = sent_count / (time.time() - start_time) + self.node.get_logger().info(f'sent_count: {sent_count}') + self.node.get_logger().info(f'time: {time.time() - start_time}') + self.node.get_logger().info(f'frame rate: {measured_frame_rate}') # Assert that we have received atleast one message on the output topic self.assertNotEqual( - len(received_messages['/nitros_statistics']), + len(received_messages['/diagnostics']), 0) - if len(received_messages['/nitros_statistics']) > 0: - # Assert that the measured frame rate within the acceptable error window - self.assertAlmostEqual(received_messages['/nitros_statistics'][0].frame_rate, - test_frame_rate, None, - 'measured frame rate error is too high', 0.1) + if len(received_messages['/diagnostics']) > 0: + # Assert that the measured frame rate is within the acceptable error window + print('message len: ', len(received_messages['/diagnostics'])) + values_received = received_messages['/diagnostics'][-1].status[0].values + diagnostics_values = { + 'frame_rate_node': 0, + 'num_non_increasing_msg': 0, + 'num_jitter_outliers_msg': 0, + 'num_jitter_outliers_node': 0, + 'max_abs_jitter_msg': 0, + 'max_abs_jitter_node': 0, + 'mean_abs_jitter_msg': 0, + 'mean_abs_jitter_node': 0, + 'frame_rate_msg': 0, + 'total_dropped_frames': 0 + } + + for kv in values_received: + if kv.key in diagnostics_values: + diagnostics_values[kv.key] = float(kv.value) + + # We are not publishing that consitently above, and this test may be running + # on a busy machine so we allow a large error window + self.assertAlmostEqual(diagnostics_values['frame_rate_node'], test_frame_rate, + None, 'measured recv rate error is too high', 5.0) + # The forward node used for testing always publishes a 0 msg timestamp + self.assertEqual(diagnostics_values['frame_rate_msg'], 0) + + self.assertEqual(diagnostics_values['total_dropped_frames'], 0) + + # Additional assertions for other diagnostic values + self.assertEqual(diagnostics_values['num_non_increasing_msg'], 0) + + self.assertEqual(diagnostics_values['num_jitter_outliers_msg'], 0) + + # we added one delayed frame, so we should have at least one jitter outlier + # we have have more if the system was very busy + self.assertGreaterEqual(diagnostics_values['num_jitter_outliers_node'], 1) + + self.assertGreaterEqual(diagnostics_values['max_abs_jitter_msg'], 0) + self.assertGreaterEqual(diagnostics_values['max_abs_jitter_node'], 0) + self.assertGreaterEqual(diagnostics_values['mean_abs_jitter_msg'], 0) + self.assertGreaterEqual(diagnostics_values['mean_abs_jitter_node'], 0) finally: [self.node.destroy_subscription(sub) for sub in subs] diff --git a/isaac_ros_nitros_bridge/.gitattributes b/isaac_ros_nitros_bridge/.gitattributes new file mode 100644 index 0000000..e3453ff --- /dev/null +++ b/isaac_ros_nitros_bridge/.gitattributes @@ -0,0 +1,29 @@ +# Ignore Python files in linguist +*.py linguist-detectable=false + +# Images +*.gif filter=lfs diff=lfs merge=lfs -text +*.jpg filter=lfs diff=lfs merge=lfs -text +*.png filter=lfs diff=lfs merge=lfs -text +*.psd filter=lfs diff=lfs merge=lfs -text + +# Archives +*.gz filter=lfs diff=lfs merge=lfs -text +*.tar filter=lfs diff=lfs merge=lfs -text +*.zip filter=lfs diff=lfs merge=lfs -text + +# Documents +*.pdf filter=lfs diff=lfs merge=lfs -text + +# Shared libraries +*.so filter=lfs diff=lfs merge=lfs -text +*.so.* filter=lfs diff=lfs merge=lfs -text + +# ROS Bags +**/resources/**/*.zstd filter=lfs diff=lfs merge=lfs -text +**/resources/**/*.db3 filter=lfs diff=lfs merge=lfs -text +**/resources/**/*.yaml filter=lfs diff=lfs merge=lfs -text +**/resources/**/*.bag filter=lfs diff=lfs merge=lfs -text + +# DNN Model files +*.onnx filter=lfs diff=lfs merge=lfs -text diff --git a/isaac_ros_nitros_bridge/.gitignore b/isaac_ros_nitros_bridge/.gitignore new file mode 100644 index 0000000..8ef8ee6 --- /dev/null +++ b/isaac_ros_nitros_bridge/.gitignore @@ -0,0 +1,6 @@ +# Ignore all pycache files +**/__pycache__/** + +# Ignore TensorRT plan files +*.plan +*.engine diff --git a/isaac_ros_nitros_bridge/CONTRIBUTING.md b/isaac_ros_nitros_bridge/CONTRIBUTING.md new file mode 100644 index 0000000..a89cd42 --- /dev/null +++ b/isaac_ros_nitros_bridge/CONTRIBUTING.md @@ -0,0 +1,14 @@ +# Isaac ROS Contribution Rules + +Any contribution that you make to this repository will +be under the Apache 2 License, as dictated by that +[license](http://www.apache.org/licenses/LICENSE-2.0.html): + +> **5. Submission of Contributions.** Unless You explicitly state otherwise, any Contribution intentionally submitted for inclusion in the Work by You to the Licensor shall be under the terms and conditions of this License, without any additional terms or conditions. Notwithstanding the above, nothing herein shall supersede or modify the terms of any separate license agreement you may have executed with Licensor regarding such Contributions. + +Contributors must sign-off each commit by adding a `Signed-off-by: ...` +line to commit messages to certify that they have the right to submit +the code they are contributing to the project according to the +[Developer Certificate of Origin (DCO)](https://developercertificate.org/). + +[//]: # (202201002) diff --git a/isaac_ros_nitros_bridge/LICENSE b/isaac_ros_nitros_bridge/LICENSE new file mode 100644 index 0000000..7a4a3ea --- /dev/null +++ b/isaac_ros_nitros_bridge/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/README.md b/isaac_ros_nitros_bridge/README.md new file mode 100644 index 0000000..dff871e --- /dev/null +++ b/isaac_ros_nitros_bridge/README.md @@ -0,0 +1,77 @@ +# Isaac ROS NITROS Bridge + +Use Isaac ROS packages in your ROS 1 Noetic with NITROS-enabled performance. + +
image
+ +--- + +## Overview + +The [Isaac ROS NITROS Bridge](https://gitlab-master.nvidia.com/isaac_ros/isaac_ros_nitros_bridge) brings +accelerated computing to versions of ROS where it is not supported, by improving +the performance of bridging between ROS versions. + +Isaac ROS provides accelerated computing ROS packages for robotics development +in ROS 2 with NITROS; this is enabled with the addition of type adaptation +(REP-2007) and type negotiation (REP-2009) in ROS 2 Humble, which is not +available in previous versions of ROS. + +Accelerated computing is essential to move beyond the limits of single threaded +performance on a CPU. To take advantage of this, it may not be practical to migrate to +a new version of ROS 2 for robotics applications that were developed previously. Some +developers have chosen to bridge between their current version of ROS, and +what is used with Isaac ROS. This improves existing robotics applications with the +addition of accelerated computing; unfortunately, the ROS bridge includes a CPU based memory +copy bridge toll. + +Isaac ROS NITROS Bridge packages improves performance with a ROS bridge. +The bridge toll is removed by moving data from CPU to GPU to avoid CPU memory copies. +This significantly improves performance across processes in different versions of ROS. +In addition the data in GPU memory can be used in place, by accelerated computing. + +
image
+ +Illustrated above is the use of NITROS Converters between ROS Noetic and ROS 2 Humble. +When sending an image from ROS Noetic to ROS 2 Humble, +the NITROS converter moves the image to GPU accelerated memory avoiding CPU memory copies. +On the Humble side of the bridge the NITROS converter adapts the image in GPU memory into +a NITROS image for use with accelerated computing. This also works the other direction from +ROS 2 Humble to ROS Noetic. When sending an NITROS image from Humble to Noetic, +the NITROS Converter maintains the image in GPU accelerated memory avoiding CPU memory +copies over the bridge, moving the image into CPU accessible memory in Noetic. + +This same principle can be applied to ROS 2, for example between Foxy and Humble +to take advantage of Isaac ROS in Humble, from applications developed in Foxy +without migrating versions of ROS. + +
image
+ +Illustrated above is the use of the ROS bridge without the benefits of NITROS converters. +Images sent from Noetic to Humble and visa-versa are copies across the ROS processes using +the CPU limiting performance and increasing latency. + +By avoiding unnecessary CPU memory copies the Isaac ROS NITROS bridge improves accelerated +computing performance and reduces end to end latency across versions of ROS. + +## Performance + +Isaac ROS NITROS Bridge can move 1080p images between ROS 1 Noetic and Isaac ROS NITROS packages up to 3x faster than the available [ros1_bridge](https://github.com/ros2/ros1_bridge). +See [Isaac ROS Benchmark](https://isaac_ros.gitlab-master-pages.nvidia.com/isaac_ros_docs/repositories_and_packages/isaac_ros_benchmark/index.html) scripts for [NITROS bridge](https://gitlab-master.nvidia.com/isaac_ros/isaac_ros_benchmark/-/blob/dev/benchmarks/isaac_ros_nitros_bridge_benchmark/scripts/isaac_ros_nitros_bridge.py) and [ros1_bridge](https://gitlab-master.nvidia.com/isaac_ros/isaac_ros_benchmark/-/blob/dev/benchmarks/isaac_ros_nitros_bridge_benchmark/scripts/isaac_ros_nitros_bridge_reference.py). + +## Documentation + +Please visit the [Isaac ROS Documentation](https://isaac_ros.gitlab-master-pages.nvidia.com/isaac_ros_docs/repositories_and_packages/isaac_ros_nitros_bridge/index.html) to learn how to use this repository. + +--- + +## Packages + +* [`isaac_ros_nitros_bridge_ros1`](https://isaac_ros.gitlab-master-pages.nvidia.com/isaac_ros_docs/repositories_and_packages/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros1/index.html) + * [API](https://isaac_ros.gitlab-master-pages.nvidia.com/isaac_ros_docs/repositories_and_packages/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros1/index.html#api) +* [`isaac_ros_nitros_bridge_ros2`](https://isaac_ros.gitlab-master-pages.nvidia.com/isaac_ros_docs/repositories_and_packages/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/index.html) + * [API](https://isaac_ros.gitlab-master-pages.nvidia.com/isaac_ros_docs/repositories_and_packages/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/index.html#api) + +## Latest + +Update 2024-05-30: Update to be compatible with JetPack 6.0 diff --git a/isaac_ros_nitros_bridge/config/nitros_bridge_convert_forward.yaml b/isaac_ros_nitros_bridge/config/nitros_bridge_convert_forward.yaml new file mode 100644 index 0000000..95fc7c0 --- /dev/null +++ b/isaac_ros_nitros_bridge/config/nitros_bridge_convert_forward.yaml @@ -0,0 +1,9 @@ +topics: + - + topic: /r2b/ros1_input_bridge_image # Topic name for ros1 bridge + type: isaac_ros_nitros_bridge_interfaces/msg/NitrosBridgeImage # Type type for ros1 bridge + queue_size: 10 + - + topic: /r2b/ros1_output_bridge_image # Topic name for ros1 bridge + type: isaac_ros_nitros_bridge_interfaces/msg/NitrosBridgeImage # Type type for ros1 bridge + queue_size: 10 diff --git a/isaac_ros_nitros_bridge/config/nitros_bridge_forward.yaml b/isaac_ros_nitros_bridge/config/nitros_bridge_forward.yaml new file mode 100644 index 0000000..9a691df --- /dev/null +++ b/isaac_ros_nitros_bridge/config/nitros_bridge_forward.yaml @@ -0,0 +1,9 @@ +topics: + - + topic: /r2b/ros2_input_image # Topic name for ros1 bridge + type: sensor_msgs/msg/Image # Type type for ros1 bridge + queue_size: 10 + - + topic: /r2b/ros2_output_image # Topic name for ros1 bridge + type: sensor_msgs/msg/Image # Type type for ros1 bridge + queue_size: 10 diff --git a/isaac_ros_nitros_bridge/config/nitros_bridge_image_converter.yaml b/isaac_ros_nitros_bridge/config/nitros_bridge_image_converter.yaml new file mode 100644 index 0000000..9fc3c15 --- /dev/null +++ b/isaac_ros_nitros_bridge/config/nitros_bridge_image_converter.yaml @@ -0,0 +1,13 @@ +topics: + - + topic: /ros1_input_bridge_image # Topic name for ros1 bridge + type: isaac_ros_nitros_bridge_interfaces/msg/NitrosBridgeImage # Type type for ros1 bridge + queue_size: 10 + - + topic: /ros1_output_bridge_image # Topic name for ros1 bridge + type: isaac_ros_nitros_bridge_interfaces/msg/NitrosBridgeImage # Type type for ros1 bridge + queue_size: 10 + - + topic: /camera_info # Topic name for ros1 bridge + type: sensor_msgs/msg/CameraInfo # Type type for ros1 bridge + queue_size: 10 diff --git a/isaac_ros_nitros_bridge/docker/Dockerfile.ros1_noetic b/isaac_ros_nitros_bridge/docker/Dockerfile.ros1_noetic new file mode 100644 index 0000000..012afac --- /dev/null +++ b/isaac_ros_nitros_bridge/docker/Dockerfile.ros1_noetic @@ -0,0 +1,190 @@ +# Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. +# +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +FROM nvcr.io/nvidia/cuda:11.4.0-devel-ubuntu20.04 + +# disable terminal interaction for apt +ENV DEBIAN_FRONTEND=noninteractive +ENV SHELL=/bin/bash +SHELL ["/bin/bash", "-c"] + +# Ensure we have universe +RUN apt-get update \ + && apt-get install -y software-properties-common \ + && add-apt-repository universe + +# Fundamentals +RUN apt-get update && apt-get install -y \ + apt-transport-https \ + bash-completion \ + build-essential \ + ca-certificates \ + clang-format \ + cmake \ + curl \ + git \ + git-lfs \ + gnupg2 \ + iputils-ping \ + locales \ + lsb-release \ + rsync \ + software-properties-common \ + wget \ + vim \ + unzip \ + mlocate \ + sudo \ + udev \ + libgoogle-glog-dev \ +&& rm -rf /var/lib/apt/lists/* \ +&& apt-get clean + +# Add Isaac apt repository +RUN wget -qO - https://isaac.download.nvidia.com/isaac-ros/repos.key | apt-key add - +RUN echo 'deb https://isaac.download.nvidia.com/isaac-ros/ubuntu/main focal main' | tee -a /etc/apt/sources.list + +# Set Python3 as default +RUN update-alternatives --install /usr/bin/python python /usr/bin/python3 1 + +# Python basics +RUN apt-get update && apt-get install -y \ + python3-pip \ + python3-pybind11 \ + python3-pytest-cov \ +&& rm -rf /var/lib/apt/lists/* \ +&& apt-get clean + +# Python3 (PIP) +RUN python3 -m pip install -U \ + argcomplete \ + autopep8 \ + flake8==4.0.1 \ + flake8-blind-except \ + flake8-builtins \ + flake8-class-newline \ + flake8-comprehensions \ + flake8-deprecated \ + flake8-docstrings \ + flake8-import-order \ + flake8-quotes \ + onnx \ + pytest-repeat \ + pytest-rerunfailures \ + pytest \ + pydocstyle \ + scikit-learn + +# Upgrade cmake to 3.22.1 to match Ubuntu 22.04 +# Key rotation 2024-01-10 +RUN wget -O - https://apt.kitware.com/keys/kitware-archive-latest.asc 2>/dev/null | gpg --dearmor - | tee /usr/share/keyrings/kitware-archive-keyring.gpg >/dev/null \ + && echo 'deb [signed-by=/usr/share/keyrings/kitware-archive-keyring.gpg] https://apt.kitware.com/ubuntu/ focal main' | tee /etc/apt/sources.list.d/kitware.list >/dev/null \ + && apt-get update \ + && apt-get remove -y cmake && apt-get purge -y cmake && apt-get remove -y cmake-data && apt-get purge -y cmake-data \ + && apt-get install -y cmake=3.22.1-0kitware1ubuntu20.04.1 cmake-data=3.22.1-0kitware1ubuntu20.04.1 \ + && cmake --version \ +&& rm -rf /var/lib/apt/lists/* \ +&& apt-get clean + +# Add ROS 2 apt repository +RUN curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg +RUN echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2-testing/ubuntu $(source /etc/os-release && echo $UBUNTU_CODENAME) main" | tee /etc/apt/sources.list.d/ros2.list > /dev/null + +# ROS fundamentals +RUN --mount=type=cache,target=/var/cache/apt \ +apt-get update && apt-get install -y \ + devscripts \ + dh-make \ + fakeroot \ + libxtensor-dev \ + python3-bloom \ + python3-colcon-common-extensions \ + python3-pip \ + python3-pybind11 \ + python3-pytest-cov \ + python3-rosdep \ + python3-rosinstall-generator \ + python3-vcstool \ + python3-wstool \ + quilt + +# Install ROS 2 Humble +RUN apt-get update && apt-get install -y ros-humble-ros-base \ + && rm -rf /var/lib/apt/lists/* \ + && apt-get clean + +# Install ROS Noetic due to CMake update +RUN sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' \ + && curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | apt-key add - \ + && apt-get update && apt-get install -y ros-noetic-ros-base + +# Install VPI packages +RUN --mount=type=cache,target=/var/cache/apt \ + apt-key adv --fetch-key https://repo.download.nvidia.com/jetson/jetson-ota-public.asc ; \ + add-apt-repository "deb http://repo.download.nvidia.com/jetson/x86_64/$(lsb_release -cs) r36.4 main" ; \ + apt-get update ; \ + apt-get install libnvvpi3 vpi3-dev + +# Setup non-root admin user +ARG USERNAME=admin +ARG USER_UID=1001 +ARG USER_GID=1001 + +# Create the 'admin' user if not already exists +RUN if [ ! $(getent passwd ${USERNAME}) ]; then \ + groupadd --gid ${USER_GID} ${USERNAME} ; \ + useradd --no-log-init --uid ${USER_UID} --gid ${USER_GID} -m ${USERNAME} ; \ + fi + +# Update 'admin' user +RUN echo ${USERNAME} ALL=\(root\) NOPASSWD:ALL > /etc/sudoers.d/${USERNAME} \ + && chmod 0440 /etc/sudoers.d/${USERNAME} \ + && adduser ${USERNAME} video && adduser ${USERNAME} plugdev && adduser ${USERNAME} sudo + +ENV USERNAME=${USERNAME} +ENV USER_GID=${USER_GID} +ENV USER_UID=${USER_UID} + +RUN mkdir /workspaces +COPY ros1_ws /workspaces/ + +# Copy scripts +RUN mkdir -p /usr/local/bin/scripts +COPY ros1_ws/isaac_ros_1-dev/src/isaac_ros_nitros/isaac_ros_nitros_bridge/scripts/*entrypoint.sh /usr/local/bin/scripts/ +RUN chmod +x /usr/local/bin/scripts/*entrypoint.sh + +# Copy middleware profiles +RUN mkdir -p /usr/local/share/middleware_profiles +COPY ros1_ws/isaac_ros-dev/src/isaac_ros_common/docker/middleware_profiles/*profile.xml /usr/local/share/middleware_profiles/ + +# Build ROS 1 workspaces +WORKDIR /workspaces/isaac_ros_1-dev/ +RUN mv src/isaac_ros_nitros/isaac_ros_nitros_bridge src/ && rm -rf src/isaac_ros_nitros +# Remove the COLCON_IGNORE file first to build the ROS 1 bridge +RUN /bin/bash -c "rm src/isaac_ros_nitros_bridge/ros1/COLCON_IGNORE && \ + source /opt/ros/noetic/setup.bash && catkin_make_isolated --install --ignore-pkg isaac_ros_nitros_bridge_ros2" + +# Build ROS 2 workspaces +WORKDIR /workspaces/isaac_ros-dev/ +RUN /bin/bash -c "source /opt/ros/humble/setup.bash && colcon build --symlink-install --packages-up-to \ + isaac_ros_nitros_bridge_interfaces \ + isaac_ros_apriltag_interfaces \ + isaac_ros_bi3d_interfaces \ + isaac_ros_nova_interfaces \ + isaac_ros_pointcloud_interfaces \ + isaac_ros_tensor_list_interfaces" + +# Build ROS 1 bridge +RUN /bin/bash -c \ + "source ../isaac_ros_1-dev/install_isolated/setup.bash && source /opt/ros/humble/setup.bash && \ + colcon build --symlink-install --packages-select ros1_bridge --cmake-force-configure" + +USER ${USERNAME} +WORKDIR /workspaces/isaac_ros_1-dev/ +ENTRYPOINT ["/usr/local/bin/scripts/nitros-bridge-entrypoint.sh"] +CMD ["nitros_bridge_convert_forward.yaml", "nitros_bridge_convert_forward.launch"] diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/CMakeLists.txt b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/CMakeLists.txt new file mode 100644 index 0000000..c08dc5e --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/CMakeLists.txt @@ -0,0 +1,80 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +cmake_minimum_required(VERSION 3.22.1) +project(isaac_ros_nitros_bridge_ros2 LANGUAGES C CXX) + +if($ENV{ROS_VERSION} EQUAL 1) + message(STATUS "Skip package ${PROJECT_NAME} for ROS 1") + return() +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake_auto REQUIRED) +find_package(CUDAToolkit REQUIRED) +ament_auto_find_build_dependencies() + +# Image converter node +ament_auto_add_library(image_converter_node SHARED src/image_converter_node.cpp) +target_link_libraries(image_converter_node CUDA::cuda_driver) +set_target_properties(image_converter_node PROPERTIES + BUILD_WITH_INSTALL_RPATH TRUE + BUILD_RPATH_USE_ORIGIN TRUE + INSTALL_RPATH_USE_LINK_PATH TRUE +) + +rclcpp_components_register_nodes(image_converter_node "nvidia::isaac_ros::nitros_bridge::ImageConverterNode") +set(node_plugins "${node_plugins}nvidia::isaac_ros::nitros_bridge::ImageConverterNode;$\n") + + +# TensorList converter node +ament_auto_add_library(tensor_list_converter_node SHARED src/tensor_list_converter_node.cpp) +target_link_libraries(tensor_list_converter_node CUDA::cuda_driver) +set_target_properties(tensor_list_converter_node PROPERTIES + BUILD_WITH_INSTALL_RPATH TRUE + BUILD_RPATH_USE_ORIGIN TRUE + INSTALL_RPATH_USE_LINK_PATH TRUE +) + +rclcpp_components_register_nodes(tensor_list_converter_node "nvidia::isaac_ros::nitros_bridge::TensorListConverterNode") +set(node_plugins "${node_plugins}nvidia::isaac_ros::nitros_bridge::TensorListConverterNode;$\n") + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + + # The FindPythonInterp and FindPythonLibs modules are removed + if(POLICY CMP0148) + cmake_policy(SET CMP0148 OLD) + endif() + + find_package(launch_testing_ament_cmake REQUIRED) + add_launch_test(test/isaac_ros_nitros_bridge_image_pol.py TIMEOUT "15") + add_launch_test(test/isaac_ros_nitros_bridge_tensor_list_pol.py TIMEOUT "15") +endif() + + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + +ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/image_converter_node.hpp b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/image_converter_node.hpp new file mode 100644 index 0000000..32ac022 --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/image_converter_node.hpp @@ -0,0 +1,98 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ISAAC_ROS_NITROS_BRIDGE_ROS2__IMAGE_CONVERTER_NODE_HPP_ +#define ISAAC_ROS_NITROS_BRIDGE_ROS2__IMAGE_CONVERTER_NODE_HPP_ + +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" + +#include "isaac_ros_managed_nitros/managed_nitros_publisher.hpp" +#include "isaac_ros_managed_nitros/managed_nitros_subscriber.hpp" + +#include "ipc_buffer_manager.hpp" +#include "sensor_msgs/msg/image.hpp" +#include "isaac_ros_nitros_bridge_interfaces/msg/nitros_bridge_image.hpp" +#include "isaac_ros_nitros_image_type/nitros_image.hpp" +#include "isaac_ros_nitros_image_type/nitros_image_builder.hpp" +#include "isaac_ros_nitros_image_type/nitros_image_view.hpp" + + +namespace nvidia +{ +namespace isaac_ros +{ +namespace nitros_bridge +{ + +class ImageConverterNode : public rclcpp::Node +{ +public: + explicit ImageConverterNode(const rclcpp::NodeOptions options = rclcpp::NodeOptions()); + + ~ImageConverterNode(); + +private: + // Convert stub message into managed NITROS message + void BridgeToROSCallback( + const isaac_ros_nitros_bridge_interfaces::msg::NitrosBridgeImage::SharedPtr msg); + + // Copy managed NITROS message data into IPC memory pool and convert to bridge message + void ROSToBridgeCallback(const nvidia::isaac_ros::nitros::NitrosImageView msg); + + // Publisher for output NitrosImage messages + std::shared_ptr> nitros_pub_; + // Publisher for output bridge messages + rclcpp::Publisher::SharedPtr + bridge_image_pub_; + + // Subscription to input NitrosImage messages + std::shared_ptr> nitros_sub_; + // Subscription to input bridge messages + rclcpp::Subscription::SharedPtr + bridge_image_sub_; + + // Number of blocks of the device memory pool + int64_t num_blocks_; + // Timeout in microsec to waiting for a buffer to be available + int64_t timeout_; + // Map between FD and device memory pointer + std::map handle_ptr_map_; + // CUDA IPC memory pool manager + std::shared_ptr ipc_buffer_manager_; + // Shared memory based IPC buffer for refcount and UID + std::shared_ptr host_ipc_buffer_; + // If received the first message + bool first_msg_received_ = false; + // CUDA driver context + CUcontext ctx_; + // CUDA IPC event handle sent by the sender + cudaIpcEventHandle_t ipc_event_handle_; + // CUDA event export from IPC event to synchronize the upstream + cudaEvent_t event_; +}; + +} // namespace nitros_bridge +} // namespace isaac_ros +} // namespace nvidia + +#endif // ISAAC_ROS_NITROS_BRIDGE_ROS2__IMAGE_CONVERTER_NODE_HPP_ diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/ipc_buffer_manager.hpp b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/ipc_buffer_manager.hpp new file mode 100644 index 0000000..7edd0fe --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/ipc_buffer_manager.hpp @@ -0,0 +1,318 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ISAAC_ROS_NITROS_BRIDGE_ROS2__IPC_BUFFER_MANAGER_HPP_ +#define ISAAC_ROS_NITROS_BRIDGE_ROS2__IPC_BUFFER_MANAGER_HPP_ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" + + +namespace nvidia +{ +namespace isaac_ros +{ + +namespace nitros_bridge +{ + +// Size of shared memory object in bytes +constexpr size_t kSharedMemorySize = 1024; + +struct DeviceIPCBuffer +{ + CUdeviceptr d_ptr; + CUmemGenericAllocationHandle generic_allocation_handle; + int pid; + int fd; + std::string uid; + size_t index; +}; + +struct HostIPCBuffer +{ + enum class Mode {CREATE, OPEN}; + std::shared_ptr shm_object_ = nullptr; + std::shared_ptr mutex_ = nullptr; + std::shared_ptr shm_ptr_ = nullptr; + boost::uuids::uuid * uid_ = nullptr; + int32_t * refcount_ = nullptr; + int start_time_ = 0; + + HostIPCBuffer(const std::string & shm_name, const Mode mode) + { + if (mode == Mode::CREATE) { + shm_object_ = std::make_shared( + boost::interprocess::open_or_create, + shm_name.c_str(), boost::interprocess::read_write); + shm_object_->truncate(kSharedMemorySize); + mutex_ = std::make_shared( + boost::interprocess::open_or_create, (shm_name).c_str()); + shm_ptr_ = std::make_shared( + *shm_object_, boost::interprocess::read_write); + refcount_ = static_cast(shm_ptr_->get_address()); + uid_ = static_cast(shm_ptr_->get_address() + sizeof(int)); + + // Initialize refcount and UID + *refcount_ = 0; + *uid_ = boost::uuids::random_generator()(); + } else { + try { + shm_object_ = std::make_shared( + boost::interprocess::open_only, shm_name.c_str(), boost::interprocess::read_write); + mutex_ = std::make_shared( + boost::interprocess::open_only, (shm_name).c_str()); + shm_ptr_ = std::make_shared( + *shm_object_, boost::interprocess::read_write); + refcount_ = static_cast(shm_ptr_->get_address()); + uid_ = static_cast(shm_ptr_->get_address() + sizeof(int)); + } catch (const boost::interprocess::interprocess_exception & ex) { + RCLCPP_ERROR( + rclcpp::get_logger("SharedMem"), "Failed to open shared memory object %s", + ex.what()); + throw std::runtime_error("Failed to open shared memory object"); + } + } + } + + bool reset_if_refcount_zero() + { + boost::interprocess::scoped_lock lock(*mutex_); + if (*refcount_ == 0) { + // Reset the start time and UID + *uid_ = boost::uuids::random_generator()(); + start_time_ = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + return true; + } + return false; + } + + bool refcoun_inc_if_uid_match(const std::string & received_uid) + { + // The UID compare and refcount increment should be atomic + boost::interprocess::scoped_lock lock(*mutex_); + if (boost::uuids::to_string(*uid_) == received_uid) { + *refcount_ += 1; + return true; + } + return false; + } + + void refcount_inc() + { + boost::interprocess::scoped_lock lock(*mutex_); + *refcount_ += 1; + } + + void refcount_dec() + { + boost::interprocess::scoped_lock lock(*mutex_); + if (refcount_ == 0) { + RCLCPP_ERROR( + rclcpp::get_logger("IPCBufferManager"), "Refcount is already zero."); + return; + } + *refcount_ -= 1; + } + + std::string get_uid() + { + boost::interprocess::scoped_lock lock(*mutex_); + auto uid = boost::uuids::to_string(*uid_); + return uid; + } +}; + +class IPCBufferManager +{ +public: + IPCBufferManager() = default; + + // Constructor, create device memory buffers and export to FD + IPCBufferManager(size_t buffer_count, size_t buffer_step, int64_t timeout) + { + buffer_count_ = buffer_count; + buffer_step_ = buffer_step; + timeout_ = timeout; + + CUmemAllocationProp prop = {}; + prop.type = CU_MEM_ALLOCATION_TYPE_PINNED; + prop.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + prop.location.id = 0; + prop.requestedHandleTypes = CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR; + size_t granularity = 0; + auto cuda_err = cuMemGetAllocationGranularity( + &granularity, &prop, CU_MEM_ALLOC_GRANULARITY_MINIMUM); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + rclcpp::get_logger("IPCBufferManager"), "Failed to call cuMemGetAllocationGranularity %s", + error_str); + } + alloc_size_ = buffer_step - (buffer_step % granularity) + granularity; + + for (size_t index = 0; index < buffer_count_; index++) { + // Create shareable device memory buffer + CUmemGenericAllocationHandle generic_allocation_handle; + auto cuda_err = cuMemCreate(&generic_allocation_handle, alloc_size_, &prop, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + rclcpp::get_logger("IPCBufferManager"), "Failed to call cuMemCreate %s", + error_str); + } + + int fd = -1; + cuda_err = cuMemExportToShareableHandle( + reinterpret_cast(&fd), + generic_allocation_handle, + CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + rclcpp::get_logger("IPCBufferManager"), "Failed to cuMemExportToShareableHandle %s", + error_str); + } + + CUdeviceptr d_ptr = 0ULL; + cuda_err = cuMemAddressReserve(&d_ptr, alloc_size_, 0, 0, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + rclcpp::get_logger("IPCBufferManager"), "Failed to call cuMemCreate %s", + error_str); + } + + cuda_err = cuMemMap(d_ptr, alloc_size_, 0, generic_allocation_handle, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + rclcpp::get_logger("IPCBufferManager"), "Failed to call cuMemCreate %s", + error_str); + } + + CUmemAccessDesc accessDesc = {}; + accessDesc.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + accessDesc.location.id = 0; + accessDesc.flags = CU_MEM_ACCESS_FLAGS_PROT_READWRITE; + cuda_err = cuMemSetAccess(d_ptr, alloc_size_, &accessDesc, 1); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + rclcpp::get_logger("IPCBufferManager"), "Failed to call cuMemSetAccess %s", + error_str); + } + + // Create host shared memory object + std::string shm_name = std::to_string(getpid()) + std::to_string(fd); + std::shared_ptr host_ipc_buffer = + std::make_shared(shm_name, HostIPCBuffer::Mode::CREATE); + std::shared_ptr device_ipc_buffer = + std::make_shared( + DeviceIPCBuffer{ + d_ptr, generic_allocation_handle, getpid(), + fd, host_ipc_buffer->get_uid(), index}); + host_ipc_buffers_.push_back(host_ipc_buffer); + device_ipc_buffers_.push_back(device_ipc_buffer); + } + } + + // Destructor, free the alloacted device memory pool + ~IPCBufferManager() + { + for (size_t i = 0; i < buffer_count_; i++) { + cuMemRelease(device_ipc_buffers_[i]->generic_allocation_handle); + cuMemUnmap(device_ipc_buffers_[i]->d_ptr, alloc_size_); + std::string shm_name = + std::to_string(device_ipc_buffers_[i]->pid) + std::to_string(device_ipc_buffers_[i]->fd); + boost::interprocess::named_mutex::remove(shm_name.c_str()); + boost::interprocess::shared_memory_object::remove(shm_name.c_str()); + } + } + + // Move the index to next available device memory block + std::shared_ptr find_next_available_buffer() + { + auto last_handle_index = current_handle_index_; + while (true) { + auto current_time = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + // TODO(yuankunz) :Reset the timeout everytime the refount is 0 + auto start_time = host_ipc_buffers_[current_handle_index_]->start_time_; + if (current_time - start_time > timeout_) { + if (host_ipc_buffers_[current_handle_index_]->reset_if_refcount_zero()) { + device_ipc_buffers_[current_handle_index_]->uid = + host_ipc_buffers_[current_handle_index_]->get_uid(); + auto ret_device_buffer = device_ipc_buffers_[current_handle_index_]; + current_handle_index_ = (current_handle_index_ + 1) % buffer_count_; + return ret_device_buffer; + } + } else { + current_handle_index_ = (current_handle_index_ + 1) % buffer_count_; + } + if (current_handle_index_ == last_handle_index) { + RCLCPP_INFO( + rclcpp::get_logger("IPCBufferManager"), "No available buffer, re-check after 1 ms"); + std::this_thread::sleep_for(std::chrono::milliseconds(1)); + } + } + } + +private: + // Number of pre-allocated device memory buffers + size_t buffer_count_; + // requested size of each device memory buffer + size_t buffer_step_; + // Index of the current device memory buffer + size_t current_handle_index_ = 0; + // Allocated size of each device memory buffer + size_t alloc_size_; + // Timeout in microseconds to reset the buffer + int64_t timeout_; + // Vector of device memory buffers + std::vector> device_ipc_buffers_; + // Vector of shared memory buffers contain refcount and UID + std::vector> host_ipc_buffers_; +}; + +} // namespace nitros_bridge +} // namespace isaac_ros +} // namespace nvidia + +#endif // ISAAC_ROS_NITROS_BRIDGE_ROS2__IPC_BUFFER_MANAGER_HPP_ diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/tensor_list_converter_node.hpp b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/tensor_list_converter_node.hpp new file mode 100644 index 0000000..dac488b --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/include/isaac_ros_nitros_bridge_ros2/tensor_list_converter_node.hpp @@ -0,0 +1,100 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ISAAC_ROS_NITROS_BRIDGE_ROS2__TENSOR_LIST_CONVERTER_NODE_HPP_ +#define ISAAC_ROS_NITROS_BRIDGE_ROS2__TENSOR_LIST_CONVERTER_NODE_HPP_ + +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" + +#include "isaac_ros_managed_nitros/managed_nitros_publisher.hpp" +#include "isaac_ros_managed_nitros/managed_nitros_subscriber.hpp" + +#include "ipc_buffer_manager.hpp" +#include "sensor_msgs/msg/image.hpp" +#include "isaac_ros_nitros_bridge_interfaces/msg/nitros_bridge_tensor_list.hpp" +#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list.hpp" +#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list_builder.hpp" +#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.hpp" +#include "isaac_ros_nitros_tensor_list_type/nitros_tensor.hpp" +#include "isaac_ros_nitros_tensor_list_type/nitros_tensor_builder.hpp" + + +namespace nvidia +{ +namespace isaac_ros +{ +namespace nitros_bridge +{ + +class TensorListConverterNode : public rclcpp::Node +{ +public: + explicit TensorListConverterNode(const rclcpp::NodeOptions options = rclcpp::NodeOptions()); + + ~TensorListConverterNode(); + +private: + // Convert stub message into managed NITROS message + void BridgeToROSCallback( + const isaac_ros_nitros_bridge_interfaces::msg::NitrosBridgeTensorList::SharedPtr msg); + + // Copy managed NITROS message data into IPC memory pool and convert to bridge message + void ROSToBridgeCallback(const nvidia::isaac_ros::nitros::NitrosTensorListView msg); + + // Publisher for output NitrosTensorList messages + std::shared_ptr> nitros_pub_; + // Publisher for output bridge messages + rclcpp::Publisher::SharedPtr + nitros_bridge_pub_; + + // Subscription to input NitrosTensorList messages + std::shared_ptr> nitros_sub_; + // Subscription to input bridge messages + rclcpp::Subscription::SharedPtr + nitros_bridge_sub_; + + // Number of blocks of the device memory pool + int64_t num_blocks_; + // Timeout in microsec to waiting for a buffer to be available + int64_t timeout_; + // Map between FD and device memory pointer + std::map handle_ptr_map_; + // CUDA IPC memory pool manager + std::shared_ptr ipc_buffer_manager_; + // Shared memory based IPC buffer for refcount and UID + std::shared_ptr host_ipc_buffer_; + // If received the first message + bool first_msg_received_ = false; + // CUDA driver context + CUcontext ctx_; + // CUDA IPC event handle sent by the sender + cudaIpcEventHandle_t ipc_event_handle_; + // CUDA event export from IPC event to synchronize the upstream + cudaEvent_t event_; +}; + +} // namespace nitros_bridge +} // namespace isaac_ros +} // namespace nvidia + +#endif // ISAAC_ROS_NITROS_BRIDGE_ROS2__TENSOR_LIST_CONVERTER_NODE_HPP_ diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_image_converter.launch.py b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_image_converter.launch.py new file mode 100644 index 0000000..5537d1d --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_image_converter.launch.py @@ -0,0 +1,73 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import launch + +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing.actions + + +def launch_setup(context): + pub_image_name = LaunchConfiguration('pub_image_name').perform(context) + sub_image_name = LaunchConfiguration('sub_image_name').perform(context) + + ros2_converter = ComposableNode( + name='ros2_converter', + namespace='', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::ImageConverterNode', + remappings=[ + ('ros2_output_bridge_image', 'ros1_input_bridge_image'), + ('ros2_output_image', pub_image_name), + ('ros2_input_bridge_image', 'ros1_output_bridge_image'), + ('ros2_input_image', sub_image_name), + ]) + + container = ComposableNodeContainer( + name='ros2_converter_container', + namespace='', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[ros2_converter], + output='screen', + arguments=['--ros-args', '--log-level', 'info'] + ) + return [container] + + +def generate_launch_description(): + launch_args = [ + DeclareLaunchArgument( + 'pub_image_name', + description='Remapped publish image name of NITROS Bridge ROS2'), + DeclareLaunchArgument( + 'sub_image_name', + description='Remapped subscribe image name of NITROS Bridge ROS2'), + ] + + nodes = launch_args + [OpaqueFunction(function=launch_setup)] + return launch.LaunchDescription( + nodes + [ + # Start tests after a fixed delay for node startup + launch.actions.TimerAction( + period=30.0, + actions=[launch_testing.actions.ReadyToTest()]) + ] + ) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_quickstart.launch.py b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_quickstart.launch.py new file mode 100644 index 0000000..ffc3e8e --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_quickstart.launch.py @@ -0,0 +1,75 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import launch + +from launch.actions import DeclareLaunchArgument, ExecuteProcess, OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing.actions + + +def launch_setup(context): + rosbag_path = LaunchConfiguration('rosbag_path').perform(context) + + rosbag_play = ExecuteProcess( + cmd=['ros2', 'bag', 'play', rosbag_path, '--loop', '--remap', + '/image:=/r2b/ros2_input_image'], + output='screen') + + ros2_converter = ComposableNode( + name='ros2_converter', + namespace='r2b', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::ImageConverterNode', + parameters=[{ + 'num_blocks': 40 + }], + remappings=[ + ('ros2_output_bridge_image', 'ros1_input_bridge_image'), + ('ros2_input_bridge_image', 'ros1_output_bridge_image') + ]) + + container = ComposableNodeContainer( + name='ros2_converter_container', + namespace='r2b', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[ros2_converter], + output='screen', + arguments=['--ros-args', '--log-level', 'info'] + ) + return [rosbag_play, container] + + +def generate_launch_description(): + launch_args = [ + DeclareLaunchArgument( + 'rosbag_path', + description='Path of the r2b rosbag') + ] + + nodes = launch_args + [OpaqueFunction(function=launch_setup)] + return launch.LaunchDescription( + nodes + [ + # Start tests after a fixed delay for node startup + launch.actions.TimerAction( + period=30.0, + actions=[launch_testing.actions.ReadyToTest()]) + ] + ) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_tensor_list_converter.launch.py b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_tensor_list_converter.launch.py new file mode 100644 index 0000000..2106080 --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/launch/isaac_ros_nitros_bridge_tensor_list_converter.launch.py @@ -0,0 +1,73 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import launch + +from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing.actions + + +def launch_setup(context): + pub_tensor_list_name = LaunchConfiguration('pub_tensor_list_name').perform(context) + sub_tensor_list_name = LaunchConfiguration('sub_tensor_list_name').perform(context) + + ros2_converter = ComposableNode( + name='ros2_converter', + namespace='', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::TensorListConverterNode', + remappings=[ + ('ros2_output_bridge_tensor_list', 'ros1_input_bridge_tensor_list'), + ('ros2_output_tensor_list', pub_tensor_list_name), + ('ros2_input_bridge_tensor_list', 'pynitros_tensor_list'), + ('ros2_input_tensor_list', sub_tensor_list_name), + ]) + + container = ComposableNodeContainer( + name='ros2_converter_container', + namespace='', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[ros2_converter], + output='screen', + arguments=['--ros-args', '--log-level', 'info'] + ) + return [container] + + +def generate_launch_description(): + launch_args = [ + DeclareLaunchArgument( + 'pub_tensor_list_name', + description='Remapped publish image name of NITROS Bridge ROS2'), + DeclareLaunchArgument( + 'sub_tensor_list_name', + description='Remapped subscribe image name of NITROS Bridge ROS2'), + ] + + nodes = launch_args + [OpaqueFunction(function=launch_setup)] + return launch.LaunchDescription( + nodes + [ + # Start tests after a fixed delay for node startup + launch.actions.TimerAction( + period=30.0, + actions=[launch_testing.actions.ReadyToTest()]) + ] + ) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/package.xml b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/package.xml new file mode 100644 index 0000000..27c6114 --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/package.xml @@ -0,0 +1,48 @@ + + + + + + + isaac_ros_nitros_bridge_ros2 + 3.2.0 + Converter between NITROS bridge messages and ROS 2 messages + + Isaac ROS Maintainers + Apache-2.0 + https://developer.nvidia.com/isaac-ros-gems/ + Yuankun Zhu + + ament_cmake + isaac_ros_common + rclcpp + rclcpp_components + std_msgs + isaac_ros_managed_nitros + isaac_ros_nitros_image_type + isaac_ros_nitros_tensor_list_type + isaac_ros_nitros_bridge_interfaces + isaac_ros_test + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/src/image_converter_node.cpp b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/src/image_converter_node.cpp new file mode 100644 index 0000000..5f28a29 --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/src/image_converter_node.cpp @@ -0,0 +1,262 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + + +#include +#include +#include + +#include "isaac_ros_nitros_bridge_ros2/image_converter_node.hpp" +#include "sensor_msgs/image_encodings.hpp" + +#define SYS_pidfd_getfd_nitros_bridge 438 + + +namespace nvidia +{ +namespace isaac_ros +{ +namespace nitros_bridge +{ + +ImageConverterNode::ImageConverterNode(const rclcpp::NodeOptions options) +: rclcpp::Node("image_converter_node", options), + nitros_pub_{std::make_shared>( + this, "ros2_output_image", + nvidia::isaac_ros::nitros::nitros_image_rgb8_t::supported_type_name)}, + bridge_image_pub_{create_publisher( + "ros2_output_bridge_image", 10)}, + nitros_sub_{std::make_shared>( + this, "ros2_input_image", nvidia::isaac_ros::nitros::nitros_image_rgb8_t::supported_type_name, + std::bind(&ImageConverterNode::ROSToBridgeCallback, this, + std::placeholders::_1))}, + bridge_image_sub_{create_subscription( + "ros2_input_bridge_image", 10, std::bind(&ImageConverterNode::BridgeToROSCallback, this, + std::placeholders::_1))}, + num_blocks_(declare_parameter("num_blocks", 40)), + timeout_(declare_parameter("timeout", 500)) +{ + cudaSetDevice(0); + cuDevicePrimaryCtxRetain(&ctx_, 0); + + cudaEventCreateWithFlags(&event_, cudaEventInterprocess | cudaEventDisableTiming); + cudaIpcGetEventHandle(reinterpret_cast(&ipc_event_handle_), event_); +} + +ImageConverterNode::~ImageConverterNode() = default; + + +void ImageConverterNode::BridgeToROSCallback( + const isaac_ros_nitros_bridge_interfaces::msg::NitrosBridgeImage::SharedPtr msg) +{ + cuCtxSetCurrent(ctx_); + + CUdeviceptr gpu_buffer = 0ULL; + CUmemGenericAllocationHandle generic_allocation_handle; + + auto pid = msg->data[0]; + auto fd = msg->data[1]; + + auto msg_uid = msg->uid; + cudaEvent_t event; + cudaIpcEventHandle_t event_handle; + + // Construct CUDA IPC event handle if it exists + if (msg->cuda_event_handle.size() != 0) { + if (msg->cuda_event_handle.size() != sizeof(cudaIpcEventHandle_t)) { + RCLCPP_ERROR(this->get_logger(), "Invalid event handle size."); + return; + } + memcpy(&event_handle, msg->cuda_event_handle.data(), sizeof(cudaIpcEventHandle_t)); + auto err = cudaIpcOpenEventHandle(&event, event_handle); + if (err != cudaSuccess) { + RCLCPP_ERROR( + this->get_logger(), "cudaIpcOpenEventHandle failed: %s", + cudaGetErrorString(err)); + return; + } + + // The event may record the completion of the previous operation + err = cudaEventSynchronize(event); + if (err != cudaSuccess) { + RCLCPP_ERROR( + this->get_logger(), "CUDA event synchronize failed: %s", + cudaGetErrorString(err)); + return; + } + } + + // Compare UID if exists + if (!msg_uid.empty()) { + std::string shm_name = std::to_string(pid) + std::to_string(fd); + host_ipc_buffer_ = std::make_shared(shm_name, HostIPCBuffer::Mode::OPEN); + if (!host_ipc_buffer_->refcoun_inc_if_uid_match(msg_uid)) { + RCLCPP_WARN(this->get_logger(), "Failed to match UID, skip."); + return; + } + } + + if (handle_ptr_map_.find(msg->data.data()[1]) != handle_ptr_map_.end()) { + gpu_buffer = handle_ptr_map_[msg->data.data()[1]]; + RCLCPP_DEBUG(this->get_logger(), "Found FD in local map."); + } else { + int pidfd = syscall(SYS_pidfd_open, msg->data.data()[0], 0); + if (pidfd <= 0) { + perror("SYS_pidfd_open failed"); + } + int fd = syscall(SYS_pidfd_getfd_nitros_bridge, pidfd, msg->data.data()[1], 0); + if (fd <= 0) { + perror("SYS_pidfd_getfd failed"); + } + + auto cuda_err = cuMemImportFromShareableHandle( + &generic_allocation_handle, + reinterpret_cast((uintptr_t)fd), + CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + this->get_logger(), "Failed to call cuMemImportFromShareableHandle %s", + error_str); + throw std::runtime_error("[NITROS Bridge] cuMemImportFromShareableHandle Error"); + } + + CUmemAllocationProp prop = {}; + prop.type = CU_MEM_ALLOCATION_TYPE_PINNED; + prop.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + prop.location.id = 0; + prop.requestedHandleTypes = CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR; + size_t granularity = 0; + + cuda_err = cuMemGetAllocationGranularity( + &granularity, &prop, CU_MEM_ALLOC_GRANULARITY_MINIMUM); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + this->get_logger(), "Failed to call cuMemGetAllocationGranularity %s", + error_str); + throw std::runtime_error( + "[NITROS Bridge] cuMemGetAllocationGranularity Error"); + } + + auto alloc_size = msg->height * msg->step; + // The alloc size must be the integral multiple of granularity + alloc_size = alloc_size - (alloc_size % granularity) + granularity; + + cuda_err = cuMemAddressReserve(&gpu_buffer, alloc_size, 0, 0, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR(this->get_logger(), "Failed to call cuMemAddressReserve %s", error_str); + throw std::runtime_error("[NITROS Bridge] cuMemAddressReserve Error"); + } + + cuda_err = cuMemMap(gpu_buffer, alloc_size, 0, generic_allocation_handle, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR(this->get_logger(), "Failed to call cuMemMap %s", error_str); + throw std::runtime_error("[NITROS Bridge] cuMemMap Error"); + } + + CUmemAccessDesc accessDesc = {}; + accessDesc.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + accessDesc.location.id = 0; + accessDesc.flags = CU_MEM_ACCESS_FLAGS_PROT_READWRITE; + cuda_err = cuMemSetAccess(gpu_buffer, alloc_size, &accessDesc, 1); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR(this->get_logger(), "Failed to call cuMemSetAccess %s", error_str); + throw std::runtime_error("[NITROS Bridge] cuMemMap Error"); + } + handle_ptr_map_[msg->data.data()[1]] = gpu_buffer; + } + + nvidia::isaac_ros::nitros::NitrosImage nitros_image = + nvidia::isaac_ros::nitros::NitrosImageBuilder() + .WithHeader(msg->header) + .WithEncoding(img_encodings::RGB8) + .WithDimensions(msg->height, msg->width) + .WithGpuData(reinterpret_cast(gpu_buffer)) + .Build(); + + nitros_pub_->publish(nitros_image); + + // Update refcount if it exists + if (!msg_uid.empty()) { + host_ipc_buffer_->refcount_dec(); + } + RCLCPP_DEBUG(this->get_logger(), "NITROS Image is Published from NITROS Bridge."); +} + +void ImageConverterNode::ROSToBridgeCallback(const nvidia::isaac_ros::nitros::NitrosImageView view) +{ + cuCtxSetCurrent(ctx_); + + if (first_msg_received_ == false) { + ipc_buffer_manager_ = std::make_shared( + num_blocks_, view.GetSizeInBytes(), timeout_); + first_msg_received_ = true; + } + + auto ipc_buffer = ipc_buffer_manager_->find_next_available_buffer(); + + isaac_ros_nitros_bridge_interfaces::msg::NitrosBridgeImage img_msg; + img_msg.header.frame_id = view.GetFrameId(); + img_msg.header.stamp.sec = view.GetTimestampSeconds(); + img_msg.header.stamp.nanosec = view.GetTimestampNanoseconds(); + img_msg.height = view.GetHeight(); + img_msg.width = view.GetWidth(); + img_msg.encoding = view.GetEncoding(); + img_msg.step = view.GetSizeInBytes() / view.GetHeight(); + + auto cuda_err = cuMemcpyDtoD( + ipc_buffer->d_ptr, + (CUdeviceptr)(view.GetGpuData()), + view.GetSizeInBytes()); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + this->get_logger(), "Failed to call cuMemcpyDtoD %s", + error_str); + throw std::runtime_error("[NITROS Bridge] cuMemcpyDtoD Error"); + } + + // cuMemcpyDtoD is an aysnchronize call, wait until it complete. + cuCtxSynchronize(); + + img_msg.data.push_back(ipc_buffer->pid); + img_msg.data.push_back(ipc_buffer->fd); + img_msg.uid = ipc_buffer->uid; + img_msg.device_id = 0; + + bridge_image_pub_->publish(img_msg); +} + +} // namespace nitros_bridge +} // namespace isaac_ros +} // namespace nvidia + +// Register as component +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(nvidia::isaac_ros::nitros_bridge::ImageConverterNode) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/src/tensor_list_converter_node.cpp b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/src/tensor_list_converter_node.cpp new file mode 100644 index 0000000..81ee18d --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/src/tensor_list_converter_node.cpp @@ -0,0 +1,338 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + + +#include +#include +#include + +#include "isaac_ros_nitros_bridge_ros2/tensor_list_converter_node.hpp" + + +#define SYS_pidfd_getfd_nitros_bridge 438 + + +namespace nvidia +{ +namespace isaac_ros +{ +namespace nitros_bridge +{ + +TensorListConverterNode::TensorListConverterNode(const rclcpp::NodeOptions options) +: rclcpp::Node("tensor_list_converter_node", options), + nitros_pub_{std::make_shared>( + this, "ros2_output_tensor_list", + nvidia::isaac_ros::nitros::nitros_tensor_list_nhwc_t::supported_type_name)}, + nitros_bridge_pub_{ + create_publisher( + "ros2_output_bridge_tensor_list", 10)}, + nitros_sub_{std::make_shared>( + this, "ros2_input_tensor_list", + nvidia::isaac_ros::nitros::nitros_tensor_list_nhwc_t::supported_type_name, + std::bind(&TensorListConverterNode::ROSToBridgeCallback, this, + std::placeholders::_1))}, + nitros_bridge_sub_{ + create_subscription( + "ros2_input_bridge_tensor_list", 10, + std::bind(&TensorListConverterNode::BridgeToROSCallback, this, + std::placeholders::_1))}, + num_blocks_(declare_parameter("num_blocks", 40)), + timeout_(declare_parameter("timeout", 500)) +{ + cudaSetDevice(0); + cuDevicePrimaryCtxRetain(&ctx_, 0); + + cudaEventCreateWithFlags(&event_, cudaEventInterprocess | cudaEventDisableTiming); + cudaIpcGetEventHandle(reinterpret_cast(&ipc_event_handle_), event_); +} + +TensorListConverterNode::~TensorListConverterNode() = default; + + +void TensorListConverterNode::BridgeToROSCallback( + const isaac_ros_nitros_bridge_interfaces::msg::NitrosBridgeTensorList::SharedPtr msg) +{ + cuCtxSetCurrent(ctx_); + + CUdeviceptr gpu_buffer = 0ULL; + CUmemGenericAllocationHandle generic_allocation_handle; + + auto msg_pid = msg->pid; + auto msg_fd = msg->fd; + auto msg_uid = msg->uid; + + cudaEvent_t event; + cudaIpcEventHandle_t event_handle; + // Construct CUDA IPC event handle if it exists + if (msg->cuda_event_handle.size() != 0) { + if (msg->cuda_event_handle.size() != sizeof(cudaIpcEventHandle_t)) { + RCLCPP_ERROR(this->get_logger(), "Invalid event handle size."); + return; + } + memcpy(&event_handle, msg->cuda_event_handle.data(), sizeof(cudaIpcEventHandle_t)); + auto err = cudaIpcOpenEventHandle(&event, event_handle); + if (err != cudaSuccess) { + fprintf(stderr, "cudaIpcOpenEventHandle failed: %s\n", cudaGetErrorString(err)); + return; + } + + // The event may record the completion of the previous operation + err = cudaEventSynchronize(event); + if (err != cudaSuccess) { + fprintf(stderr, "CUDA event synchronize failed: %s\n", cudaGetErrorString(err)); + return; + } + } + + // Get total size of all tensors + size_t total_size = 0; + for (size_t i = 0; i < msg->tensors.size(); i++) { + auto tensor = msg->tensors[i]; + if (tensor.shape.rank == 0) { + RCLCPP_INFO(this->get_logger(), "Received tensor with rank 0, skip."); + continue; + } + if (tensor.shape.dims.size() == 0) { + RCLCPP_ERROR(this->get_logger(), "Invalid tensor shape."); + return; + } + if (tensor.strides.size() == 0) { + RCLCPP_ERROR(this->get_logger(), "Invalid tensor strides."); + return; + } + total_size += tensor.strides[0] * tensor.shape.dims[0]; + } + + // Compare UID if it exists + // Compare UID if exists + if (!msg_uid.empty()) { + std::string shm_name = std::to_string(msg_pid) + std::to_string(msg_fd); + host_ipc_buffer_ = std::make_shared(shm_name, HostIPCBuffer::Mode::OPEN); + if (!host_ipc_buffer_->refcoun_inc_if_uid_match(msg_uid)) { + RCLCPP_WARN(this->get_logger(), "Failed to match UID, skip."); + return; + } + } + + if (handle_ptr_map_.find(msg_fd) != handle_ptr_map_.end()) { + gpu_buffer = handle_ptr_map_[msg_fd]; + RCLCPP_DEBUG(this->get_logger(), "Found FD in local map."); + } else { + int pidfd = syscall(SYS_pidfd_open, msg_pid, 0); + if (pidfd <= 0) { + perror("SYS_pidfd_open failed"); + } + int fd = syscall(SYS_pidfd_getfd_nitros_bridge, pidfd, msg_fd, 0); + if (fd <= 0) { + perror("SYS_pidfd_getfd failed"); + } + + auto cuda_err = cuMemImportFromShareableHandle( + &generic_allocation_handle, + reinterpret_cast((uintptr_t)fd), + CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + this->get_logger(), "Failed to call cuMemImportFromShareableHandle %s", + error_str); + throw std::runtime_error( + "[NITROS Bridge] cuMemImportFromShareableHandle Error"); + } + + CUmemAllocationProp prop = {}; + prop.type = CU_MEM_ALLOCATION_TYPE_PINNED; + prop.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + prop.location.id = 0; + prop.requestedHandleTypes = CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR; + size_t granularity = 0; + + cuda_err = cuMemGetAllocationGranularity( + &granularity, &prop, CU_MEM_ALLOC_GRANULARITY_MINIMUM); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + this->get_logger(), "Failed to call cuMemGetAllocationGranularity %s", + error_str); + throw std::runtime_error( + "[NITROS Bridge] cuMemGetAllocationGranularity Error"); + } + + // The alloc size must be the integral multiple of granularity + auto alloc_size = total_size - (total_size % granularity) + granularity; + + cuda_err = cuMemAddressReserve(&gpu_buffer, alloc_size, 0, 0, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR(this->get_logger(), "Failed to call cuMemAddressReserve %s", error_str); + throw std::runtime_error( + "[NITROS Bridge] cuMemAddressReserve Error"); + } + + cuda_err = cuMemMap(gpu_buffer, alloc_size, 0, generic_allocation_handle, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR(this->get_logger(), "Failed to call cuMemMap %s", error_str); + throw std::runtime_error( + "[NITROS Bridge] cuMemMap Error"); + } + + CUmemAccessDesc accessDesc = {}; + accessDesc.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + accessDesc.location.id = 0; + accessDesc.flags = CU_MEM_ACCESS_FLAGS_PROT_READWRITE; + cuda_err = cuMemSetAccess(gpu_buffer, alloc_size, &accessDesc, 1); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR(this->get_logger(), "Failed to call cuMemSetAccess %s", error_str); + throw std::runtime_error( + "[NITROS Bridge] cuMemSetAccess Error"); + } + handle_ptr_map_[msg_fd] = gpu_buffer; + } + + auto nitros_tensor_list_builder = + nvidia::isaac_ros::nitros::NitrosTensorListBuilder() + .WithHeader(msg->header); + + int offset = 0; + for (size_t i = 0; i < msg->tensors.size(); i++) { + auto ros_tensor = msg->tensors[i]; + auto tensor_shape = std::vector{ + ros_tensor.shape.dims.begin(), ros_tensor.shape.dims.end()}; + + auto cur_tensor = nvidia::isaac_ros::nitros::NitrosTensorBuilder() + .WithShape(nvidia::isaac_ros::nitros::NitrosTensorShape(tensor_shape)) + .WithDataType(nvidia::isaac_ros::nitros::NitrosDataType::kFloat32) + .WithData(reinterpret_cast(gpu_buffer + offset)) + .Build(); + nitros_tensor_list_builder.AddTensor(ros_tensor.name.c_str(), cur_tensor); + offset += ros_tensor.data.size(); + } + + auto nitros_tensor_list = nitros_tensor_list_builder.Build(); + + nitros_pub_->publish(nitros_tensor_list); + + // Update refcount if it exists + if (!msg_uid.empty()) { + host_ipc_buffer_->refcount_dec(); + } + + RCLCPP_DEBUG(this->get_logger(), "NITROS Tensor List is Published from NITROS Bridge."); +} + +void TensorListConverterNode::ROSToBridgeCallback( + const nvidia::isaac_ros::nitros::NitrosTensorListView view) +{ + cuCtxSetCurrent(ctx_); + + auto tensor_count = view.GetTensorCount(); + // Get total size first + if (tensor_count == 0) { + RCLCPP_INFO(this->get_logger(), "No tensor found in the list."); + return; + } + auto tensor_list = view.GetAllTensor(); + size_t total_size = 0; + + // Get total size of all tensors + for (size_t i = 0; i < tensor_count; i++) { + auto tensor = tensor_list[i]; + auto tensor_bytes_per_element = tensor.GetBytesPerElement(); + auto tensor_element_count = tensor.GetElementCount(); + total_size += tensor_element_count * tensor_bytes_per_element; + } + + // Create IPC buffer manager + if (first_msg_received_ == false) { + ipc_buffer_manager_ = std::make_shared( + num_blocks_, total_size, timeout_); + first_msg_received_ = true; + } + + auto ipc_buffer = ipc_buffer_manager_->find_next_available_buffer(); + isaac_ros_nitros_bridge_interfaces::msg::NitrosBridgeTensorList tensor_list_msg; + tensor_list_msg.header.frame_id = view.GetFrameId(); + tensor_list_msg.header.stamp.sec = view.GetTimestampSeconds(); + tensor_list_msg.header.stamp.nanosec = view.GetTimestampNanoseconds(); + + size_t offset = 0; + for (size_t i = 0; i < tensor_count; i++) { + auto tensor = tensor_list[i]; + auto tensor_shape = tensor.GetShape().shape(); + auto tensor_rank = tensor.GetRank(); + auto tensor_element_type = tensor.GetElementType(); + auto tensor_name = tensor.GetName(); + auto tensor_bytes_per_element = tensor.GetBytesPerElement(); + auto tensor_element_count = tensor.GetElementCount(); + std::vector tensor_dims; + std::vector tensor_strides; + for (uint32_t i = 0; i < tensor_rank; ++i) { + tensor_dims.push_back(tensor_shape.dimension(i)); + } + + isaac_ros_tensor_list_interfaces::msg::Tensor ros2_tensor; + ros2_tensor.name = tensor_name; + ros2_tensor.shape.dims = tensor_dims; + ros2_tensor.data_type = static_cast(tensor_element_type); + ros2_tensor.shape.rank = tensor_rank; + ros2_tensor.strides = tensor.GetStrides(); + + auto cuda_err = cuMemcpyDtoD( + ipc_buffer->d_ptr + offset, + (CUdeviceptr)(tensor.GetBuffer()), + tensor_element_count * tensor_bytes_per_element); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + RCLCPP_ERROR( + rclcpp::get_logger(""), "Failed to call cuMemcpyDtoD %s", + error_str); + throw std::runtime_error("[NITROS Bridge] cuMemcpyDtoD Error"); + } + offset += tensor_element_count * tensor_bytes_per_element; + + tensor_list_msg.tensors.push_back(ros2_tensor); + } + + // cuMemcpyDtoD is an aysnchronize call, wait until it complete. + cuCtxSynchronize(); + + tensor_list_msg.pid = ipc_buffer->pid; + tensor_list_msg.fd = ipc_buffer->fd; + tensor_list_msg.uid = ipc_buffer->uid; + tensor_list_msg.device_id = 0; + + nitros_bridge_pub_->publish(tensor_list_msg); +} + +} // namespace nitros_bridge +} // namespace isaac_ros +} // namespace nvidia + +// Register as component +#include "rclcpp_components/register_node_macro.hpp" +RCLCPP_COMPONENTS_REGISTER_NODE(nvidia::isaac_ros::nitros_bridge::TensorListConverterNode) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_image_pol.py b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_image_pol.py new file mode 100644 index 0000000..f7b875c --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_image_pol.py @@ -0,0 +1,176 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Proof-of-Life test for interprocess NITROS bridge image on ROS 2. + +NITROSBridgeImageConverter1(NITROSImage->NITROSBridgeImage) +NITROSBridgeImageConverter2(NITROSBridgeImage->NITROSImage) +""" + +import os +import pathlib +import subprocess +import time + +from isaac_ros_test import IsaacROSBaseTest, JSONConversion + +import launch +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing + +import pytest +import rclpy +from sensor_msgs.msg import Image + + +@pytest.mark.rostest +def generate_test_description(): + """Generate launch description with all ROS 2 nodes for testing.""" + ptace_result = subprocess.run(['cat', '/proc/sys/kernel/yama/ptrace_scope'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + pidfd_getfd_result = subprocess.run(['grep', 'pidfd_getfd', '/proc/kallsyms'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + if (ptace_result.stdout.strip() == '0' and pidfd_getfd_result.returncode == 0): + ros2_converter_1 = ComposableNode( + name='ros2_converter', + namespace='r2b', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::ImageConverterNode', + parameters=[{ + 'num_blocks': 5 + }], + remappings=[ + ('ros2_output_bridge_image', 'ros2_converter_output'), + ]) + + ros2_converter_2 = ComposableNode( + name='ros2_converter', + namespace='r2b', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::ImageConverterNode', + parameters=[{ + 'num_blocks': 5 + }], + remappings=[('ros2_input_bridge_image', 'ros2_converter_output')]) + + ros2_converter_1_container = ComposableNodeContainer( + name='ros2_converter_1_container', + namespace='r2b', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[ros2_converter_1], + output='screen', + arguments=['--ros-args', '--log-level', 'info']) + + ros2_converter_2_container = ComposableNodeContainer( + name='ros2_converter_2_container', + namespace='r2b', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[ros2_converter_2], + output='screen', + arguments=['--ros-args', '--log-level', 'info']) + + return IsaacROSNitrosBridgeTest.generate_test_description([ + ros2_converter_1_container, ros2_converter_2_container, + launch.actions.TimerAction(period=2.5, actions=[launch_testing.actions.ReadyToTest()]) + ]) + else: + IsaacROSNitrosBridgeTest.skip_test = True + return IsaacROSNitrosBridgeTest.generate_test_description( + [launch_testing.actions.ReadyToTest()]) + + +class IsaacROSNitrosBridgeTest(IsaacROSBaseTest): + """Validate Nitros Bridge on Image type.""" + + filepath = pathlib.Path(os.path.dirname(__file__)) + skip_test = False + + @IsaacROSBaseTest.for_each_test_case(subfolder='nitros_image') + def test_nitros_bridge_image(self, test_folder) -> None: + """Expect the image received from NitrosImage type conversion to be identical to source.""" + if self.skip_test: + self.skipTest('No ptrace permission! Skipping test.') + else: + IsaacROSNitrosBridgeTest.DEFAULT_NAMESPACE = 'r2b' + self.generate_namespace_lookup(['ros2_input_image', 'ros2_output_image']) + received_messages = {} + + received_image_sub = self.create_logging_subscribers( + subscription_requests=[('ros2_output_image', Image)], + received_messages=received_messages) + + image_pub = self.node.create_publisher(Image, self.namespaces['ros2_input_image'], + self.DEFAULT_QOS) + + try: + image = JSONConversion.load_image_from_json(test_folder / 'image.json') + timestamp = self.node.get_clock().now().to_msg() + image.header.stamp = timestamp + + # Wait at most TIMEOUT seconds for subscriber to respond + TIMEOUT = 30 + end_time = time.time() + TIMEOUT + + done = False + while time.time() < end_time: + image_pub.publish(image) + rclpy.spin_once(self.node, timeout_sec=0.1) + + # If we have received a message on the output topic, break + if 'ros2_output_image' in received_messages: + done = True + break + + self.assertTrue(done, "Didn't receive output on output_image topic!") + + received_image = received_messages['ros2_output_image'] + + print(f'Source image data size: {len(image.data)}') + print(f'Received image data size: {len(received_image.data)}') + + self.assertEqual(str(timestamp), str(received_image.header.stamp), + 'Timestamps do not match.') + + self.assertEqual( + len(image.data), len(received_image.data), + 'Source and received image sizes do not match: ' + + f'{len(image.data)} != {len(received_image.data)}') + + # Make sure that the source and received images are the same + self.assertEqual( + received_image.height, image.height, + 'Source and received image heights do not match: ' + + f'{image.height} != {received_image.height}') + self.assertEqual( + received_image.width, image.width, + 'Source and received image widths do not match: ' + + f'{image.width} != {received_image.width}') + + for i in range(len(image.data)): + self.assertEqual(image.data[i], received_image.data[i], + 'Source and received image pixels do not match') + + finally: + self.node.destroy_subscription(received_image_sub) + self.node.destroy_publisher(image_pub) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_pol.py b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_pol.py new file mode 100644 index 0000000..f643c07 --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_pol.py @@ -0,0 +1,141 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Proof-of-Life test for NITROS Bridge between ROS 1 and ROS 2. + +Need to run together with the ROS Noeitc example container. +""" + +import os +import pathlib +import time + +from isaac_ros_test import IsaacROSBaseTest, JSONConversion + +import launch +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing + +import pytest +import rclpy +from sensor_msgs.msg import Image + + +@pytest.mark.rostest +def generate_test_description(): + """Generate launch description with all ROS 2 nodes for testing.""" + ros2_converter = ComposableNode( + name='ros2_converter', + namespace='r2b', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::ImageConverterNode', + parameters=[{ + 'num_blocks': 40 + }], + remappings=[ + ('ros2_output_bridge_image', 'ros1_input_bridge_image'), + ('ros2_input_bridge_image', 'ros1_output_bridge_image') + ]) + + container = ComposableNodeContainer( + name='ros2_converter_container', + namespace='r2b', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[ros2_converter], + output='screen', + arguments=['--ros-args', '--log-level', 'info'] + ) + + return IsaacROSNitrosBridgeTest.generate_test_description([ + container, + launch.actions.TimerAction( + period=2.5, actions=[launch_testing.actions.ReadyToTest()]) + ]) + + +class IsaacROSNitrosBridgeTest(IsaacROSBaseTest): + """Validate Nitros Bridge on Image type.""" + + filepath = pathlib.Path(os.path.dirname(__file__)) + + @IsaacROSBaseTest.for_each_test_case(subfolder='nitros_image') + def test_nitros_bridge_image(self, test_folder) -> None: + """Expect the image received from NitrosImage type conversion to be identical to source.""" + IsaacROSNitrosBridgeTest.DEFAULT_NAMESPACE = 'r2b' + self.generate_namespace_lookup(['ros2_input_image', 'ros2_output_image']) + received_messages = {} + + received_image_sub = self.create_logging_subscribers( + subscription_requests=[('ros2_output_image', Image)], + received_messages=received_messages + ) + + image_pub = self.node.create_publisher( + Image, self.namespaces['ros2_input_image'], self.DEFAULT_QOS) + + try: + image = JSONConversion.load_image_from_json( + test_folder / 'image.json') + timestamp = self.node.get_clock().now().to_msg() + image.header.stamp = timestamp + + # Wait at most TIMEOUT seconds for subscriber to respond + TIMEOUT = 30 + end_time = time.time() + TIMEOUT + + done = False + while time.time() < end_time: + image_pub.publish(image) + rclpy.spin_once(self.node, timeout_sec=0.1) + + # If we have received a message on the output topic, break + if 'ros2_output_image' in received_messages: + done = True + break + + self.assertTrue(done, "Didn't receive output on output_image topic!") + + received_image = received_messages['ros2_output_image'] + + print(f'Source image data size: {len(image.data)}') + print(f'Received image data size: {len(received_image.data)}') + + self.assertEqual(str(timestamp), str(received_image.header.stamp), + 'Timestamps do not match.') + + self.assertEqual(len(image.data), len(received_image.data), + 'Source and received image sizes do not match: ' + + f'{len(image.data)} != {len(received_image.data)}') + + # Make sure that the source and received images are the same + self.assertEqual(received_image.height, image.height, + 'Source and received image heights do not match: ' + + f'{image.height} != {received_image.height}') + self.assertEqual(received_image.width, image.width, + 'Source and received image widths do not match: ' + + f'{image.width} != {received_image.width}') + + for i in range(len(image.data)): + self.assertEqual(image.data[i], received_image.data[i], + 'Source and received image pixels do not match') + + finally: + self.node.destroy_subscription(received_image_sub) + self.node.destroy_publisher(image_pub) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_tensor_list_pol.py b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_tensor_list_pol.py new file mode 100644 index 0000000..676f855 --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/isaac_ros_nitros_bridge_tensor_list_pol.py @@ -0,0 +1,196 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Proof-of-Life test for interprocess NITROS bridge tensor list on ROS 2. + +NITROSBridgeTensorListConverter1(NITROSTensorList->NITROSBridgeTensorList) +NITROSBridgeTensorListConverter2(NITROSBridgeTensorList->NITROSTensorList) +""" + +import os +import pathlib +import subprocess +import time + +from isaac_ros_tensor_list_interfaces.msg import Tensor, TensorList, TensorShape +from isaac_ros_test import IsaacROSBaseTest + +import launch +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +import launch_testing +import numpy as np + +import pytest +import rclpy + + +@pytest.mark.rostest +def generate_test_description(): + """Generate launch description with all ROS 2 nodes for testing.""" + ptace_result = subprocess.run(['cat', '/proc/sys/kernel/yama/ptrace_scope'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + pidfd_getfd_result = subprocess.run(['grep', 'pidfd_getfd', '/proc/kallsyms'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + if (ptace_result.stdout.strip() == '0' and pidfd_getfd_result.returncode == 0): + tensor_list_converter_1 = ComposableNode( + name='ros2_converter', + namespace='r2b', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::TensorListConverterNode', + parameters=[{ + 'num_blocks': 5 + }], + remappings=[ + ('ros2_output_bridge_tensor_list', 'ros2_converter_output'), + ]) + + tensor_list_converter_2 = ComposableNode( + name='ros2_converter', + namespace='r2b', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::TensorListConverterNode', + parameters=[{ + 'num_blocks': 5 + }], + remappings=[('ros2_input_bridge_tensor_list', 'ros2_converter_output')]) + + tensor_list_converter_container_1 = ComposableNodeContainer( + name='ros2_converter_1_container', + namespace='r2b', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[tensor_list_converter_1], + output='screen', + arguments=['--ros-args', '--log-level', 'info']) + + tensor_list_converter_container_2 = ComposableNodeContainer( + name='ros2_converter_2_container', + namespace='r2b', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[tensor_list_converter_2], + output='screen', + arguments=['--ros-args', '--log-level', 'info']) + + return IsaacROSNitrosBridgeTest.generate_test_description([ + tensor_list_converter_container_1, tensor_list_converter_container_2, + launch.actions.TimerAction(period=2.5, actions=[launch_testing.actions.ReadyToTest()]) + ]) + else: + IsaacROSNitrosBridgeTest.skip_test = True + return IsaacROSNitrosBridgeTest.generate_test_description( + [launch_testing.actions.ReadyToTest()]) + + +class IsaacROSNitrosBridgeTest(IsaacROSBaseTest): + """Validate Nitros Bridge on TensorList type.""" + + filepath = pathlib.Path(os.path.dirname(__file__)) + skip_test = False + + def test_nitros_bridge_tensor_list(self) -> None: + """Expect the received tensor list to be identical to source.""" + if self.skip_test: + self.skipTest('No ptrace permission! Skipping test.') + else: + IsaacROSNitrosBridgeTest.DEFAULT_NAMESPACE = 'r2b' + self.generate_namespace_lookup(['ros2_input_tensor_list', 'ros2_output_tensor_list']) + received_messages = {} + + received_tensor_list_sub = self.create_logging_subscribers( + subscription_requests=[('ros2_output_tensor_list', TensorList)], + received_messages=received_messages) + + tensor_list_pub = self.node.create_publisher(TensorList, + self.namespaces['ros2_input_tensor_list'], + self.DEFAULT_QOS) + + try: + DATA_TYPE = 9 + INPUT_TENSOR_DIMENSIONS = [10, 3, 100, 100] + INPUT_TENSOR_NAME = 'input' + INPUT_TENSOR_STRIDE = 4 + + tensor_list = TensorList() + tensor = Tensor() + tensor_shape = TensorShape() + + tensor_shape.rank = len(INPUT_TENSOR_DIMENSIONS) + tensor_shape.dims = INPUT_TENSOR_DIMENSIONS + + tensor.shape = tensor_shape + tensor.name = INPUT_TENSOR_NAME + tensor.data_type = DATA_TYPE + tensor.strides = [] + + data_length = INPUT_TENSOR_STRIDE * np.prod(INPUT_TENSOR_DIMENSIONS) + tensor.data = np.random.randint(256, size=data_length).tolist() + + tensor_list.tensors = [tensor, tensor] + timestamp = self.node.get_clock().now().to_msg() + tensor_list.header.stamp = timestamp + + # Wait at most TIMEOUT seconds for subscriber to respond + TIMEOUT = 30 + end_time = time.time() + TIMEOUT + + done = False + while time.time() < end_time: + tensor_list_pub.publish(tensor_list) + rclpy.spin_once(self.node, timeout_sec=0.1) + + # If we have received a message on the output topic, break + if 'ros2_output_tensor_list' in received_messages: + done = True + break + + self.assertTrue(done, "Didn't receive output on output_tensor_list topic!") + + received_tensor_list = received_messages['ros2_output_tensor_list'] + self.assertEqual(len(tensor_list.tensors), len(received_tensor_list.tensors), + 'Source and received tensor list size do not match') + + for i in range(len(tensor_list.tensors)): + source_tensor = tensor_list.tensors[i] + received_tensor = received_tensor_list.tensors[i] + self.assertEqual(source_tensor.name, received_tensor.name, + 'Source and received tensor names do not match') + self.assertEqual(source_tensor.name, received_tensor.name, + 'Source and received tensor names do not match') + self.assertEqual(source_tensor.data_type, received_tensor.data_type, + 'Source and received tensor data types do not match') + self.assertEqual(source_tensor.shape.rank, received_tensor.shape.rank, + 'Source and received tensor ranks do not match') + self.assertEqual(source_tensor.shape.dims, received_tensor.shape.dims, + 'Source and received tensor dimensions do not match') + self.assertEqual(len(source_tensor.data), len(received_tensor.data), + 'Source and received tensor data do not match') + self.assertEqual(str(timestamp), str(received_tensor_list.header.stamp), + 'Timestamps do not match.') + + for j in range(len(source_tensor.data)): + self.assertEqual(source_tensor.data[j], received_tensor.data[j], + 'Source and received image pixels do not match') + + finally: + self.node.destroy_subscription(received_tensor_list_sub) + self.node.destroy_publisher(tensor_list_pub) diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/test_cases/nitros_image/profile/NVIDIAprofile.png b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/test_cases/nitros_image/profile/NVIDIAprofile.png new file mode 100644 index 0000000..0e0ae64 --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/test_cases/nitros_image/profile/NVIDIAprofile.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aa345be1c5972fa1ad601db83ec2fd56c5fb428e09de166b76b72d266c4cb346 +size 94919 diff --git a/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/test_cases/nitros_image/profile/image.json b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/test_cases/nitros_image/profile/image.json new file mode 100644 index 0000000..faaec9d --- /dev/null +++ b/isaac_ros_nitros_bridge/isaac_ros_nitros_bridge_ros2/test/test_cases/nitros_image/profile/image.json @@ -0,0 +1,4 @@ +{ + "image": "NVIDIAprofile.png", + "encoding": "bgr8" +} \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/resources/quickstart.bag/metadata.yaml b/isaac_ros_nitros_bridge/resources/quickstart.bag/metadata.yaml new file mode 100644 index 0000000..009b0ee --- /dev/null +++ b/isaac_ros_nitros_bridge/resources/quickstart.bag/metadata.yaml @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5dd7b3038c4e9a03311d6123502a6f4224417c2360c039c61148e15328b97d5e +size 1476 diff --git a/isaac_ros_nitros_bridge/resources/quickstart.bag/quickstart.bag_0.db3 b/isaac_ros_nitros_bridge/resources/quickstart.bag/quickstart.bag_0.db3 new file mode 100644 index 0000000..1c490a8 --- /dev/null +++ b/isaac_ros_nitros_bridge/resources/quickstart.bag/quickstart.bag_0.db3 @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aca0bfa2cbb013092f93fe3e83dd6608090d88d8b34c0c80dcff5e464f41357e +size 418136064 diff --git a/isaac_ros_nitros_bridge/resources/quickstart.bag/quickstart.bag_0.db3.zstd b/isaac_ros_nitros_bridge/resources/quickstart.bag/quickstart.bag_0.db3.zstd new file mode 100644 index 0000000..f421d96 --- /dev/null +++ b/isaac_ros_nitros_bridge/resources/quickstart.bag/quickstart.bag_0.db3.zstd @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:14a4d829dc8baf05c2e1c60d7d66d1e924add3cf5d313124deca670050cea989 +size 232126462 diff --git a/isaac_ros_nitros_bridge/resources/unet_sample_data_ros1.bag b/isaac_ros_nitros_bridge/resources/unet_sample_data_ros1.bag new file mode 100644 index 0000000..d095c56 --- /dev/null +++ b/isaac_ros_nitros_bridge/resources/unet_sample_data_ros1.bag @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:da28d6e18a7c7d2cd7d0a607ae64df097e09e03d104c733a04457ed96f984a96 +size 2300750 diff --git a/isaac_ros_nitros_bridge/ros1/COLCON_IGNORE b/isaac_ros_nitros_bridge/ros1/COLCON_IGNORE new file mode 100644 index 0000000..e69de29 diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/CMakeLists.txt b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/CMakeLists.txt new file mode 100644 index 0000000..ce0022b --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/CMakeLists.txt @@ -0,0 +1,78 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +cmake_minimum_required(VERSION 3.22.1) +project(isaac_ros_nitros_bridge_ros1) + +if($ENV{ROS_VERSION} EQUAL 2) + message(STATUS "Skip package ${PROJECT_NAME} for ROS 2") + return() +endif() + +find_package( + catkin REQUIRED + COMPONENTS message_generation + std_msgs + sensor_msgs + roscpp + nodelet) +find_package(isaac_ros_nitros_bridge_msgs REQUIRED) +find_package(CUDAToolkit REQUIRED) +set(CMAKE_CUDA_ARCHITECTURES "89;87;86;80;75;72;70;61;60") + +#find_package(cv_bridge REQUIRED) +#find_package(OpenCV 4 REQUIRED COMPONENTS opencv_core opencv_imgproc opencv_imgcodecs) + +include_directories( + include + ${CUDA_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ${isaac_ros_nitros_bridge_msgs_INCLUDE_DIRS}) + +catkin_package(CATKIN_DEPENDS message_runtime std_msgs sensor_msgs isaac_ros_nitros_bridge_msgs) + +############# +## Library ## +############# + +add_library(isaac_ros_nitros_bridge_ros1 + src/image_converter_node.cpp) + +target_link_libraries(isaac_ros_nitros_bridge_ros1 + ${catkin_LIBRARIES} + CUDA::cudart + CUDA::cuda_driver +) + +############# +## Install ## +############# + +install(TARGETS isaac_ros_nitros_bridge_ros1 + DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + +install(FILES + launch/nitros_bridge_convert_forward.launch + launch/nitros_bridge_forward.launch + launch/nitros_bridge_image_converter.launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + +install(FILES + nodelet_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/include/image_converter_node.hpp b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/include/image_converter_node.hpp new file mode 100644 index 0000000..b210929 --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/include/image_converter_node.hpp @@ -0,0 +1,88 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ISAAC_ROS_NITROS_BRIDGE_ROS1__IMAGE_CONVERTER_NODE_HPP_ +#define ISAAC_ROS_NITROS_BRIDGE_ROS1__IMAGE_CONVERTER_NODE_HPP_ + +#include +#include +#include +#include +#include + +#include "ros/ros.h" + +#include "ipc_buffer_manager.hpp" +#include "sensor_msgs/Image.h" +#include "isaac_ros_nitros_bridge_msgs/NitrosBridgeImage.h" + +namespace nvidia +{ +namespace isaac_ros +{ +namespace nitros_bridge +{ + +class ImageConverterNode : public nodelet::Nodelet +{ +public: + ImageConverterNode() {} + +private: + virtual void onInit() override; + + // Convert stub message into managed NITROS message + void BridgeToROSCallback( + const isaac_ros_nitros_bridge_msgs::NitrosBridgeImage::ConstPtr & msg); + + // Copy managed NITROS message data into IPC memory pool and convert to bridge message + void ROSToBridgeCallback(const sensor_msgs::Image::ConstPtr & msg); + + // Publisher for output image messages + ros::Publisher image_pub_; + // Publisher for output bridge messages + ros::Publisher bridge_image_pub_; + // Subscription to input image messages + ros::Subscriber image_sub_; + // Subscription to input bridge messages + ros::Subscriber bridge_image_sub_; + + // Number of blocks of the device memory pool + int num_blocks_; + // Timeout in microsec to waiting for a buffer to be available + int timeout_; + // Map between FD and device memory pointer + std::map handle_ptr_map_; + // CUDA IPC memory pool manager + std::shared_ptr ipc_buffer_manager_; + // Shared memory based IPC buffer for refcount and UID + std::shared_ptr host_ipc_buffer_; + // If received the first message + bool first_msg_received_ = false; + // CUDA driver context + CUcontext ctx_; + // CUDA IPC event handle sent by the sender + cudaIpcEventHandle_t ipc_event_handle_; + // CUDA event export from IPC event to synchronize the upstream + cudaEvent_t event_; +}; + +} // namespace nitros_bridge +} // namespace isaac_ros +} // namespace nvidia + +#endif // ISAAC_ROS_NITROS_BRIDGE_ROS1__IMAGE_CONVERTER_NODE_HPP_ diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/include/ipc_buffer_manager.hpp b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/include/ipc_buffer_manager.hpp new file mode 100644 index 0000000..801e1cc --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/include/ipc_buffer_manager.hpp @@ -0,0 +1,304 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ISAAC_ROS_NITROS_BRIDGE_ROS1__IPC_BUFFER_MANAGER_HPP_ +#define ISAAC_ROS_NITROS_BRIDGE_ROS1__IPC_BUFFER_MANAGER_HPP_ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ros/ros.h" + + +namespace nvidia +{ +namespace isaac_ros +{ + +namespace nitros_bridge +{ + +// Size of shared memory object in bytes +constexpr size_t kSharedMemorySize = 1024; + +struct DeviceIPCBuffer +{ + CUdeviceptr d_ptr; + CUmemGenericAllocationHandle generic_allocation_handle; + int pid; + int fd; + std::string uid; + size_t index; +}; + +struct HostIPCBuffer +{ + enum class Mode {CREATE, OPEN}; + std::shared_ptr shm_object_ = nullptr; + std::shared_ptr mutex_ = nullptr; + std::shared_ptr shm_ptr_ = nullptr; + boost::uuids::uuid * uid_ = nullptr; + int32_t * refcount_ = nullptr; + int start_time_ = 0; + + HostIPCBuffer(const std::string & shm_name, const Mode mode) + { + if (mode == Mode::CREATE) { + shm_object_ = std::make_shared( + boost::interprocess::open_or_create, + shm_name.c_str(), boost::interprocess::read_write); + shm_object_->truncate(kSharedMemorySize); + mutex_ = std::make_shared( + boost::interprocess::open_or_create, (shm_name).c_str()); + shm_ptr_ = std::make_shared( + *shm_object_, boost::interprocess::read_write); + refcount_ = static_cast(shm_ptr_->get_address()); + uid_ = static_cast(shm_ptr_->get_address() + sizeof(int)); + + // Initialize refcount and UID + *refcount_ = 0; + *uid_ = boost::uuids::random_generator()(); + } else { + try { + shm_object_ = std::make_shared( + boost::interprocess::open_only, shm_name.c_str(), boost::interprocess::read_write); + mutex_ = std::make_shared( + boost::interprocess::open_only, (shm_name).c_str()); + shm_ptr_ = std::make_shared( + *shm_object_, boost::interprocess::read_write); + refcount_ = static_cast(shm_ptr_->get_address()); + uid_ = static_cast(shm_ptr_->get_address() + sizeof(int)); + } catch (const boost::interprocess::interprocess_exception & ex) { + ROS_ERROR("Failed to open shared memory object %s", ex.what()); + throw std::runtime_error("Failed to open shared memory object"); + } + } + } + + bool reset_if_refcount_zero() + { + boost::interprocess::scoped_lock lock(*mutex_); + if (*refcount_ == 0) { + // Reset the start time and UID + *uid_ = boost::uuids::random_generator()(); + start_time_ = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + return true; + } + return false; + } + + bool refcoun_inc_if_uid_match(const std::string & received_uid) + { + // The UID compare and refcount increment should be atomic + boost::interprocess::scoped_lock lock(*mutex_); + if (boost::uuids::to_string(*uid_) == received_uid) { + *refcount_ += 1; + return true; + } + return false; + } + + void refcount_inc() + { + boost::interprocess::scoped_lock lock(*mutex_); + *refcount_ += 1; + } + + void refcount_dec() + { + boost::interprocess::scoped_lock lock(*mutex_); + if (refcount_ == 0) { + ROS_ERROR("Refcount is already zero."); + return; + } + *refcount_ -= 1; + } + + std::string get_uid() + { + boost::interprocess::scoped_lock lock(*mutex_); + auto uid = boost::uuids::to_string(*uid_); + return uid; + } +}; + +class IPCBufferManager +{ +public: + IPCBufferManager() = default; + + // Constructor, create device memory buffers and export to FD + IPCBufferManager(size_t buffer_count, size_t buffer_step, int64_t timeout) + { + buffer_count_ = buffer_count; + buffer_step_ = buffer_step; + timeout_ = timeout; + + CUmemAllocationProp prop = {}; + prop.type = CU_MEM_ALLOCATION_TYPE_PINNED; + prop.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + prop.location.id = 0; + prop.requestedHandleTypes = CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR; + size_t granularity = 0; + auto cuda_err = cuMemGetAllocationGranularity( + &granularity, &prop, CU_MEM_ALLOC_GRANULARITY_MINIMUM); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemGetAllocationGranularity %s", error_str); + } + alloc_size_ = buffer_step - (buffer_step % granularity) + granularity; + + for (size_t index = 0; index < buffer_count_; index++) { + // Create shareable device memory buffer + CUmemGenericAllocationHandle generic_allocation_handle; + auto cuda_err = cuMemCreate(&generic_allocation_handle, alloc_size_, &prop, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemCreate %s", error_str); + } + + int fd = -1; + cuda_err = cuMemExportToShareableHandle( + reinterpret_cast(&fd), + generic_allocation_handle, + CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR( "Failed to cuMemExportToShareableHandle %s", error_str); + } + + CUdeviceptr d_ptr = 0ULL; + cuda_err = cuMemAddressReserve(&d_ptr, alloc_size_, 0, 0, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemCreate %s", error_str); + } + + cuda_err = cuMemMap(d_ptr, alloc_size_, 0, generic_allocation_handle, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemCreate %s", error_str); + } + + CUmemAccessDesc accessDesc = {}; + accessDesc.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + accessDesc.location.id = 0; + accessDesc.flags = CU_MEM_ACCESS_FLAGS_PROT_READWRITE; + cuda_err = cuMemSetAccess(d_ptr, alloc_size_, &accessDesc, 1); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemSetAccess %s", error_str); + } + + // Create host shared memory object + std::string shm_name = std::to_string(getpid()) + std::to_string(fd); + std::shared_ptr host_ipc_buffer = + std::make_shared(shm_name, HostIPCBuffer::Mode::CREATE); + std::shared_ptr device_ipc_buffer = + std::make_shared( + DeviceIPCBuffer{ + d_ptr, generic_allocation_handle, getpid(), + fd, host_ipc_buffer->get_uid(), index}); + host_ipc_buffers_.push_back(host_ipc_buffer); + device_ipc_buffers_.push_back(device_ipc_buffer); + } + } + + // Destructor, free the alloacted device memory pool + ~IPCBufferManager() + { + for (size_t i = 0; i < buffer_count_; i++) { + cuMemRelease(device_ipc_buffers_[i]->generic_allocation_handle); + cuMemUnmap(device_ipc_buffers_[i]->d_ptr, alloc_size_); + std::string shm_name = + std::to_string(device_ipc_buffers_[i]->pid) + std::to_string(device_ipc_buffers_[i]->fd); + boost::interprocess::named_mutex::remove(shm_name.c_str()); + boost::interprocess::shared_memory_object::remove(shm_name.c_str()); + } + } + + // Move the index to next available device memory block + std::shared_ptr find_next_available_buffer() + { + auto last_handle_index = current_handle_index_; + while (true) { + auto current_time = std::chrono::duration_cast( + std::chrono::system_clock::now().time_since_epoch()).count(); + // TODO(yuankunz) :Reset the timeout everytime the refount is 0 + auto start_time = host_ipc_buffers_[current_handle_index_]->start_time_; + if (current_time - start_time > timeout_) { + if (host_ipc_buffers_[current_handle_index_]->reset_if_refcount_zero()) { + device_ipc_buffers_[current_handle_index_]->uid = + host_ipc_buffers_[current_handle_index_]->get_uid(); + auto ret_device_buffer = device_ipc_buffers_[current_handle_index_]; + current_handle_index_ = (current_handle_index_ + 1) % buffer_count_; + return ret_device_buffer; + } + } else { + current_handle_index_ = (current_handle_index_ + 1) % buffer_count_; + } + if (current_handle_index_ == last_handle_index) { + ROS_INFO("No available buffer, re-check after 1 ms"); + std::this_thread::sleep_for(std::chrono::milliseconds(1)); + } + } + } + +private: + // Number of pre-allocated device memory buffers + size_t buffer_count_; + // requested size of each device memory buffer + size_t buffer_step_; + // Index of the current device memory buffer + size_t current_handle_index_ = 0; + // Allocated size of each device memory buffer + size_t alloc_size_; + // Timeout in microseconds to reset the buffer + int64_t timeout_; + // Vector of device memory buffers + std::vector> device_ipc_buffers_; + // Vector of shared memory buffers contain refcount and UID + std::vector> host_ipc_buffers_; +}; + +} // namespace nitros_bridge +} // namespace isaac_ros +} // namespace nvidia + +#endif // ISAAC_ROS_NITROS_BRIDGE_ROS1__IPC_BUFFER_MANAGER_HPP_ diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_convert_forward.launch b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_convert_forward.launch new file mode 100644 index 0000000..519a8a3 --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_convert_forward.launch @@ -0,0 +1,49 @@ + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_forward.launch b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_forward.launch new file mode 100644 index 0000000..06711bc --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_forward.launch @@ -0,0 +1,40 @@ + + + + + + + + + + \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_image_converter.launch b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_image_converter.launch new file mode 100644 index 0000000..48701ba --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/launch/nitros_bridge_image_converter.launch @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/nodelet_plugins.xml b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/nodelet_plugins.xml new file mode 100644 index 0000000..337c492 --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/nodelet_plugins.xml @@ -0,0 +1,29 @@ + + + + + + + + This nodelet receives a message and publishes it. + + + \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/package.xml b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/package.xml new file mode 100644 index 0000000..210122e --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/package.xml @@ -0,0 +1,52 @@ + + + + + + isaac_ros_nitros_bridge_ros1 + 3.2.0 + Converter between NITROS bridge messages and ROS1 messages + Isaac ROS Maintainers + Apache-2.0 + Yuankun Zhu + + catkin + roscpp + std_msgs + sensor_msgs + message_generation + nodelet + isaac_ros_nitros_bridge_msgs + isaac_ros_common + roscpp + std_msgs + sensor_msgs + isaac_ros_nitros_bridge_msgs + roscpp + rospy + std_msgs + sensor_msgs + message_runtime + nodelet + isaac_ros_nitros_bridge_msgs + + + + + diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/src/image_converter_node.cpp b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/src/image_converter_node.cpp new file mode 100644 index 0000000..f85f6fb --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_nitros_bridge_ros1/src/image_converter_node.cpp @@ -0,0 +1,250 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + + +#include +#include +#include + +#include "image_converter_node.hpp" + +#define SYS_pidfd_getfd_nitros_bridge 438 + + +namespace nvidia +{ +namespace isaac_ros +{ +namespace nitros_bridge +{ + +void ImageConverterNode::onInit() +{ + ros::NodeHandle & private_nh = getPrivateNodeHandle(); + + // Create publisher topics + bridge_image_pub_ = private_nh.advertise( + "ros1_output_bridge_image", 10); + image_pub_ = private_nh.advertise("ros1_output_image", 10); + + // Create subscriber topics + image_sub_ = private_nh.subscribe( + "ros1_input_image", 10, &ImageConverterNode::ROSToBridgeCallback, + this); + bridge_image_sub_ = private_nh.subscribe( + "ros1_input_bridge_image", 10, + &ImageConverterNode::BridgeToROSCallback, this); + + private_nh.param("num_blocks", num_blocks_, 40); + private_nh.param("timeout", timeout_, 100); + + cudaSetDevice(0); + cuDevicePrimaryCtxRetain(&ctx_, 0); + + cudaEventCreateWithFlags(&event_, cudaEventInterprocess | cudaEventDisableTiming); + cudaIpcGetEventHandle(reinterpret_cast(&ipc_event_handle_), event_); +} + +void ImageConverterNode::BridgeToROSCallback( + const isaac_ros_nitros_bridge_msgs::NitrosBridgeImage::ConstPtr & input_msg) +{ + cuCtxSetCurrent(ctx_); + + CUdeviceptr gpu_buffer = 0ULL; + CUmemGenericAllocationHandle generic_allocation_handle; + + auto pid = input_msg->data[0]; + auto fd = input_msg->data[1]; + + auto msg_uid = input_msg->uid; + cudaEvent_t event; + cudaIpcEventHandle_t event_handle; + + // Construct CUDA IPC event handle if it exists + if (input_msg->cuda_event_handle.size() != 0) { + if (input_msg->cuda_event_handle.size() != sizeof(cudaIpcEventHandle_t)) { + ROS_ERROR("Invalid event handle size."); + return; + } + memcpy(&event_handle, input_msg->cuda_event_handle.data(), sizeof(cudaIpcEventHandle_t)); + auto err = cudaIpcOpenEventHandle(&event, event_handle); + if (err != cudaSuccess) { + ROS_ERROR( "cudaIpcOpenEventHandle failed: %s", cudaGetErrorString(err)); + return; + } + + // The event may record the completion of the previous operation + err = cudaEventSynchronize(event); + if (err != cudaSuccess) { + ROS_ERROR("CUDA event synchronize failed: %s", cudaGetErrorString(err)); + return; + } + } + + // Compare UID if exists + if (!msg_uid.empty()) { + std::string shm_name = std::to_string(pid) + std::to_string(fd); + host_ipc_buffer_ = std::make_shared(shm_name, HostIPCBuffer::Mode::OPEN); + if (!host_ipc_buffer_->refcoun_inc_if_uid_match(msg_uid)) { + ROS_WARN("Failed to match UID, skip."); + return; + } + } + + if (handle_ptr_map_.find(input_msg->data.data()[1]) != handle_ptr_map_.end()) { + gpu_buffer = handle_ptr_map_[input_msg->data.data()[1]]; + ROS_DEBUG("Found FD in local map."); + } else { + int pidfd = syscall(SYS_pidfd_open, input_msg->data.data()[0], 0); + if (pidfd <= 0) { + perror("SYS_pidfd_open failed"); + } + int fd = syscall(SYS_pidfd_getfd_nitros_bridge, pidfd, input_msg->data.data()[1], 0); + if (fd <= 0) { + perror("SYS_pidfd_getfd failed"); + } + + auto cuda_err = cuMemImportFromShareableHandle( + &generic_allocation_handle, + reinterpret_cast((uintptr_t)fd), + CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR( "Failed to call cuMemImportFromShareableHandle %s", error_str); + throw std::runtime_error("[NITROS Bridge] cuMemImportFromShareableHandle Error"); + } + + CUmemAllocationProp prop = {}; + prop.type = CU_MEM_ALLOCATION_TYPE_PINNED; + prop.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + prop.location.id = 0; + prop.requestedHandleTypes = CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR; + size_t granularity = 0; + + cuda_err = cuMemGetAllocationGranularity( + &granularity, &prop, CU_MEM_ALLOC_GRANULARITY_MINIMUM); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR( "Failed to call cuMemGetAllocationGranularity %s", error_str); + throw std::runtime_error( + "[NITROS Bridge] cuMemGetAllocationGranularity Error"); + } + + auto alloc_size = input_msg->height * input_msg->step; + // The alloc size must be the integral multiple of granularity + alloc_size = alloc_size - (alloc_size % granularity) + granularity; + + cuda_err = cuMemAddressReserve(&gpu_buffer, alloc_size, 0, 0, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemAddressReserve %s", error_str); + throw std::runtime_error("[NITROS Bridge] cuMemAddressReserve Error"); + } + + cuda_err = cuMemMap(gpu_buffer, alloc_size, 0, generic_allocation_handle, 0); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemMap %s", error_str); + throw std::runtime_error("[NITROS Bridge] cuMemMap Error"); + } + + CUmemAccessDesc accessDesc = {}; + accessDesc.location.type = CU_MEM_LOCATION_TYPE_DEVICE; + accessDesc.location.id = 0; + accessDesc.flags = CU_MEM_ACCESS_FLAGS_PROT_READWRITE; + cuda_err = cuMemSetAccess(gpu_buffer, alloc_size, &accessDesc, 1); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemSetAccess %s", error_str); + throw std::runtime_error("[NITROS Bridge] cuMemMap Error"); + } + handle_ptr_map_[input_msg->data.data()[1]] = gpu_buffer; + } + + sensor_msgs::Image output_msg; + output_msg.header = input_msg->header; + output_msg.height = input_msg->height; + output_msg.width = input_msg->width; + output_msg.encoding = input_msg->encoding; + output_msg.step = input_msg->step; + output_msg.data.resize(input_msg->step * input_msg->height); + + auto cuda_err = cuMemcpyDtoH( + output_msg.data.data(), gpu_buffer, input_msg->step * input_msg->height); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemcpyDtoH %s", error_str); + } + + image_pub_.publish(output_msg); + + // Update refcount if it exists + if (!msg_uid.empty()) { + host_ipc_buffer_->refcount_dec(); + } + ROS_DEBUG("NITROS Image is Published from NITROS Bridge."); +} + +void ImageConverterNode::ROSToBridgeCallback(const sensor_msgs::Image::ConstPtr & input_msg) +{ + cuCtxSetCurrent(ctx_); + + if (first_msg_received_ == false) { + ipc_buffer_manager_ = std::make_shared< + IPCBufferManager>(num_blocks_, input_msg->step * input_msg->height, timeout_); + first_msg_received_ = true; + } + + auto ipc_buffer = ipc_buffer_manager_->find_next_available_buffer(); + + isaac_ros_nitros_bridge_msgs::NitrosBridgeImage msg; + msg.header = input_msg->header; + msg.height = input_msg->height; + msg.width = input_msg->width; + msg.encoding = input_msg->encoding; + msg.step = input_msg->step; + + auto cuda_err = cuMemcpyHtoD( + ipc_buffer->d_ptr, + input_msg->data.data(), + msg.step * msg.height); + if (CUDA_SUCCESS != cuda_err) { + const char * error_str = NULL; + cuGetErrorString(cuda_err, &error_str); + ROS_ERROR("Failed to call cuMemcpyDtoD %s", error_str); + throw std::runtime_error("[NITROS Bridge] cuMemcpyDtoD Error"); + } + + msg.data.push_back(ipc_buffer->pid); + msg.data.push_back(ipc_buffer->fd); + msg.uid = ipc_buffer->uid; + msg.device_id = 0; + + bridge_image_pub_.publish(msg); +} + +} // namespace nitros_bridge +} // namespace isaac_ros +} // namespace nvidia + +PLUGINLIB_EXPORT_CLASS(nvidia::isaac_ros::nitros_bridge::ImageConverterNode, nodelet::Nodelet); diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/CMakeLists.txt b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/CMakeLists.txt new file mode 100644 index 0000000..0d64021 --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/CMakeLists.txt @@ -0,0 +1,61 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +cmake_minimum_required(VERSION 3.22.1) +project(isaac_ros_ros1_forward) + +if($ENV{ROS_VERSION} EQUAL 2) + message(STATUS "Skip package ${PROJECT_NAME} for ROS 2") + return() +endif() + +find_package( + catkin REQUIRED + COMPONENTS message_generation + std_msgs + sensor_msgs + roscpp + nodelet + topic_tools) + +include_directories( + include + ${catkin_INCLUDE_DIRS}) + +catkin_package(CATKIN_DEPENDS message_runtime std_msgs sensor_msgs) + +############# +## Library ## +############# + +add_library(isaac_ros_ros1_forward + src/ros1_forward_node.cpp) + +target_link_libraries(isaac_ros_ros1_forward + ${catkin_LIBRARIES} ) + +############# +## Install ## +############# + +install(TARGETS isaac_ros_ros1_forward + DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + +install(FILES + nodelet_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/include/ros1_forward_node.hpp b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/include/ros1_forward_node.hpp new file mode 100644 index 0000000..6aabcce --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/include/ros1_forward_node.hpp @@ -0,0 +1,55 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + +#ifndef ISAAC_ROS_ROS1_Forward__ROS1_FORWARD_NODE_HPP_ +#define ISAAC_ROS_ROS1_Forward__ROS1_FORWARD_NODE_HPP_ + +#include +#include + +#include "ros/ros.h" +#include "topic_tools/shape_shifter.h" + + +namespace nvidia +{ +namespace isaac_ros +{ +namespace ros1_forward +{ + +class ROS1ForwardNode : public nodelet::Nodelet +{ +public: + ROS1ForwardNode() {} + +private: + virtual void onInit() override; + + // Convert bridge message into ros message and copy back to CPU + void ForwardCallback(const topic_tools::ShapeShifter::ConstPtr & msg); + std::string input_md5_sum_; + + ros::Publisher pub_; + ros::Subscriber sub_; +}; + +} // namespace ros1_forward +} // namespace isaac_ros +} // namespace nvidia + +#endif // ISAAC_ROS_ROS1_Forward__ROS1_FORWARD_NODE_HPP_ diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/nodelet_plugins.xml b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/nodelet_plugins.xml new file mode 100644 index 0000000..c5dcfca --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/nodelet_plugins.xml @@ -0,0 +1,29 @@ + + + + + + + + This nodelet receives a message and publishes it. + + + \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/package.xml b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/package.xml new file mode 100644 index 0000000..071baf1 --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/package.xml @@ -0,0 +1,54 @@ + + + + + + isaac_ros_ros1_forward + 3.2.0 + Forward ROS1 Messages + Isaac ROS Maintainers + Apache-2.0 + Yuankun Zhu + + catkin + roscpp + std_msgs + sensor_msgs + message_generation + nodelet + topic_tools + isaac_ros_common + roscpp + std_msgs + sensor_msgs + roscpp + rospy + std_msgs + sensor_msgs + message_runtime + nodelet + topic_tools + + + + + + + + diff --git a/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/src/ros1_forward_node.cpp b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/src/ros1_forward_node.cpp new file mode 100644 index 0000000..48bc725 --- /dev/null +++ b/isaac_ros_nitros_bridge/ros1/isaac_ros_ros1_forward/src/ros1_forward_node.cpp @@ -0,0 +1,58 @@ +// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// SPDX-License-Identifier: Apache-2.0 + + +#include +#include + +#include "ros/ros.h" +#include "ros1_forward_node.hpp" + +namespace nvidia +{ +namespace isaac_ros +{ +namespace ros1_forward +{ + +void ROS1ForwardNode::onInit() +{ + ros::NodeHandle & private_nh = getPrivateNodeHandle(); + + // Create subscriber topics + sub_ = private_nh.subscribe("forward_input", 10, &ROS1ForwardNode::ForwardCallback, this); +} + +void ROS1ForwardNode::ForwardCallback(const topic_tools::ShapeShifter::ConstPtr & input_msg) +{ + ROS_DEBUG("Received message in ForwardCallback."); + if (input_msg->getMD5Sum() != input_md5_sum_) { + ros::NodeHandle & private_nh = getPrivateNodeHandle(); + // Create publisher topics + ros::AdvertiseOptions opts("forward_output", 10, input_msg->getMD5Sum(), + input_msg->getDataType(), input_msg->getMessageDefinition()); + pub_ = private_nh.advertise(opts); + } + + pub_.publish(input_msg); +} + +} // namespace ros1_forward +} // namespace isaac_ros +} // namespace nvidia + +PLUGINLIB_EXPORT_CLASS(nvidia::isaac_ros::ros1_forward::ROS1ForwardNode, nodelet::Nodelet); diff --git a/isaac_ros_nitros_bridge/scripts/isaac_ros_nitros_bridge_ros1.py b/isaac_ros_nitros_bridge/scripts/isaac_ros_nitros_bridge_ros1.py new file mode 100644 index 0000000..93dabb8 --- /dev/null +++ b/isaac_ros_nitros_bridge/scripts/isaac_ros_nitros_bridge_ros1.py @@ -0,0 +1,103 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import argparse +import os +import subprocess +import time + +ROS1_WS_PATH = '/workspaces/isaac_ros_1-dev' +ROS2_WS_PATH = '/workspaces/isaac_ros-dev' + +ROS1_INSTALL_PATH = 'install_isolated/setup.bash' +ROS1_BRIDGE_INSTALL_PATH = 'install/setup.bash' + +DEFAULT_ROS1_LAUNCH_FILE = 'nitros_bridge_image_converter.launch' + +parser = argparse.ArgumentParser( + description='Start the NITROS Bridge ROS1 converter and ROS1 bridge.', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + +parser.add_argument("-c", + "--bridge_config_file", + type = str, + default = "nitros_bridge_image_converter.yaml", + help="Path to the bridge configuration file") + +parser.add_argument("-l", + "--launch_file", + type = str, + default = DEFAULT_ROS1_LAUNCH_FILE, + help="ROS1 launch file name. Example: sample.launch") + +parser.add_argument("-s", + "--sub_image_name", + type = str, + default = "/image", + help="ROS1 image converter subscriber topic name. Example: /image") + +parser.add_argument("-p", + "--pub_image_name", + type = str, + default = "/ros1_output_image", + help="ROS1 image converter publisher topic name. Example: /ros1_output_image") + +args = parser.parse_args() + +roscore_cmd = 'source /opt/ros/noetic/setup.bash && roscore' +subprocess.Popen( + roscore_cmd, + env=os.environ, + shell=True, + executable='/bin/bash' +) +# Wait one second to ensure roscore is fully launched +time.sleep(1) + +ros1_setup_path = os.path.join(ROS1_WS_PATH, ROS1_INSTALL_PATH) +stop_ros_nodes_cmd = f'source {ros1_setup_path} && rosnode kill -a' +subprocess.run( + stop_ros_nodes_cmd, + env=os.environ, + shell=True, + executable='/bin/bash' +) + +ros1_launch_cmd = "" +if args.launch_file == DEFAULT_ROS1_LAUNCH_FILE: + ros1_launch_cmd = f'roslaunch isaac_ros_nitros_bridge_ros1 {DEFAULT_ROS1_LAUNCH_FILE} pub_image_name:={args.pub_image_name} sub_image_name:={args.sub_image_name}' +else: + ros1_launch_cmd = f'roslaunch isaac_ros_nitros_bridge_ros1 {args.launch_file}' + +ros1_converter_cmd = f'source {ros1_setup_path} \ + && rosparam load {args.bridge_config_file} \ + && {ros1_launch_cmd}' +subprocess.Popen( + ros1_converter_cmd, + env=os.environ, + shell=True, + executable='/bin/bash' +) + +ros1_bridge_setup_path = os.path.join(ROS2_WS_PATH, ROS1_BRIDGE_INSTALL_PATH) +ros1_bridge_cmd = f'source {ros1_bridge_setup_path} && ros2 run ros1_bridge parameter_bridge' +subprocess.Popen( + ros1_bridge_cmd, + env=os.environ, + shell=True, + executable='/bin/bash' +) diff --git a/isaac_ros_nitros_bridge/scripts/nitros-bridge-entrypoint.sh b/isaac_ros_nitros_bridge/scripts/nitros-bridge-entrypoint.sh new file mode 100644 index 0000000..a50077d --- /dev/null +++ b/isaac_ros_nitros_bridge/scripts/nitros-bridge-entrypoint.sh @@ -0,0 +1,28 @@ +#!/bin/bash +# +# Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. +# +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + + + +CONFIG_DIR="/workspaces/isaac_ros_1-dev/src/isaac_ros_nitros_bridge/config/" +SCRIPT_DIR="/workspaces/isaac_ros_1-dev/src/isaac_ros_nitros_bridge/scripts/" + +echo "Using ROS1 config file: ${CONFIG_DIR}${1}" +echo "Using ROS1 launch file: $2" + +# Set ptrace scope to enable CUDA IPC +echo 0 | sudo tee /proc/sys/kernel/yama/ptrace_scope + +if [ -z "$3" ] && [ -z "$4" ]; then + python3 "${SCRIPT_DIR}isaac_ros_nitros_bridge_ros1.py" -c "${CONFIG_DIR}${1}" -l $2 +else + python3 "${SCRIPT_DIR}isaac_ros_nitros_bridge_ros1.py" -c "${CONFIG_DIR}${1}" -l $2 -s $3 -p $4 +fi + +tail -f /dev/null \ No newline at end of file diff --git a/isaac_ros_nitros_bridge/scripts/workspace-entrypoint.sh b/isaac_ros_nitros_bridge/scripts/workspace-entrypoint.sh new file mode 100644 index 0000000..fe9eef4 --- /dev/null +++ b/isaac_ros_nitros_bridge/scripts/workspace-entrypoint.sh @@ -0,0 +1,15 @@ +#!/bin/bash +# +# Copyright (c) 2024, NVIDIA CORPORATION. All rights reserved. +# +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + + +# Restart udev daemon +sudo service udev restart + +$@ diff --git a/isaac_ros_nitros_interfaces/CMakeLists.txt b/isaac_ros_nitros_interfaces/CMakeLists.txt deleted file mode 100644 index 71f8a3b..0000000 --- a/isaac_ros_nitros_interfaces/CMakeLists.txt +++ /dev/null @@ -1,49 +0,0 @@ -# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -# Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# SPDX-License-Identifier: Apache-2.0 - -cmake_minimum_required(VERSION 3.22.1) -project(isaac_ros_nitros_interfaces LANGUAGES C CXX) - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# The FindPythonInterp and FindPythonLibs modules are removed -if(POLICY CMP0148) - cmake_policy(SET CMP0148 OLD) -endif() - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -# Prepare custom test interfaces -find_package(rosidl_default_generators REQUIRED) -rosidl_generate_interfaces(${PROJECT_NAME} - msg/TopicStatistics.msg -) -ament_export_dependencies(rosidl_default_runtime) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - - # Ignore copyright notices since we use custom NVIDIA Isaac ROS Software License - set(ament_cmake_copyright_FOUND TRUE) - ament_lint_auto_find_test_dependencies() - -endif() - -ament_auto_package() diff --git a/isaac_ros_nitros_interfaces/msg/TopicStatistics.msg b/isaac_ros_nitros_interfaces/msg/TopicStatistics.msg deleted file mode 100644 index a18f68a..0000000 --- a/isaac_ros_nitros_interfaces/msg/TopicStatistics.msg +++ /dev/null @@ -1,26 +0,0 @@ -# Statistics data for a ROS Node - -string node_name # Name of the ROS Node associated with the topic -string node_namespace # Namspace of the ROS topic -string topic_name # Name of the topic -bool is_subscriber # true if subscriber and false if publisher -float32 frame_rate_node # Windowed mean frame rate calculated using the node clock -float32 frame_rate_msg # Windowed mean frame rate calculated using the message timestamp -# jitter is the difference between the time between msgs(dt) -# calculated from fps specified in NITROS statistics ROS param -# and measured using node clock or the message timestamps -# Units is microseconds -# mean absolute jitter calculated using the node clock -int32 mean_abs_jitter_node -# mean absolute jitter calculated using the message timestamp -int32 mean_abs_jitter_msg -# maximum absolute jitter calculated using the node clock -int32 max_abs_jitter_node -# maximum absolute jitter calculated using the message timestamp -int32 max_abs_jitter_msg -# number of messages outside the jitter tolerance using the node clock -uint64 num_jitter_outliers_node -# number of messages outside the jitter tolerance using the message timestamp -uint64 num_jitter_outliers_msg -# number of messages with non-increasing msg times -uint64 num_non_increasing_msg diff --git a/isaac_ros_nitros_interfaces/package.xml b/isaac_ros_nitros_interfaces/package.xml deleted file mode 100644 index c64bcdc..0000000 --- a/isaac_ros_nitros_interfaces/package.xml +++ /dev/null @@ -1,37 +0,0 @@ - - - - - - - isaac_ros_nitros_interfaces - 3.1.0 - Interfaces for Isaac ROS NITROS - - Isaac ROS Maintainers - NVIDIA Isaac ROS Software License - https://developer.nvidia.com/blog/accelerating-ai-modules-for-ros-and-ros-2-on-jetson/ - Ashwin Varghese Kuruttukulam - - rosidl_default_generators - rosidl_default_runtime - - isaac_ros_common - - ament_lint_auto - ament_lint_common - - rosidl_interface_packages - - - ament_cmake - - diff --git a/isaac_ros_nitros_topic_tools/CMakeLists.txt b/isaac_ros_nitros_topic_tools/CMakeLists.txt index ebdf2ef..7d4e2ac 100644 --- a/isaac_ros_nitros_topic_tools/CMakeLists.txt +++ b/isaac_ros_nitros_topic_tools/CMakeLists.txt @@ -56,4 +56,10 @@ find_package(ament_lint_auto REQUIRED) add_launch_test(test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_2_test.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package(INSTALL_TO_SHARE launch) diff --git a/isaac_ros_nitros_topic_tools/package.xml b/isaac_ros_nitros_topic_tools/package.xml index f9065e9..07e54cc 100644 --- a/isaac_ros_nitros_topic_tools/package.xml +++ b/isaac_ros_nitros_topic_tools/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_topic_tools - 3.1.0 + 3.2.0 Isaac ROS Nitros Topic Tools Isaac ROS Maintainers diff --git a/isaac_ros_nitros_topic_tools/src/isaac_ros_nitros_camera_drop_node.cpp b/isaac_ros_nitros_topic_tools/src/isaac_ros_nitros_camera_drop_node.cpp index 2dc0097..22ce01d 100644 --- a/isaac_ros_nitros_topic_tools/src/isaac_ros_nitros_camera_drop_node.cpp +++ b/isaac_ros_nitros_topic_tools/src/isaac_ros_nitros_camera_drop_node.cpp @@ -69,7 +69,7 @@ NitrosCameraDropNode::NitrosCameraDropNode(const rclcpp::NodeOptions & options) nvidia::isaac_ros::nitros::ManagedNitrosPublisher>( this, "image_1_drop", nvidia::isaac_ros::nitros::nitros_image_rgb8_t::supported_type_name, - nvidia::isaac_ros::nitros::NitrosStatisticsConfig(), output_qos); + nvidia::isaac_ros::nitros::NitrosDiagnosticsConfig(), output_qos); camera_info_pub_1_ = this->create_publisher< sensor_msgs::msg::CameraInfo>("camera_info_1_drop", output_qos); @@ -91,7 +91,7 @@ NitrosCameraDropNode::NitrosCameraDropNode(const rclcpp::NodeOptions & options) nvidia::isaac_ros::nitros::ManagedNitrosPublisher>( this, "image_2_drop", nvidia::isaac_ros::nitros::nitros_image_rgb8_t::supported_type_name, - nvidia::isaac_ros::nitros::NitrosStatisticsConfig(), output_qos); + nvidia::isaac_ros::nitros::NitrosDiagnosticsConfig(), output_qos); camera_info_pub_2_ = this->create_publisher< sensor_msgs::msg::CameraInfo>("camera_info_2_drop", output_qos); // Initialize sync policy diff --git a/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_0_test.py b/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_0_test.py index 60c293e..92900f5 100644 --- a/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_0_test.py +++ b/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_0_test.py @@ -100,7 +100,7 @@ def test_drop_node(self) -> None: try: image_msg = self.create_image('test_image') camera_info_msg = CameraInfo() - camera_info_msg.distortion_model = 'pinhole' + camera_info_msg.distortion_model = 'plumb_bob' self.node.get_logger().info('Starting to publish messages') # Publish TOTAL_COUNT number of messages diff --git a/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_1_test.py b/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_1_test.py index 0715a3a..581e7fb 100644 --- a/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_1_test.py +++ b/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_1_test.py @@ -110,11 +110,11 @@ def test_drop_node(self) -> None: try: image_msg_1 = self.create_image('test_image_1') camera_info_msg_1 = CameraInfo() - camera_info_msg_1.distortion_model = 'pinhole' + camera_info_msg_1.distortion_model = 'plumb_bob' image_msg_2 = self.create_image('test_image_2') camera_info_msg_2 = CameraInfo() - camera_info_msg_2.distortion_model = 'pinhole' + camera_info_msg_2.distortion_model = 'plumb_bob' self.node.get_logger().info('Starting to publish messages') # Publish TOTAL_COUNT number of messages diff --git a/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_2_test.py b/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_2_test.py index cb6a608..a88ff5a 100644 --- a/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_2_test.py +++ b/isaac_ros_nitros_topic_tools/test/isaac_ros_nitros_topic_tools_camera_drop_node_mode_2_test.py @@ -104,7 +104,7 @@ def test_drop_node(self) -> None: try: image_msg = self.create_image('test_image') camera_info_msg = CameraInfo() - camera_info_msg.distortion_model = 'pinhole' + camera_info_msg.distortion_model = 'plumb_bob' depth_msg = self.create_image('test_depth') self.node.get_logger().info('Starting to publish messages') diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/CMakeLists.txt deleted file mode 100644 index dee8f2a..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/CMakeLists.txt +++ /dev/null @@ -1,97 +0,0 @@ -# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -# Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# SPDX-License-Identifier: Apache-2.0 - -cmake_minimum_required(VERSION 3.22.1) -project(isaac_ros_nitros_april_tag_detection_array_type LANGUAGES C CXX) - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -# NVTX -option(USE_NVTX "Enable NVTX markers for improved profiling (if available)" ON) -if(USE_NVTX) - add_definitions(-DUSE_NVTX) - link_directories("${CUDA_TOOLKIT_ROOT_DIR}/lib64") - link_libraries("nvToolsExt") -endif() - -# Dependencies -find_package(Eigen3 3.3 REQUIRED NO_MODULE) -find_package(yaml-cpp) - -# NitrosAprilTagDetectionArray -ament_auto_add_library(${PROJECT_NAME} SHARED - src/nitros_april_tag_detection_array.cpp - src/fiducial_message.cpp -) -target_link_libraries(${PROJECT_NAME} - Eigen3::Eigen - yaml-cpp -) -set_target_properties(${PROJECT_NAME} PROPERTIES - BUILD_WITH_INSTALL_RPATH TRUE - BUILD_RPATH_USE_ORIGIN TRUE - INSTALL_RPATH_USE_LINK_PATH TRUE) - -# Make library available for sharing in Nitros -install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION share/${PROJECT_NAME}/gxf/lib/fiducial_message) - -if(BUILD_TESTING) - # Install test/config directory - install(DIRECTORY test/config DESTINATION share/${PROJECT_NAME}/test) - - # NitrosAprilTagDetectionArrayForwardNode - ament_auto_add_library(isaac_ros_nitros_april_tag_detection_array_forward_node SHARED - test/src/nitros_april_tag_detection_array_forward_node.cpp - ) - target_link_libraries(isaac_ros_nitros_april_tag_detection_array_forward_node ${PROJECT_NAME}) - set_target_properties(isaac_ros_nitros_april_tag_detection_array_forward_node PROPERTIES - BUILD_WITH_INSTALL_RPATH TRUE - BUILD_RPATH_USE_ORIGIN TRUE - INSTALL_RPATH_USE_LINK_PATH TRUE) - rclcpp_components_register_nodes(isaac_ros_nitros_april_tag_detection_array_forward_node - "nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArrayForwardNode") - set(node_plugins "${node_plugins}nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArrayForwardNode;\ - $\n") - - # Test registration extension - ament_auto_add_library(isaac_ros_nitros_april_tag_detection_array_test_ext SHARED - test/src/fiducial_message_test_ext.cpp - ) - install(TARGETS isaac_ros_nitros_april_tag_detection_array_test_ext - LIBRARY DESTINATION share/${PROJECT_NAME}/gxf/lib/fiducial_message/test) - - find_package(ament_lint_auto REQUIRED) - - # Ignore copyright notices since we use custom NVIDIA Isaac ROS Software License - set(ament_cmake_copyright_FOUND TRUE) - ament_lint_auto_find_test_dependencies() - - # The FindPythonInterp and FindPythonLibs modules are removed - if(POLICY CMP0148) - cmake_policy(SET CMP0148 OLD) - endif() - - find_package(launch_testing_ament_cmake REQUIRED) - add_launch_test(test/isaac_ros_nitros_april_tag_detection_array_type_test_pol.py TIMEOUT "15") -endif() - -ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/extensions/fiducials/messages/fiducial_message.hpp b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/extensions/fiducials/messages/fiducial_message.hpp deleted file mode 100644 index f1d18c0..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/extensions/fiducials/messages/fiducial_message.hpp +++ /dev/null @@ -1,77 +0,0 @@ -// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// SPDX-License-Identifier: Apache-2.0 -#pragma once - -#include "gems/core/math/pose3.hpp" -#include "extensions/fiducials/gems/fiducial_info.hpp" -#include "gxf/core/entity.hpp" -#include "gxf/core/expected.hpp" -#include "gxf/std/tensor.hpp" - -namespace nvidia -{ -namespace isaac -{ - -// A fiducial is an object placed in the field of view -// of an imaging system for use as a point of reference or a measure -struct FiducialMessageParts -{ - // The message entity - gxf::Entity entity; - // View to the FiducialsInfo instance holding meta information about this message - gxf::Handle info; - // 3D pose of the detected tag from the camera coordinates, - // consisting of orientation (quaternion) and translation - // Camera coordinate (X - right, Y - down, Z - outward) - // Tag coordinate (X - right, Y - down, Z - opposite to tag face direction) - // Tag coordinates are centered at tag's upper-left corner - // ie. Pose has identity quaternion and zero translation, when tag is facing the camera and it's - // upper-left corner is centered at the camera center - gxf::Handle<::nvidia::isaac::Pose3d> pose; - // List of keypoints of the detected fiducial, in image space - gxf::Handle keypoints; -}; - -// Message structure to organize a list of fiducials -struct FiducialListMessageParts -{ - gxf::Entity entity; - FixedVector, kMaxComponents> info; - FixedVector, kMaxComponents> pose; - FixedVector, kMaxComponents> keypoints; - size_t count; -}; - -// Creates a fiducial message entity and returns a view to it -// Message entity is activated by default -gxf::Expected CreateFiducialMessage(gxf_context_t context); - -// Parses a fiducial message entity and returns a view to it -gxf::Expected GetFiducialMessage(gxf::Entity message); - -// Creates a fiducial list message entity and returns a view to it -// Message entity is activated by default -gxf::Expected CreateFiducialListMessage( - gxf_context_t context, - size_t count); - -// Parses a fiducial list message entity and returns a view to it -gxf::Expected GetFiducialListMessage(gxf::Entity message); - -} // namespace isaac -} // namespace nvidia diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/isaac_ros_nitros_april_tag_detection_array_type/nitros_april_tag_detection_array.hpp b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/isaac_ros_nitros_april_tag_detection_array_type/nitros_april_tag_detection_array.hpp deleted file mode 100644 index 93c1f42..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/isaac_ros_nitros_april_tag_detection_array_type/nitros_april_tag_detection_array.hpp +++ /dev/null @@ -1,100 +0,0 @@ -// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// SPDX-License-Identifier: Apache-2.0 - -#ifndef ISAAC_ROS_NITROS_APRIL_TAG_DETECTION_ARRAY_TYPE__NITROS_APRIL_TAG_DETECTION_ARRAY_HPP_ -#define ISAAC_ROS_NITROS_APRIL_TAG_DETECTION_ARRAY_TYPE__NITROS_APRIL_TAG_DETECTION_ARRAY_HPP_ -/* - * Type adaptation for: - * Nitros type: NitrosAprilTagDetectionArray - * ROS type: isaac_ros_apriltag_interfaces::msg::AprilTagDetectionArray - */ - -#include - -#include "isaac_ros_apriltag_interfaces/msg/april_tag_detection_array.hpp" -#include "isaac_ros_nitros/types/nitros_format_agent.hpp" -#include "isaac_ros_nitros/types/nitros_type_base.hpp" - -#include "rclcpp/type_adapter.hpp" - - -namespace nvidia -{ -namespace isaac_ros -{ -namespace nitros -{ - -// Type forward declaration -struct NitrosAprilTagDetectionArray; - -// Formats -struct nitros_april_tag_detection_array_t -{ - using MsgT = NitrosAprilTagDetectionArray; - static const inline std::string supported_type_name = "nitros_april_tag_detection_array"; -}; - -// NITROS data type registration factory -NITROS_TYPE_FACTORY_BEGIN(NitrosAprilTagDetectionArray) -// Supported data formats -NITROS_FORMAT_FACTORY_BEGIN() -NITROS_FORMAT_ADD(nitros_april_tag_detection_array_t) -NITROS_FORMAT_FACTORY_END() -// Required extensions -NITROS_TYPE_EXTENSION_FACTORY_BEGIN() -NITROS_TYPE_EXTENSION_ADD("isaac_ros_gxf", "gxf/lib/std/libgxf_std.so") -NITROS_TYPE_EXTENSION_ADD("isaac_ros_gxf", "gxf/lib/serialization/libgxf_serialization.so") -// for nvidia::isaac::StringProvider -NITROS_TYPE_EXTENSION_ADD("gxf_isaac_gxf_helpers", "gxf/lib/libgxf_isaac_gxf_helpers.so") -// for nvidia::isaac::SightReceiver -NITROS_TYPE_EXTENSION_ADD("gxf_isaac_sight", "gxf/lib/libgxf_isaac_sight.so") -// for nvidia::isaac::PoseTree -NITROS_TYPE_EXTENSION_ADD("gxf_isaac_atlas", "gxf/lib/libgxf_isaac_atlas.so") -// for nvidia::isaac::PoseFrameUid -NITROS_TYPE_EXTENSION_ADD("gxf_isaac_messages", "gxf/lib/libgxf_isaac_messages.so") -NITROS_TYPE_EXTENSION_FACTORY_END() -NITROS_TYPE_FACTORY_END() - -} // namespace nitros -} // namespace isaac_ros -} // namespace nvidia - - -template<> -struct rclcpp::TypeAdapter< - nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArray, - isaac_ros_apriltag_interfaces::msg::AprilTagDetectionArray> -{ - using is_specialized = std::true_type; - using custom_type = nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArray; - using ros_message_type = isaac_ros_apriltag_interfaces::msg::AprilTagDetectionArray; - - static void convert_to_ros_message( - const custom_type & source, - ros_message_type & destination); - - static void convert_to_custom( - const ros_message_type & source, - custom_type & destination); -}; - -RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE( - nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArray, - isaac_ros_apriltag_interfaces::msg::AprilTagDetectionArray); - -#endif // ISAAC_ROS_NITROS_APRIL_TAG_DETECTION_ARRAY_TYPE__NITROS_APRIL_TAG_DETECTION_ARRAY_HPP_ diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/package.xml deleted file mode 100644 index ef83b8d..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/package.xml +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - isaac_ros_nitros_april_tag_detection_array_type - 3.1.0 - Isaac ROS Nitros Apriltag Detection Array Type - - Isaac ROS Maintainers - NVIDIA Isaac ROS Software License - https://developer.nvidia.com/isaac-ros-gems/ - Ashwin Varghese Kuruttukulam - CY Chen - Swapnesh Wani - - ament_cmake - - rclcpp - rclcpp_components - isaac_ros_apriltag_interfaces - isaac_ros_nitros - gxf_isaac_messages - - isaac_ros_common - gxf_isaac_gems - - gxf_isaac_gxf_helpers - gxf_isaac_sight - gxf_isaac_atlas - - ament_lint_auto - ament_lint_common - isaac_ros_test - - - ament_cmake - - diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/src/fiducial_message.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/src/fiducial_message.cpp deleted file mode 100644 index 4601441..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/src/fiducial_message.cpp +++ /dev/null @@ -1,103 +0,0 @@ -// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// SPDX-License-Identifier: Apache-2.0 -#include "extensions/fiducials/messages/fiducial_message.hpp" - -namespace nvidia -{ -namespace isaac -{ - -namespace -{ - -// Name for the FiducialInfo in message -constexpr char kNameInfo[] = "info"; -// Name for the Pose3 in message -constexpr char kNamePose[] = "pose"; -// Name for the Tensor in message -constexpr char kNameKeypoints[] = "keypoints"; - -} // namespace - -gxf::Expected CreateFiducialMessage(gxf_context_t context) -{ - FiducialMessageParts parts; - return gxf::Entity::New(context) - .assign_to(parts.entity) - .and_then([&]() {return parts.entity.add(kNameInfo);}) - .assign_to(parts.info) - .and_then([&]() {return parts.entity.add<::nvidia::isaac::Pose3d>(kNamePose);}) - .assign_to(parts.pose) - .and_then([&]() {return parts.entity.add(kNameKeypoints);}) - .assign_to(parts.keypoints) - .substitute(parts); -} - -gxf::Expected GetFiducialMessage(gxf::Entity message) -{ - FiducialMessageParts parts; - parts.entity = message; - return parts.entity.get(kNameInfo) - .assign_to(parts.info) - .and_then([&]() {return parts.entity.get<::nvidia::isaac::Pose3d>(kNamePose);}) - .assign_to(parts.pose) - .and_then([&]() {return parts.entity.get(kNameKeypoints);}) - .assign_to(parts.keypoints) - .substitute(parts); -} - -gxf::Expected CreateFiducialListMessage( - gxf_context_t context, - size_t count) -{ - gxf::Entity entity; - return gxf::Entity::New(context) - .assign_to(entity) - .and_then( - [&]() { - gxf::Expected result; - for (size_t i = 0; i < count; i++) { - result = result & - entity.add(kNameInfo) & - entity.add<::nvidia::isaac::Pose3d>(kNamePose) & - entity.add(kNameKeypoints); - } - return result; - }) - .and_then([&]() {return GetFiducialListMessage(entity);}); -} - -gxf::Expected GetFiducialListMessage(gxf::Entity message) -{ - FiducialListMessageParts parts; - parts.entity = message; - - auto result = parts.entity.findAll(parts.info) - .and_then([&]() {parts.entity.findAll<::nvidia::isaac::Pose3d>(parts.pose);}) - .and_then([&]() {parts.entity.findAll(parts.keypoints);}); - if (!result) { - return gxf::ForwardError(result); - } - if (parts.info.size() != parts.pose.size() || parts.info.size() != parts.keypoints.size()) { - return gxf::Unexpected{GXF_FAILURE}; - } - parts.count = parts.info.size(); - return parts; -} - -} // namespace isaac -} // namespace nvidia diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/src/nitros_april_tag_detection_array.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/src/nitros_april_tag_detection_array.cpp deleted file mode 100644 index f016bc8..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/src/nitros_april_tag_detection_array.cpp +++ /dev/null @@ -1,309 +0,0 @@ -// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// SPDX-License-Identifier: Apache-2.0 - -#include -#include -#include - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-parameter" -#pragma GCC diagnostic ignored "-Wmissing-field-initializers" -#pragma GCC diagnostic ignored "-Wpedantic" -#include "gxf/core/entity.hpp" -#include "gxf/core/gxf.h" -#include "gxf/multimedia/camera.hpp" -#include "gxf/std/timestamp.hpp" -#include "gems/core/math/pose3.hpp" -#include "gems/core/math/types.hpp" -#include "extensions/fiducials/gems/fiducial_info.hpp" -#include "extensions/fiducials/messages/fiducial_message.hpp" -#pragma GCC diagnostic pop - -#include "isaac_ros_nitros_april_tag_detection_array_type/nitros_april_tag_detection_array.hpp" -#include "isaac_ros_nitros/types/type_adapter_nitros_context.hpp" - - -// Conversion from -::nvidia::isaac::Pose3d DetectionToPose3d(const float translation[3], const float rotation[4]) -{ - return ::nvidia::isaac::Pose3d{ - ::nvidia::isaac::SO3d::FromQuaternion( - ::nvidia::isaac::Quaterniond{rotation[0], rotation[1], rotation[2], - rotation[3]}), - ::nvidia::isaac::Vector3d(translation[0], translation[1], translation[2]) - }; -} - -// Gets corner points as a tensor -nvidia::gxf::Expected CornersToTensor( - float corners[8], - nvidia::gxf::Handle allocator) -{ - nvidia::gxf::Tensor tensor; - return tensor.reshape( - nvidia::gxf::Shape{4, 2}, nvidia::gxf::MemoryStorageType::kHost, - allocator) - .and_then([&]() {return tensor.data();}) - .map( - [&](double * points) { - const int stride = tensor.shape().dimension(0); - for (int i = 0; i < stride; i++) { - points[i] = corners[2 * i]; // y - points[i + stride] = corners[2 * i + 1]; - } - return std::move(tensor); - }); -} - -void ExtractFamilyId(std::string family_id, std::string & family_, int & id_) -{ - size_t i = 0; - bool family_read_done = false; - std::string family; - std::string id; - - // For AprilTag, the id is of the format - // Ex. If the decoded tag ID is 14 and belongs to TagFamily tag36h11, the id is tag36h11_14 - // This struct in defined in fiducial_info.hpp - while (i < family_id.size()) { - if (family_id[i] == '_') {family_read_done = true;} else if (family_read_done) { - id.push_back(family_id[i]); - } else {family.push_back(family_id[i]);} - i++; - } - family_ = family; - id_ = stoi(id); // convert to int -} - -void rclcpp::TypeAdapter< - nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArray, - isaac_ros_apriltag_interfaces::msg::AprilTagDetectionArray>::convert_to_ros_message( - const custom_type & source, ros_message_type & destination) -{ - nvidia::isaac_ros::nitros::nvtxRangePushWrapper( - "NitrosAprilTagDetectionArray::convert_to_ros_message", - nvidia::isaac_ros::nitros::CLR_PURPLE); - - RCLCPP_DEBUG( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), - "[convert_to_ros_message] Conversion started for handle=%ld", source.handle); - - auto context = nvidia::isaac_ros::nitros::GetTypeAdapterNitrosContext().getContext(); - auto msg_entity = nvidia::gxf::Entity::Shared(context, source.handle); - - // Populate timestamp information back into ROS header - auto input_timestamp = msg_entity->get("timestamp"); - if (!input_timestamp) { // Fallback to label 'timestamp' - input_timestamp = msg_entity->get(); - } - if (input_timestamp) { - destination.header.stamp.sec = static_cast( - input_timestamp.value()->acqtime / static_cast(1e9)); - destination.header.stamp.nanosec = static_cast( - input_timestamp.value()->acqtime % static_cast(1e9)); - } - - // Extract apriltags array to a struct type defined in fiducial_message.hpp - auto apriltags_detections_array_expected = nvidia::isaac::GetFiducialListMessage( - msg_entity.value()); - if (!apriltags_detections_array_expected) { - std::stringstream error_msg; - error_msg << - "[convert_to_ros_message] Failed to get apriltags detections data from message entity: " << - GxfResultStr(apriltags_detections_array_expected.error()); - RCLCPP_ERROR( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), error_msg.str().c_str()); - throw std::runtime_error(error_msg.str().c_str()); - } - auto apriltags_detections_array = apriltags_detections_array_expected.value(); - - // Extract number of tags detected - size_t tags_count = apriltags_detections_array.count; - - // resize output array to the number of tags detected before populating - destination.detections.resize(tags_count); - - for (size_t i = 0; i < tags_count; i++) { - // struct is defined in fiducial_message.hpp - auto info = apriltags_detections_array.info.at(i).value(); - auto pose = apriltags_detections_array.pose.at(i).value(); - auto keypoints = apriltags_detections_array.keypoints.at(i).value(); - - isaac_ros_apriltag_interfaces::msg::AprilTagDetection msg_detection; - - std::string tag_family_id = info->id; - // extracting family and id from tag info - ExtractFamilyId(tag_family_id, msg_detection.family, msg_detection.id); - - // poulate tag pose data - msg_detection.pose.pose.pose.position.x = pose->translation.x(); - msg_detection.pose.pose.pose.position.y = pose->translation.y(); - msg_detection.pose.pose.pose.position.z = pose->translation.z(); - msg_detection.pose.pose.pose.orientation.x = pose->rotation.quaternion().x(); - msg_detection.pose.pose.pose.orientation.y = pose->rotation.quaternion().y(); - msg_detection.pose.pose.pose.orientation.z = pose->rotation.quaternion().z(); - msg_detection.pose.pose.pose.orientation.w = pose->rotation.quaternion().w(); - - // populate center and corners - nvidia::gxf::Handle corners_tensor_handle = keypoints; - auto corners_tensor_data = corners_tensor_handle->data().value(); - const int stride = corners_tensor_handle->shape().dimension(0); - - for (int j = 0; j < stride; j++) { - msg_detection.corners[j].y = corners_tensor_data[j]; - msg_detection.corners[j].x = corners_tensor_data[j + stride]; - } - msg_detection.center.x = (msg_detection.corners[0].x + msg_detection.corners[1].x) / 2; - msg_detection.center.y = (msg_detection.corners[1].y + msg_detection.corners[2].y) / 2; - destination.detections[i] = msg_detection; - } - - // Set frame ID - destination.header.frame_id = source.frame_id; - - RCLCPP_DEBUG( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), - "[convert_to_ros_message] Conversion completed"); - - nvidia::isaac_ros::nitros::nvtxRangePopWrapper(); -} - -void rclcpp::TypeAdapter< - nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArray, - isaac_ros_apriltag_interfaces::msg::AprilTagDetectionArray>::convert_to_custom( - const ros_message_type & source, - custom_type & destination) -{ - nvidia::isaac_ros::nitros::nvtxRangePushWrapper( - "NitrosAprilTagDetectionArray::convert_to_custom", - nvidia::isaac_ros::nitros::CLR_PURPLE); - - RCLCPP_DEBUG( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), - "[convert_to_custom] Conversion started"); - - auto context = nvidia::isaac_ros::nitros::GetTypeAdapterNitrosContext().getContext(); - - // Get pointer to allocator component - const std::string kEntityName = "memory_pool"; - const std::string kComponentName = "unbounded_allocator"; - const std::string kComponentTypeName = "nvidia::gxf::UnboundedAllocator"; - - gxf_uid_t cid; - nvidia::isaac_ros::nitros::GetTypeAdapterNitrosContext().getCid( - kEntityName, kComponentName, kComponentTypeName, cid); - - auto maybe_allocator_handle = - nvidia::gxf::Handle::Create(context, cid); - if (!maybe_allocator_handle) { - std::stringstream error_msg; - error_msg << - "[convert_to_custom] Failed to get allocator's handle: " << - GxfResultStr(maybe_allocator_handle.error()); - RCLCPP_ERROR( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), error_msg.str().c_str()); - throw std::runtime_error(error_msg.str().c_str()); - } - auto allocator_handle = maybe_allocator_handle.value(); - - auto message = nvidia::gxf::Entity::New(context); - if (!message) { - std::stringstream error_msg; - error_msg << - "[convert_to_custom] Error initializing new message entity: " << - GxfResultStr(message.error()); - RCLCPP_ERROR( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), error_msg.str().c_str()); - throw std::runtime_error(error_msg.str().c_str()); - } - - // Add timestamp to the message - uint64_t input_timestamp = - source.header.stamp.sec * static_cast(1e9) + - source.header.stamp.nanosec; - auto output_timestamp = message->add("timestamp"); - if (!output_timestamp) { - std::stringstream error_msg; - error_msg << "[convert_to_custom] Failed to add a timestamp component to message: " << - GxfResultStr(output_timestamp.error()); - RCLCPP_ERROR( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), error_msg.str().c_str()); - throw std::runtime_error(error_msg.str().c_str()); - } - output_timestamp.value()->acqtime = input_timestamp; - - // count number of tags first to know how many times to run the below for loop - size_t tags_count = static_cast(source.detections.size()); - auto create_fiducial_list_message_result = - nvidia::isaac::CreateFiducialListMessage(context, tags_count) - .map( - [&](nvidia::isaac::FiducialListMessageParts apriltags_list) -> nvidia::gxf::Expected { - nvidia::gxf::Expected result; - for (size_t i = 0; i < tags_count; i++) { - apriltags_list.info[i].value()->type = nvidia::isaac::FiducialInfo::Type::kAprilTag; - apriltags_list.info[i].value()->id = source.detections[i].family + "_" + - std::to_string(source.detections[i].id); - - // Create float instead of directly from ros msg to not change the original CornersToTensor - float corners_[8]; - for (int j = 0; j < 4; j++) { - corners_[2 * j] = source.detections[i].corners[j].y; - corners_[2 * j + 1] = source.detections[i].corners[j].x; - } - // add corners from ros msg here - auto keypoints = CornersToTensor(corners_, allocator_handle); - if (!keypoints) { - return nvidia::gxf::ForwardError(keypoints); - } - *apriltags_list.keypoints[i].value() = std::move(keypoints.value()); - - const float translation[3] = { - static_cast(source.detections[i].pose.pose.pose.position.x), - static_cast(source.detections[i].pose.pose.pose.position.y), - static_cast(source.detections[i].pose.pose.pose.position.z) - }; - const float rotation[4] = { - static_cast(source.detections[i].pose.pose.pose.orientation.w), - static_cast(source.detections[i].pose.pose.pose.orientation.x), - static_cast(source.detections[i].pose.pose.pose.orientation.y), - static_cast(source.detections[i].pose.pose.pose.orientation.z) - }; - // add pose from ros msg here - *apriltags_list.pose[i].value() = DetectionToPose3d(translation, rotation); - } - message = apriltags_list.entity; - return result; - }); - if (!create_fiducial_list_message_result) { - std::stringstream error_msg; - error_msg << - "[convert_to_custom] Failed to complete the fiducial list message: " << - GxfResultStr(create_fiducial_list_message_result.error()); - RCLCPP_ERROR( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), error_msg.str().c_str()); - throw std::runtime_error(error_msg.str().c_str()); - } - - // Set frame ID - destination.frame_id = source.header.frame_id; - - // Set Entity Id - destination.handle = message->eid(); - GxfEntityRefCountInc(context, message->eid()); - - nvidia::isaac_ros::nitros::nvtxRangePopWrapper(); -} diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/config/test_forward_node.yaml b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/config/test_forward_node.yaml deleted file mode 100644 index 51d2fc5..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/config/test_forward_node.yaml +++ /dev/null @@ -1,55 +0,0 @@ -%YAML 1.2 -# Copyright (c) 2022-2023, NVIDIA CORPORATION. All rights reserved. -# -# NVIDIA CORPORATION and its licensors retain all intellectual property -# and proprietary rights in and to this software, related documentation -# and any modifications thereto. Any use, reproduction, disclosure or -# distribution of this software and related documentation without an express -# license agreement from NVIDIA CORPORATION is strictly prohibited. ---- -name: forward -components: -- name: input - type: nvidia::gxf::DoubleBufferReceiver - parameters: - capacity: 1 -- name: output - type: nvidia::gxf::DoubleBufferTransmitter -- type: nvidia::isaac_ros::MessageForward - parameters: - in: input - out: output -- type: nvidia::gxf::MessageAvailableSchedulingTerm - parameters: - receiver: input - min_size: 1 ---- -name: sink -components: -- name: input - type: nvidia::gxf::DoubleBufferReceiver - parameters: - capacity: 1 -- type: nvidia::gxf::MessageAvailableSchedulingTerm - parameters: - receiver: input - min_size: 1 -- name: sink - type: nvidia::isaac_ros::MessageRelay - parameters: - source: input ---- -components: -- type: nvidia::gxf::Connection - parameters: - source: forward/output - target: sink/input ---- -components: -- type: nvidia::gxf::GreedyScheduler - parameters: - clock: clock - stop_on_deadlock: false - check_recession_period_us: 100 -- name: clock - type: nvidia::gxf::RealtimeClock \ No newline at end of file diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/isaac_ros_nitros_april_tag_detection_array_type_test_pol.py b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/isaac_ros_nitros_april_tag_detection_array_type_test_pol.py deleted file mode 100644 index e4080d2..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/isaac_ros_nitros_april_tag_detection_array_type_test_pol.py +++ /dev/null @@ -1,202 +0,0 @@ -# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -# Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# SPDX-License-Identifier: Apache-2.0 - -"""Proof-of-Life test for the NitrosAprilTagDetectionArray type adapter.""" - -import os -import pathlib -import time - -from isaac_ros_apriltag_interfaces.msg import AprilTagDetection, AprilTagDetectionArray -from isaac_ros_test import IsaacROSBaseTest, JSONConversion - -import launch -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode -import launch_testing - -import pytest -import rclpy - - -@pytest.mark.rostest -def generate_test_description(): - """Generate launch description with all ROS 2 nodes for testing.""" - test_ns = IsaacROSNitrosAprilTagDetectionArrayTest.generate_namespace() - container = ComposableNodeContainer( - name='test_container', - namespace='isaac_ros_nitros_container', - package='rclcpp_components', - executable='component_container_mt', - composable_node_descriptions=[ - ComposableNode( - package='isaac_ros_nitros_april_tag_detection_array_type', - plugin='nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArrayForwardNode', - name='NitrosAprilTagDetectionArrayForwardNode', - namespace=test_ns, - parameters=[{ - 'compatible_format': 'nitros_april_tag_detection_array' - }], - remappings=[ - (test_ns+'/topic_forward_input', test_ns+'/input'), - (test_ns+'/topic_forward_output', test_ns+'/output'), - ] - ), - ], - output='both', - arguments=['--ros-args', '--log-level', 'info'], - ) - - return IsaacROSNitrosAprilTagDetectionArrayTest.generate_test_description([ - container, - launch.actions.TimerAction( - period=2.5, actions=[launch_testing.actions.ReadyToTest()]) - ]) - - -class IsaacROSNitrosAprilTagDetectionArrayTest(IsaacROSBaseTest): - """Validate NitrosAprilTagDetectionArray type adapter.""" - - filepath = pathlib.Path(os.path.dirname(__file__)) - - @IsaacROSBaseTest.for_each_test_case(subfolder='nitros_april_tag_detection_array') - def test_nitros_april_tag_detection_array_type_conversions(self, test_folder) -> None: - """Expect the tag from NitrosAprilTagDetectionArray type to be compatible with source.""" - self.generate_namespace_lookup(['input', 'output']) - received_messages = {} - - received_message_sub = self.create_logging_subscribers( - subscription_requests=[('output', AprilTagDetectionArray)], - received_messages=received_messages - ) - - april_tag_detection_array_pub = self.node.create_publisher( - AprilTagDetectionArray, self.namespaces['input'], self.DEFAULT_QOS) - - try: - print(test_folder) - april_tag_detection_array = self.load_april_tag_detection_array_from_json( - test_folder / 'april_tag_detection_array.json') - - # Wait at most TIMEOUT seconds for subscriber to respond - TIMEOUT = 10 - end_time = time.time() + TIMEOUT - - done = False - while time.time() < end_time: - timestamp = self.node.get_clock().now().to_msg() - april_tag_detection_array.header.stamp = timestamp - - april_tag_detection_array_pub.publish(april_tag_detection_array) - - rclpy.spin_once(self.node, timeout_sec=0.1) - - # If we have received a message on the output topic, break - if 'output' in received_messages: - done = True - break - - self.assertTrue(done, "Didn't receive output on the output topic!") - - received_april_tag_detection_array = received_messages['output'] - - self.assertEqual(len(april_tag_detection_array.detections), - len(received_april_tag_detection_array.detections)) - - if(len(april_tag_detection_array.detections) == - len(received_april_tag_detection_array.detections)): - for count, april_tag_detection in enumerate(april_tag_detection_array.detections): - received_april_tag_detection = received_april_tag_detection_array.detections[ - count] - self.assertEqual(april_tag_detection.family, - received_april_tag_detection.family) - self.assertEqual(april_tag_detection.id, - received_april_tag_detection.id) - for i in range(4): - self.assertEqual(april_tag_detection.corners[i].x, - received_april_tag_detection.corners[i].x) - self.assertEqual(april_tag_detection.corners[i].y, - received_april_tag_detection.corners[i].y) - self.assertEqual(april_tag_detection.pose.pose.pose.position.x, - received_april_tag_detection.pose.pose.pose.position.x) - self.assertEqual(april_tag_detection.pose.pose.pose.position.y, - received_april_tag_detection.pose.pose.pose.position.y) - self.assertEqual(april_tag_detection.pose.pose.pose.position.z, - received_april_tag_detection.pose.pose.pose.position.z) - self.assertEqual(april_tag_detection.pose.pose.pose.orientation.x, - received_april_tag_detection.pose.pose.pose.orientation.x) - self.assertEqual(april_tag_detection.pose.pose.pose.orientation.y, - received_april_tag_detection.pose.pose.pose.orientation.y) - self.assertEqual(april_tag_detection.pose.pose.pose.orientation.z, - received_april_tag_detection.pose.pose.pose.orientation.z) - self.assertEqual(april_tag_detection.pose.pose.pose.orientation.w, - received_april_tag_detection.pose.pose.pose.orientation.w) - print('The received april tag detection array has been verified successfully') - finally: - self.node.destroy_subscription(received_message_sub) - self.node.destroy_publisher(april_tag_detection_array_pub) - - @staticmethod - def load_april_tag_detection_array_from_json( - json_filepath: pathlib.Path) -> AprilTagDetectionArray: - """ - Load a AprilTagDetectionArray message from a JSON filepath. - - Parameters - ---------- - json_filepath : Path - The path to a JSON file containing the AprilTagDetectionArray fields - - Returns - ------- - AprilTagDetectionArray - Generated AprilTagDetectionArray message - - """ - apriltag_detection_array_json = JSONConversion.load_from_json( - json_filepath) - - apriltag_detection_array = AprilTagDetectionArray() - apriltag_detection_array.header.frame_id = apriltag_detection_array_json[ - 'header']['frame_id'] - for detection in apriltag_detection_array_json['detections']: - apriltag_detection = AprilTagDetection() - apriltag_detection.id = detection['id'] - apriltag_detection.family = detection['family'] - apriltag_detection.center.x = detection['center']['x'] - apriltag_detection.center.y = detection['center']['y'] - for corner_index, corner in enumerate(detection['corners']): - apriltag_detection.corners[corner_index].x = corner['x'] - apriltag_detection.corners[corner_index].y = corner['y'] - apriltag_detection.pose.header.frame_id = detection['pose']['header']['frame_id'] - apriltag_detection.pose.pose.pose.position.x = detection[ - 'pose']['pose']['pose']['position']['x'] - apriltag_detection.pose.pose.pose.position.y = detection[ - 'pose']['pose']['pose']['position']['y'] - apriltag_detection.pose.pose.pose.position.z = detection[ - 'pose']['pose']['pose']['position']['z'] - apriltag_detection.pose.pose.pose.orientation.x = detection[ - 'pose']['pose']['pose']['orientation']['x'] - apriltag_detection.pose.pose.pose.orientation.y = detection[ - 'pose']['pose']['pose']['orientation']['y'] - apriltag_detection.pose.pose.pose.orientation.z = detection[ - 'pose']['pose']['pose']['orientation']['z'] - apriltag_detection.pose.pose.pose.orientation.w = detection[ - 'pose']['pose']['pose']['orientation']['w'] - apriltag_detection_array.detections.append(apriltag_detection) - - return apriltag_detection_array diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/src/nitros_april_tag_detection_array_forward_node.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/src/nitros_april_tag_detection_array_forward_node.cpp deleted file mode 100644 index 9285feb..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/src/nitros_april_tag_detection_array_forward_node.cpp +++ /dev/null @@ -1,94 +0,0 @@ -// SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2022-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// SPDX-License-Identifier: Apache-2.0 - -#include "isaac_ros_nitros_april_tag_detection_array_type/nitros_april_tag_detection_array.hpp" -#include "isaac_ros_nitros/nitros_node.hpp" - -#include "rclcpp_components/register_node_macro.hpp" - -namespace nvidia -{ -namespace isaac_ros -{ -namespace nitros -{ - -constexpr char PACKAGE_NAME[] = "isaac_ros_nitros_april_tag_detection_array_type"; -constexpr char FORWARD_FORMAT[] = "nitros_april_tag_detection_array"; - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wpedantic" -class NitrosAprilTagDetectionArrayForwardNode : public NitrosNode -{ -public: - explicit NitrosAprilTagDetectionArrayForwardNode(const rclcpp::NodeOptions & options) - : NitrosNode( - options, - // Application graph filename - "test/config/test_forward_node.yaml", - // I/O configuration map - { - {"forward/input", - { - .type = NitrosPublisherSubscriberType::NEGOTIATED, - .qos = rclcpp::QoS(1), - .compatible_data_format = FORWARD_FORMAT, - .topic_name = "topic_forward_input", - .use_compatible_format_only = true, - } - }, - {"sink/sink", - { - .type = NitrosPublisherSubscriberType::NEGOTIATED, - .qos = rclcpp::QoS( - 1), - .compatible_data_format = FORWARD_FORMAT, - .topic_name = "topic_forward_output", - .use_compatible_format_only = true, - } - } - }, - // Extension specs - {}, - // Optimizer's rule filenames - {}, - // Extension so file list - { - {"gxf_isaac_message_compositor", "gxf/lib/libgxf_isaac_message_compositor.so"}, - {"isaac_ros_nitros_april_tag_detection_array_type", "gxf/lib/fiducial_message/test/libisaac_ros_nitros_april_tag_detection_array_test_ext.so"} // NOLINT - }, - // Test node package name - PACKAGE_NAME) - { - std::string compatible_format = declare_parameter("compatible_format", ""); - if (!compatible_format.empty()) { - config_map_["forward/input"].compatible_data_format = compatible_format; - config_map_["sink/sink"].compatible_data_format = compatible_format; - } - - registerSupportedType(); - - startNitrosNode(); - } -}; -#pragma GCC diagnostic pop - -} // namespace nitros -} // namespace isaac_ros -} // namespace nvidia - -RCLCPP_COMPONENTS_REGISTER_NODE(nvidia::isaac_ros::nitros::NitrosAprilTagDetectionArrayForwardNode) diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/test_cases/nitros_april_tag_detection_array/profile/april_tag_detection_array.json b/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/test_cases/nitros_april_tag_detection_array/profile/april_tag_detection_array.json deleted file mode 100644 index bce0727..0000000 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/test_cases/nitros_april_tag_detection_array/profile/april_tag_detection_array.json +++ /dev/null @@ -1,99 +0,0 @@ -{ - "header": { - "frame_id": "tf_camera" - }, - "detections":[ - { - "id": 1, - "family": "tag36h11", - "center":{ - "x": 2.0, - "y": 3.0 - }, - "corners":[ - { - "x": 4.0, - "y": 5.0 - }, - { - "x": 6.0, - "y": 7.0 - }, - { - "x": 8.0, - "y": 9.0 - }, - { - "x": 10.0, - "y": 11.0 - } - ], - "pose":{ - "header": { - "frame_id": "tf_camera_tag1" - }, - "pose": { - "pose":{ - "position": { - "x": 1.0, - "y": 0.0, - "z": 0.0 - }, - "orientation": { - "x": 0.0, - "y": 0.0, - "z": 0.0, - "w": 1.0 - } - } - } - } - }, - { - "id": 2, - "family": "tag36h11", - "center":{ - "x": 12.0, - "y": 13.0 - }, - "corners":[ - { - "x": 14.0, - "y": 15.0 - }, - { - "x": 16.0, - "y": 17.0 - }, - { - "x": 18.0, - "y": 19.0 - }, - { - "x": 20.0, - "y": 21.0 - } - ], - "pose":{ - "header": { - "frame_id": "tf_camera_tag2" - }, - "pose": { - "pose":{ - "position": { - "x": 0.0, - "y": 1.0, - "z": 0.0 - }, - "orientation": { - "x": 0.0, - "y": 0.0, - "z": 0.0, - "w": 1.0 - } - } - } - } - } - ] -} \ No newline at end of file diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_battery_state_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_battery_state_type/CMakeLists.txt index 83ad67b..f3637c5 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_battery_state_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_battery_state_type/CMakeLists.txt @@ -80,4 +80,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_battery_state_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_battery_state_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_battery_state_type/package.xml index 68c9f19..5bb35f9 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_battery_state_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_battery_state_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_battery_state_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Battery State Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/CMakeLists.txt index 64a6085..96de8c0 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/CMakeLists.txt @@ -37,7 +37,11 @@ endif() find_package(yaml-cpp) # NitrosCameraInfo -ament_auto_add_library(${PROJECT_NAME} SHARED src/nitros_camera_info.cpp) +ament_auto_add_library(${PROJECT_NAME} SHARED + src/nitros_camera_info.cpp + src/nitros_camera_info_view.cpp +) + target_link_libraries(${PROJECT_NAME} yaml-cpp ) @@ -78,4 +82,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_camera_info_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/include/isaac_ros_nitros_camera_info_type/nitros_camera_info.hpp b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/include/isaac_ros_nitros_camera_info_type/nitros_camera_info.hpp index 05cd450..0c8dee0 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/include/isaac_ros_nitros_camera_info_type/nitros_camera_info.hpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/include/isaac_ros_nitros_camera_info_type/nitros_camera_info.hpp @@ -28,6 +28,11 @@ #include "isaac_ros_nitros/types/nitros_format_agent.hpp" #include "isaac_ros_nitros/types/nitros_type_base.hpp" +#include "gxf/core/gxf.h" +#include "gxf/core/entity.hpp" +#include "gxf/multimedia/camera.hpp" +#include "gxf/std/timestamp.hpp" + #include "rclcpp/type_adapter.hpp" #include "sensor_msgs/msg/camera_info.hpp" @@ -63,6 +68,11 @@ NITROS_TYPE_EXTENSION_ADD("isaac_ros_gxf", "gxf/lib/multimedia/libgxf_multimedia NITROS_TYPE_EXTENSION_FACTORY_END() NITROS_TYPE_FACTORY_END() +// Helper for convert_to_custom, resusable in other nodes +void copy_ros_to_gxf_camera_info( + sensor_msgs::msg::CameraInfo source, + nvidia::gxf::Expected & destination); + } // namespace nitros } // namespace isaac_ros } // namespace nvidia diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/extensions/fiducials/gems/fiducial_info.hpp b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/include/isaac_ros_nitros_camera_info_type/nitros_camera_info_view.hpp similarity index 50% rename from isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/extensions/fiducials/gems/fiducial_info.hpp rename to isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/include/isaac_ros_nitros_camera_info_type/nitros_camera_info_view.hpp index cd9ad44..eb6f9cb 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/include/extensions/fiducials/gems/fiducial_info.hpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/include/isaac_ros_nitros_camera_info_type/nitros_camera_info_view.hpp @@ -1,5 +1,5 @@ // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -14,33 +14,25 @@ // limitations under the License. // // SPDX-License-Identifier: Apache-2.0 -#pragma once -#include +#ifndef ISAAC_ROS_NITROS_CAMERA_INFO_TYPE__NITROS_CAMERA_INFO_VIEW_HPP_ +#define ISAAC_ROS_NITROS_CAMERA_INFO_TYPE__NITROS_CAMERA_INFO_VIEW_HPP_ + +#include "isaac_ros_nitros/types/nitros_type_view_factory.hpp" +#include "isaac_ros_nitros_camera_info_type/nitros_camera_info.hpp" namespace nvidia { -namespace isaac +namespace isaac_ros { - -// Data structure holding meta information about fiducial messages. -struct FiducialInfo +namespace nitros { - // A fiducial can be of type (April Tag, QRCode, Barcode or ARTag) - enum class Type - { - kAprilTag, - kQrCode, - kBarcode, - kArTag, - }; - // Enum to identify the type of fiducial represented by the message - Type type; - // Text field that identifies the ID of the fiducial - // For AprilTag, the id is of the format - // Ex. If the decoded tag ID is 14 and belongs to TagFamily tag36h11, the id is tag36h11_14 - std::string id; -}; -} // namespace isaac +NITROS_TYPE_VIEW_FACTORY_BEGIN(NitrosCameraInfo) +NITROS_TYPE_VIEW_FACTORY_END(NitrosCameraInfo) + +} // namespace nitros +} // namespace isaac_ros } // namespace nvidia + +#endif // ISAAC_ROS_NITROS_CAMERA_INFO_TYPE__NITROS_CAMERA_INFO_VIEW_HPP_ diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/package.xml index 676b7ce..75150c9 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_camera_info_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Camera Info Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/src/nitros_camera_info.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/src/nitros_camera_info.cpp index 92a5c4f..3507e3b 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/src/nitros_camera_info.cpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/src/nitros_camera_info.cpp @@ -23,10 +23,6 @@ #pragma GCC diagnostic ignored "-Wunused-parameter" #pragma GCC diagnostic ignored "-Wmissing-field-initializers" #pragma GCC diagnostic ignored "-Wpedantic" -#include "gxf/core/entity.hpp" -#include "gxf/core/gxf.h" -#include "gxf/multimedia/camera.hpp" -#include "gxf/std/timestamp.hpp" #pragma GCC diagnostic pop #include "isaac_ros_nitros_camera_info_type/nitros_camera_info.hpp" @@ -39,12 +35,12 @@ constexpr char RAW_CAMERA_MODEL_GXF_NAME[] = "intrinsics"; constexpr char RECT_CAMERA_MODEL_GXF_NAME[] = "target_camera"; constexpr char EXTRINSICS_GXF_NAME[] = "extrinsics"; constexpr char TARGET_EXTRINSICS_DELTA_GXF_NAME[] = "target_extrinsics_delta"; +constexpr int NUM_COFF_PLUMB_BOB = 5; namespace { using DistortionType = nvidia::gxf::DistortionType; const std::unordered_map g_ros_to_gxf_distortion_model({ - {"pinhole", DistortionType::Perspective}, {"plumb_bob", DistortionType::Brown}, {"rational_polynomial", DistortionType::Polynomial}, {"equidistant", DistortionType::FisheyeEquidistant} @@ -53,12 +49,207 @@ const std::unordered_map g_ros_to_gxf_distortion_mo const std::unordered_map g_gxf_to_ros_distortion_model({ {DistortionType::Polynomial, "rational_polynomial"}, {DistortionType::FisheyeEquidistant, "equidistant"}, - {DistortionType::Perspective, "pinhole"}, + {DistortionType::Perspective, "plumb_bob"}, {DistortionType::Brown, "plumb_bob"} }); } // namespace +namespace nvidia +{ +namespace isaac_ros +{ +namespace nitros +{ + +// Convert between an existing ROS CameraInfo message and an existing GXF CameraModel object +// Also used in argus_camera_node.cpp +void copy_ros_to_gxf_camera_info( + sensor_msgs::msg::CameraInfo source, + nvidia::gxf::Expected & destination) +{ + RCLCPP_DEBUG( + rclcpp::get_logger( + "NitrosCameraInfo"), + "[convert_to_custom] Overriding CameraModel with values loaded from URL"); + + auto raw_gxf_camera_model = destination->get(RAW_CAMERA_MODEL_GXF_NAME); + auto rect_gxf_camera_model = + destination->get(RECT_CAMERA_MODEL_GXF_NAME); + auto extrinsics_gxf_pose_3d = destination->get(EXTRINSICS_GXF_NAME); + auto target_extrinsics_delta_gxf_pose_3d = destination->get( + TARGET_EXTRINSICS_DELTA_GXF_NAME); + + if (!raw_gxf_camera_model) { + std::stringstream error_msg; + error_msg << + "[convert_to_custom] Failed to get the existing CameraModel object: " << + GxfResultStr(raw_gxf_camera_model.error()); + RCLCPP_ERROR( + rclcpp::get_logger("NitrosCameraInfo"), error_msg.str().c_str()); + throw std::runtime_error(error_msg.str().c_str()); + } + + if (!extrinsics_gxf_pose_3d) { + std::stringstream error_msg; + error_msg << "[convert_to_custom] Failed to get Pose3D object from message entity: " << + GxfResultStr(extrinsics_gxf_pose_3d.error()); + RCLCPP_ERROR( + rclcpp::get_logger("NitrosCameraInfo"), error_msg.str().c_str()); + throw std::runtime_error(error_msg.str().c_str()); + } + + if (!rect_gxf_camera_model) { + std::stringstream warn_msg; + warn_msg << "[convert_to_custom] Rectified camera model from message entity: " << + GxfResultStr(rect_gxf_camera_model.error()) << " this is expected for monocular cameras"; + RCLCPP_WARN_ONCE( + rclcpp::get_logger("NitrosCameraInfo"), warn_msg.str().c_str()); + rect_gxf_camera_model = raw_gxf_camera_model; + } else { + // Only set this to perspective/0 if we did not fall back to the raw camera model + // otherwise we will overwrite the distortion model + rect_gxf_camera_model.value()->distortion_type = DistortionType::Perspective; + memset( + rect_gxf_camera_model.value()->distortion_coefficients.data(), 0, + rect_gxf_camera_model.value()->kMaxDistortionCoefficients * sizeof(float)); + } + + if (!target_extrinsics_delta_gxf_pose_3d) { + std::stringstream warn_msg; + warn_msg << + "[convert_to_custom] Failed to get the target extrinsics delta Pose3D object: " << + GxfResultStr(target_extrinsics_delta_gxf_pose_3d.error()) << + " this is expected for monocular cameras"; + RCLCPP_WARN_ONCE( + rclcpp::get_logger("NitrosCameraInfo"), warn_msg.str().c_str()); + // Add a target extrinsics delta, we should only be taking this path + // in the case where we override camera info for a monocular camera. + // So this delta should be identity rotation and 0 translation, but + // we will set it to whatever the rectification matrix passed in is. + // This way overridden camera info messages behave exactly like the + // original eeprom case. + target_extrinsics_delta_gxf_pose_3d = destination->add( + TARGET_EXTRINSICS_DELTA_GXF_NAME); + } + + raw_gxf_camera_model.value()->dimensions = {source.width, source.height}; + raw_gxf_camera_model.value()->focal_length = { + static_cast(source.k[0]), static_cast(source.k[4])}; + raw_gxf_camera_model.value()->principal_point = { + static_cast(source.k[2]), static_cast(source.k[5])}; + + const auto distortion = g_ros_to_gxf_distortion_model.find(source.distortion_model); + if (distortion == std::end(g_ros_to_gxf_distortion_model)) { + std::stringstream error_msg; + error_msg << + "[convert_to_custom] Unsupported distortion model from ROS [" << + source.distortion_model.c_str() << "]."; + RCLCPP_ERROR( + rclcpp::get_logger("NitrosCameraInfo"), error_msg.str().c_str()); + throw std::runtime_error(error_msg.str().c_str()); + } else { + raw_gxf_camera_model.value()->distortion_type = distortion->second; + } + + memset( + raw_gxf_camera_model.value()->distortion_coefficients.data(), 0, + sizeof(raw_gxf_camera_model.value()->distortion_coefficients)); + + // If the distortion model is "Brown", check if all the distortion parameters are zero + // If yes, then set the distortion type to "Perspective" + if (distortion->second == DistortionType::Brown && source.d.size() == NUM_COFF_PLUMB_BOB) { + if (std::all_of( + source.d.begin(), source.d.end(), + [](const auto & value) {return value == 0;})) + { + raw_gxf_camera_model.value()->distortion_type = DistortionType::Perspective; + } + } + + if (source.d.size() > nvidia::gxf::CameraModel::kMaxDistortionCoefficients) { + std::stringstream error_msg; + error_msg << + "[convert_to_custom] More number of coefficients for distortion model found [ # of coeff: " << + source.d.size() << " > " << nvidia::gxf::CameraModel::kMaxDistortionCoefficients << "]."; + RCLCPP_ERROR( + rclcpp::get_logger("NitrosCameraInfo"), error_msg.str().c_str()); + throw std::runtime_error(error_msg.str().c_str()); + } + + if (raw_gxf_camera_model.value()->distortion_type == DistortionType::Polynomial) { + // prevents distortion parameters array access if its empty + // simulators may send empty distortion parameter array since images are already rectified + if (!source.d.empty()) { + // distortion parameters in GXF: k1, k2, k3, k4, k5, k6, p1, p2 + // distortion parameters in ROS message: k1, k2, p1, p2, k3 ... + raw_gxf_camera_model.value()->distortion_coefficients[0] = source.d[0]; + raw_gxf_camera_model.value()->distortion_coefficients[1] = source.d[1]; + + for (uint16_t index = 2; index < source.d.size() - 2; index++) { + raw_gxf_camera_model.value()->distortion_coefficients[index] = source.d[index + 2]; + } + raw_gxf_camera_model.value()->distortion_coefficients[6] = source.d[2]; + raw_gxf_camera_model.value()->distortion_coefficients[7] = source.d[3]; + } + } else if (raw_gxf_camera_model.value()->distortion_type == DistortionType::Brown) { + // prevents distortion parameters array access if its empty + // simulators may send empty distortion parameter array since images are already rectified + if (!source.d.empty()) { + // distortion parameters in GXF: k1, k2, k3, k4, k5, k6, p1, p2 + // distortion parameters in ROS message: k1, k2, p1, p2, k3 ... + raw_gxf_camera_model.value()->distortion_coefficients[0] = source.d[0]; + raw_gxf_camera_model.value()->distortion_coefficients[1] = source.d[1]; + raw_gxf_camera_model.value()->distortion_coefficients[2] = source.d[4]; + for (uint16_t index = 3; + index < nvidia::gxf::CameraModel::kMaxDistortionCoefficients - 2; + index++) + { + raw_gxf_camera_model.value()->distortion_coefficients[index] = 0; + } + raw_gxf_camera_model.value()->distortion_coefficients[6] = source.d[2]; + raw_gxf_camera_model.value()->distortion_coefficients[7] = source.d[3]; + } + } else { + std::copy( + std::begin(source.d), std::end(source.d), + std::begin(raw_gxf_camera_model.value()->distortion_coefficients)); + } + + rect_gxf_camera_model.value()->dimensions = {source.width, source.height}; + rect_gxf_camera_model.value()->focal_length = { + static_cast(source.p[0]), static_cast(source.p[5])}; + rect_gxf_camera_model.value()->principal_point = { + static_cast(source.p[2]), static_cast(source.p[6])}; + + // populate rectification rotation matrix into the TARGET_EXTRINSICS_DELTA_GXF_NAME + std::copy( + std::begin(source.r), std::end(source.r), + std::begin(target_extrinsics_delta_gxf_pose_3d.value()->rotation)); + + // Based on the comments for the camera info msg type, p[0] == 0 means the topic + // contains no calibration data, ie, its an uncalibrated camera + if (source.p[0] == 0.0f) { + RCLCPP_WARN( + rclcpp::get_logger("NitrosCameraInfo"), + "[convert_to_custom] Received an uncalibrated camera info msg."); + extrinsics_gxf_pose_3d.value()->translation = { + 0, + 0, + 0}; + } else { + // populate extrinsics translation the EXTRINSICS_GXF_NAME + extrinsics_gxf_pose_3d.value()->translation = { + static_cast(source.p[3]) / static_cast(source.p[0]), + static_cast(source.p[7]), + static_cast(source.p[11])}; + } +} + +} // namespace nitros +} // namespace isaac_ros +} // namespace nvidia + void rclcpp::TypeAdapter< nvidia::isaac_ros::nitros::NitrosCameraInfo, sensor_msgs::msg::CameraInfo>::convert_to_ros_message( @@ -115,12 +306,11 @@ void rclcpp::TypeAdapter< destination.distortion_model = distortion->second; } - // Resize d buffer to the right size - destination.d.resize( - sizeof(raw_gxf_camera_model.value()->distortion_coefficients) / - sizeof(float)); - if (raw_gxf_camera_model.value()->distortion_type == DistortionType::Polynomial) { + // Resize d buffer to the right size + destination.d.resize( + sizeof(raw_gxf_camera_model.value()->distortion_coefficients) / + sizeof(float)); destination.d[0] = raw_gxf_camera_model.value()->distortion_coefficients[0]; destination.d[1] = raw_gxf_camera_model.value()->distortion_coefficients[1]; destination.d[2] = raw_gxf_camera_model.value()->distortion_coefficients[6]; @@ -130,15 +320,26 @@ void rclcpp::TypeAdapter< destination.d[6] = raw_gxf_camera_model.value()->distortion_coefficients[4]; destination.d[7] = raw_gxf_camera_model.value()->distortion_coefficients[5]; } else if (raw_gxf_camera_model.value()->distortion_type == DistortionType::Brown) { + // Resize d buffer to the right size + destination.d.resize(NUM_COFF_PLUMB_BOB); destination.d[0] = raw_gxf_camera_model.value()->distortion_coefficients[0]; destination.d[1] = raw_gxf_camera_model.value()->distortion_coefficients[1]; destination.d[2] = raw_gxf_camera_model.value()->distortion_coefficients[6]; destination.d[3] = raw_gxf_camera_model.value()->distortion_coefficients[7]; destination.d[4] = raw_gxf_camera_model.value()->distortion_coefficients[2]; - destination.d[5] = 0; - destination.d[6] = 0; - destination.d[7] = 0; + } else if (raw_gxf_camera_model.value()->distortion_type == DistortionType::Perspective) { + // Resize d buffer to the right size + destination.d.resize(NUM_COFF_PLUMB_BOB); + destination.d[0] = 0.0; + destination.d[1] = 0.0; + destination.d[2] = 0.0; + destination.d[3] = 0.0; + destination.d[4] = 0.0; } else { + // Resize d buffer to the right size + destination.d.resize( + sizeof(raw_gxf_camera_model.value()->distortion_coefficients) / + sizeof(float)); std::copy( std::begin(raw_gxf_camera_model.value()->distortion_coefficients), std::end(raw_gxf_camera_model.value()->distortion_coefficients), std::begin(destination.d)); @@ -256,86 +457,7 @@ void rclcpp::TypeAdapter< } auto raw_gxf_camera_model = message->add(RAW_CAMERA_MODEL_GXF_NAME); - - raw_gxf_camera_model.value()->dimensions = {source.width, source.height}; - raw_gxf_camera_model.value()->focal_length = { - static_cast(source.k[0]), static_cast(source.k[4])}; - raw_gxf_camera_model.value()->principal_point = { - static_cast(source.k[2]), static_cast(source.k[5])}; - - const auto distortion = g_ros_to_gxf_distortion_model.find(source.distortion_model); - if (distortion == std::end(g_ros_to_gxf_distortion_model)) { - std::stringstream error_msg; - error_msg << - "[convert_to_custom] Unsupported distortion model from ROS [" << - source.distortion_model.c_str() << "]."; - RCLCPP_ERROR( - rclcpp::get_logger("NitrosCameraInfo"), error_msg.str().c_str()); - throw std::runtime_error(error_msg.str().c_str()); - } else { - raw_gxf_camera_model.value()->distortion_type = distortion->second; - } - - if (source.d.size() > nvidia::gxf::CameraModel::kMaxDistortionCoefficients) { - std::stringstream error_msg; - error_msg << - "[convert_to_custom] More number of coefficients for distortion model found [ # of coeff: " << - source.d.size() << " > " << nvidia::gxf::CameraModel::kMaxDistortionCoefficients << "]."; - RCLCPP_ERROR( - rclcpp::get_logger("NitrosCameraInfo"), error_msg.str().c_str()); - throw std::runtime_error(error_msg.str().c_str()); - } - - if (raw_gxf_camera_model.value()->distortion_type == DistortionType::Polynomial) { - // prevents distortion parameters array access if its empty - // simulators may send empty distortion parameter array since images are already rectified - if (!source.d.empty()) { - // distortion parameters in GXF: k1, k2, k3, k4, k5, k6, p1, p2 - // distortion parameters in ROS message: k1, k2, p1, p2, k3 ... - raw_gxf_camera_model.value()->distortion_coefficients[0] = source.d[0]; - raw_gxf_camera_model.value()->distortion_coefficients[1] = source.d[1]; - - for (uint16_t index = 2; index < source.d.size() - 2; index++) { - raw_gxf_camera_model.value()->distortion_coefficients[index] = source.d[index + 2]; - } - raw_gxf_camera_model.value()->distortion_coefficients[6] = source.d[2]; - raw_gxf_camera_model.value()->distortion_coefficients[7] = source.d[3]; - } - } else if (raw_gxf_camera_model.value()->distortion_type == DistortionType::Brown) { - // prevents distortion parameters array access if its empty - // simulators may send empty distortion parameter array since images are already rectified - if (!source.d.empty()) { - // distortion parameters in GXF: k1, k2, k3, k4, k5, k6, p1, p2 - // distortion parameters in ROS message: k1, k2, p1, p2, k3 ... - raw_gxf_camera_model.value()->distortion_coefficients[0] = source.d[0]; - raw_gxf_camera_model.value()->distortion_coefficients[1] = source.d[1]; - raw_gxf_camera_model.value()->distortion_coefficients[2] = source.d[4]; - for (uint16_t index = 3; - index < nvidia::gxf::CameraModel::kMaxDistortionCoefficients - 2; - index++) - { - raw_gxf_camera_model.value()->distortion_coefficients[index] = 0; - } - raw_gxf_camera_model.value()->distortion_coefficients[6] = source.d[2]; - raw_gxf_camera_model.value()->distortion_coefficients[7] = source.d[3]; - } - } else { - std::copy( - std::begin(source.d), std::end(source.d), - std::begin(raw_gxf_camera_model.value()->distortion_coefficients)); - } - - // add rectified image camera model auto rect_gxf_camera_model = message->add(RECT_CAMERA_MODEL_GXF_NAME); - rect_gxf_camera_model.value()->dimensions = {source.width, source.height}; - rect_gxf_camera_model.value()->focal_length = { - static_cast(source.p[0]), static_cast(source.p[5])}; - rect_gxf_camera_model.value()->principal_point = { - static_cast(source.p[2]), static_cast(source.p[6])}; - rect_gxf_camera_model.value()->distortion_type = DistortionType::Perspective; - memset( - rect_gxf_camera_model.value()->distortion_coefficients, 0, - rect_gxf_camera_model.value()->kMaxDistortionCoefficients * sizeof(float)); // this pose3D entity is used to passthrough the translation between the two cameras // this translation data is not used by the tensorops rectification library // Note: The rotation of this EXTRINSICS_GXF_NAME pose3D entity is set identity @@ -346,28 +468,8 @@ void rclcpp::TypeAdapter< auto target_extrinsics_delta_gxf_pose_3d = message->add( TARGET_EXTRINSICS_DELTA_GXF_NAME); - // populate rectification rotation matrix into the TARGET_EXTRINSICS_DELTA_GXF_NAME - std::copy( - std::begin(source.r), std::end(source.r), - std::begin(target_extrinsics_delta_gxf_pose_3d.value()->rotation)); - // Based on the comments for the camera info msg type, p[0] == 0 means the topic - // contains no calibration data, ie, its an uncalibrated camera - if (source.p[0] == 0.0f) { - RCLCPP_WARN( - rclcpp::get_logger("NitrosCameraInfo"), - "[convert_to_custom] Received an uncalibrated camera info msg."); - extrinsics_gxf_pose_3d.value()->translation = { - 0, - 0, - 0}; - } else { - // populate extrinsics translation the EXTRINSICS_GXF_NAME - extrinsics_gxf_pose_3d.value()->translation = { - static_cast(source.p[3]) / static_cast(source.p[0]), - static_cast(source.p[7]), - static_cast(source.p[11])}; - } + nvidia::isaac_ros::nitros::copy_ros_to_gxf_camera_info(source, message); // Add timestamp to the message uint64_t input_timestamp = diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/src/fiducial_message_test_ext.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/src/nitros_camera_info_view.cpp similarity index 54% rename from isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/src/fiducial_message_test_ext.cpp rename to isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/src/nitros_camera_info_view.cpp index 2be1f3e..e03a495 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_april_tag_detection_array_type/test/src/fiducial_message_test_ext.cpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_camera_info_type/src/nitros_camera_info_view.cpp @@ -1,5 +1,5 @@ // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -15,19 +15,17 @@ // // SPDX-License-Identifier: Apache-2.0 -#include "extensions/fiducials/gems/fiducial_info.hpp" -#include "gxf/std/extension_factory_helper.hpp" +#include "isaac_ros_nitros_camera_info_type/nitros_camera_info_view.hpp" -GXF_EXT_FACTORY_BEGIN() +namespace nvidia +{ +namespace isaac_ros +{ +namespace nitros +{ -GXF_EXT_FACTORY_SET_INFO( - 0xd8d7816ec0485ad4, 0xff795a414bd445ca, "FiducialsTestMessageExtension", - "Test extension for fiducials messages", - "NVIDIA", "1.0.0", "LICENSE"); +void NitrosCameraInfoView::InitView() {} -GXF_EXT_FACTORY_ADD_0( - 0xe91d3fa6a42b85ff, 0x966f4e80c607ca9e, - nvidia::isaac::FiducialInfo, - "Holds fiducial meta information."); - -GXF_EXT_FACTORY_END() +} // namespace nitros +} // namespace isaac_ros +} // namespace nvidia diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_compressed_image_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_compressed_image_type/CMakeLists.txt index 87088b2..a6a8d50 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_compressed_image_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_compressed_image_type/CMakeLists.txt @@ -72,4 +72,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_compressed_image_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_compressed_image_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_compressed_image_type/package.xml index 936e252..df6dfd6 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_compressed_image_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_compressed_image_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_compressed_image_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Compressed Image Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_compressed_video_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_compressed_video_type/CMakeLists.txt index 1e63f34..c9d7a27 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_compressed_video_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_compressed_video_type/CMakeLists.txt @@ -76,4 +76,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_compressed_video_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_compressed_video_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_compressed_video_type/package.xml index fe04a4b..fde99dc 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_compressed_video_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_compressed_video_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_compressed_video_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Compressed Video Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_correlated_timestamp_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_correlated_timestamp_type/CMakeLists.txt index 6bde053..e9358c6 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_correlated_timestamp_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_correlated_timestamp_type/CMakeLists.txt @@ -80,4 +80,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_correlated_timestamp_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_correlated_timestamp_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_correlated_timestamp_type/package.xml index 395a32f..4331d28 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_correlated_timestamp_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_correlated_timestamp_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_correlated_timestamp_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Correlated Timestamp Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/CMakeLists.txt index fd6431e..1968016 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/CMakeLists.txt @@ -101,4 +101,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_detection2_d_array_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/include/detectnet/detection2_d.hpp b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/include/detectnet/detection2_d.hpp index 2e5a93a..ad292e8 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/include/detectnet/detection2_d.hpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/include/detectnet/detection2_d.hpp @@ -14,6 +14,7 @@ // limitations under the License. // // SPDX-License-Identifier: Apache-2.0 + #ifndef DETECTNET__DETECTION2_D_HPP_ #define DETECTNET__DETECTION2_D_HPP_ diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/include/detectnet/detection2_d_array_message.hpp b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/include/detectnet/detection2_d_array_message.hpp index ea88b90..0988bd6 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/include/detectnet/detection2_d_array_message.hpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/include/detectnet/detection2_d_array_message.hpp @@ -14,14 +14,15 @@ // limitations under the License. // // SPDX-License-Identifier: Apache-2.0 + #ifndef DETECTNET__DETECTION2_D_ARRAY_MESSAGE_HPP_ #define DETECTNET__DETECTION2_D_ARRAY_MESSAGE_HPP_ #include +#include "detection2_d.hpp" #include "gxf/core/entity.hpp" #include "gxf/std/timestamp.hpp" -#include "detection2_d.hpp" namespace nvidia { diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/package.xml index 6d26bda..c5729d9 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_detection2_d_array_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Detection 2D Array Type Isaac ROS Maintainers @@ -33,7 +33,6 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. ament_lint_auto ament_lint_common isaac_ros_test - isaac_ros_nitros_interfaces ament_cmake diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/src/detection2_d_array_message.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/src/detection2_d_array_message.cpp index 30dfe4f..6a79e54 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/src/detection2_d_array_message.cpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/src/detection2_d_array_message.cpp @@ -18,6 +18,7 @@ #include "detection2_d_array_message.hpp" #include +#include namespace nvidia { diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/test/isaac_ros_nitros_detection2_d_array_type_test_pol.py b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/test/isaac_ros_nitros_detection2_d_array_type_test_pol.py index be2721b..b212ba8 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/test/isaac_ros_nitros_detection2_d_array_type_test_pol.py +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection2_d_array_type/test/isaac_ros_nitros_detection2_d_array_type_test_pol.py @@ -119,7 +119,7 @@ def test_nitros_detection2_d_array_type_conversions(self, test_folder) -> None: self.assertEqual(len(nitros_detection2_d_array.detections), len(received_nitros_detection2_d_array.detections)) - if(len(nitros_detection2_d_array.detections) == + if (len(nitros_detection2_d_array.detections) == len(received_nitros_detection2_d_array.detections)): for detection_count, detection2_d in \ enumerate(nitros_detection2_d_array.detections): @@ -127,7 +127,7 @@ def test_nitros_detection2_d_array_type_conversions(self, test_folder) -> None: detection_count] self.assertEqual(len(detection2_d.results), len(received_detection2_d.results)) - if(len(detection2_d.results) == + if (len(detection2_d.results) == len(received_detection2_d.results)): for result_count, result in enumerate(detection2_d.results): received_result = received_detection2_d.results[result_count] diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/CMakeLists.txt index 2ffc2ba..9555768 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/CMakeLists.txt @@ -96,4 +96,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_detection3_d_array_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/package.xml index 8b42207..871c4e2 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_detection3_d_array_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Detection 3D Array Type Isaac ROS Maintainers @@ -35,7 +35,6 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. ament_lint_auto ament_lint_common isaac_ros_test - isaac_ros_nitros_interfaces ament_cmake diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/src/detection3_d_array_message.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/src/detection3_d_array_message.cpp index 9b8283f..ba8b2b0 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/src/detection3_d_array_message.cpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/src/detection3_d_array_message.cpp @@ -1,5 +1,5 @@ // SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES -// Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +// Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -17,6 +17,8 @@ #include "detection3_d_array_message/detection3_d_array_message.hpp" +#include "gems/gxf_helpers/expected_macro_gxf.hpp" + namespace nvidia { namespace isaac @@ -56,16 +58,12 @@ gxf::Expected GetDetection3DListMessage(gxf::Entity { Detection3DListMessageParts parts; parts.entity = entity; - auto result = - parts.entity.findAll<::nvidia::isaac::Pose3d>(parts.poses) - .and_then([&]() {parts.entity.findAll<::nvidia::isaac::Vector3f>(parts.bbox_sizes);}) - .and_then([&]() {parts.entity.findAll(parts.hypothesis);}) - .and_then([&]() {return parts.entity.get(kTimestampName);}) - .log_error("Entity does not contain component Timestamp %s.", kTimestampName) - .assign_to(parts.timestamp); - if (!result) { - return gxf::ForwardError(result); - } + + parts.poses = UNWRAP_OR_RETURN(parts.entity.findAll<::nvidia::isaac::Pose3d>()); + parts.bbox_sizes = UNWRAP_OR_RETURN(parts.entity.findAll<::nvidia::isaac::Vector3f>()); + parts.hypothesis = UNWRAP_OR_RETURN(parts.entity.findAll<::nvidia::isaac::ObjectHypothesis>()); + parts.timestamp = UNWRAP_OR_RETURN(parts.entity.get(kTimestampName)); + if (parts.poses.size() != parts.bbox_sizes.size() || parts.poses.size() != parts.hypothesis.size()) { diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/test/isaac_ros_nitros_detection3_d_array_type_test_pol.py b/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/test/isaac_ros_nitros_detection3_d_array_type_test_pol.py index 800bb14..0f47e58 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/test/isaac_ros_nitros_detection3_d_array_type_test_pol.py +++ b/isaac_ros_nitros_type/isaac_ros_nitros_detection3_d_array_type/test/isaac_ros_nitros_detection3_d_array_type_test_pol.py @@ -123,7 +123,7 @@ def test_nitros_detection3_d_array_type_conversions(self, test_folder) -> None: self.assertEqual(len(nitros_detection3_d_array.detections), len(received_nitros_detection3_d_array.detections)) - if(len(nitros_detection3_d_array.detections) == + if (len(nitros_detection3_d_array.detections) == len(received_nitros_detection3_d_array.detections)): for detection_count, detection3_d in \ enumerate(nitros_detection3_d_array.detections): @@ -131,7 +131,7 @@ def test_nitros_detection3_d_array_type_conversions(self, test_folder) -> None: detection_count] self.assertEqual(len(detection3_d.results), len(received_detection3_d.results)) - if(len(detection3_d.results) == + if (len(detection3_d.results) == len(received_detection3_d.results)): for result_count, result in enumerate(detection3_d.results): received_result = received_detection3_d.results[result_count] diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_disparity_image_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_disparity_image_type/CMakeLists.txt index da20747..fd61fdf 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_disparity_image_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_disparity_image_type/CMakeLists.txt @@ -77,4 +77,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_disparity_image_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_disparity_image_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_disparity_image_type/package.xml index cd32d19..420da50 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_disparity_image_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_disparity_image_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_disparity_image_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Disparity Image Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_encoder_ticks_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_encoder_ticks_type/CMakeLists.txt index f660f06..fbd98d5 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_encoder_ticks_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_encoder_ticks_type/CMakeLists.txt @@ -80,4 +80,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_encoder_ticks_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_encoder_ticks_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_encoder_ticks_type/package.xml index ea39955..2975fc1 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_encoder_ticks_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_encoder_ticks_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_encoder_ticks_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Encoder Ticks Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_flat_scan_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_flat_scan_type/CMakeLists.txt index 1545542..e87a2a7 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_flat_scan_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_flat_scan_type/CMakeLists.txt @@ -80,4 +80,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_flat_scan_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_flat_scan_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_flat_scan_type/package.xml index 66a0aee..618473c 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_flat_scan_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_flat_scan_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_flat_scan_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Flat Scan Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_image_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_image_type/CMakeLists.txt index 36b1fda..1656974 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_image_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_image_type/CMakeLists.txt @@ -82,4 +82,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_image_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_image_type/include/isaac_ros_nitros_image_type/nitros_image_details.hpp b/isaac_ros_nitros_type/isaac_ros_nitros_image_type/include/isaac_ros_nitros_image_type/nitros_image_details.hpp index 614baa7..e4db2fb 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_image_type/include/isaac_ros_nitros_image_type/nitros_image_details.hpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_image_type/include/isaac_ros_nitros_image_type/nitros_image_details.hpp @@ -153,6 +153,15 @@ struct NoPaddingColorPlanes std::array planes; }; +template<> +struct NoPaddingColorPlanes +{ + NoPaddingColorPlanes(size_t width) + : planes({nvidia::gxf::ColorPlane("Y", 1, width), + nvidia::gxf::ColorPlane("UV", 2, width * 2)}) {} + std::array planes; +}; + template<> struct NoPaddingColorPlanes { @@ -162,6 +171,15 @@ struct NoPaddingColorPlanes std::array planes; }; +template<> +struct NoPaddingColorPlanes +{ + NoPaddingColorPlanes(size_t width) + : planes({nvidia::gxf::ColorPlane("Y", 1, width), + nvidia::gxf::ColorPlane("UV", 2, width * 2)}) {} + std::array planes; +}; + template<> struct NoPaddingColorPlanes { diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_image_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_image_type/package.xml index e0f5c09..42699df 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_image_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_image_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_image_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Image Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_image_type/src/nitros_image_builder.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_image_type/src/nitros_image_builder.cpp index 0cb65e5..11cbd9c 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_image_type/src/nitros_image_builder.cpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_image_type/src/nitros_image_builder.cpp @@ -294,11 +294,21 @@ NitrosImage NitrosImageBuilder::Build() width_, height_, message, data_, nitros_image_.frame_id); break; + case VideoFormat::GXF_VIDEO_FORMAT_NV24_ER: + create_image( + width_, height_, message, data_, nitros_image_.frame_id); + break; + case VideoFormat::GXF_VIDEO_FORMAT_NV12: create_image( width_, height_, message, data_, nitros_image_.frame_id); break; + case VideoFormat::GXF_VIDEO_FORMAT_NV12_ER: + create_image( + width_, height_, message, data_, nitros_image_.frame_id); + break; + case VideoFormat::GXF_VIDEO_FORMAT_RGB32: create_image( width_, height_, message, data_, nitros_image_.frame_id); diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_imu_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_imu_type/CMakeLists.txt index ea20172..4d72423 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_imu_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_imu_type/CMakeLists.txt @@ -80,4 +80,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_imu_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_imu_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_imu_type/package.xml index e2a84a3..0af2649 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_imu_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_imu_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_imu_type - 3.1.0 + 3.2.0 Isaac ROS NITROS IMU Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_occupancy_grid_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_occupancy_grid_type/CMakeLists.txt index 1ea862a..9ba6447 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_occupancy_grid_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_occupancy_grid_type/CMakeLists.txt @@ -77,4 +77,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_occupancy_grid_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_occupancy_grid_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_occupancy_grid_type/package.xml index e702653..67b6536 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_occupancy_grid_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_occupancy_grid_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_occupancy_grid_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Occupancy Grid Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/CMakeLists.txt index 17bfdae..cf48c49 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/CMakeLists.txt @@ -80,4 +80,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_odometry_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/package.xml index 8e3b2a9..4331bb2 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_odometry_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Odometry Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/src/nitros_odometry.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/src/nitros_odometry.cpp index ec36708..a11812b 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/src/nitros_odometry.cpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_odometry_type/src/nitros_odometry.cpp @@ -164,7 +164,7 @@ void rclcpp::TypeAdapter< "[convert_to_custom] Failed to get allocator's handle: " << GxfResultStr(maybe_allocator_handle.error()); RCLCPP_ERROR( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), error_msg.str().c_str()); + rclcpp::get_logger("NitrosOdometry"), error_msg.str().c_str()); throw std::runtime_error(error_msg.str().c_str()); } auto allocator_handle = maybe_allocator_handle.value(); diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_point_cloud_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_point_cloud_type/CMakeLists.txt index ea01da0..cc6599c 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_point_cloud_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_point_cloud_type/CMakeLists.txt @@ -78,4 +78,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_point_cloud_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_point_cloud_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_point_cloud_type/package.xml index 196e4b3..285c5e1 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_point_cloud_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_point_cloud_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_point_cloud_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Point Cloud Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_pose_array_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_pose_array_type/CMakeLists.txt index d9ac911..fa20977 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_pose_array_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_pose_array_type/CMakeLists.txt @@ -75,4 +75,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_pose_array_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_pose_array_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_pose_array_type/package.xml index 6f436f9..96336e6 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_pose_array_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_pose_array_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_pose_array_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Pose Array Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_pose_cov_stamped_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_pose_cov_stamped_type/CMakeLists.txt index e986509..869a4dd 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_pose_cov_stamped_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_pose_cov_stamped_type/CMakeLists.txt @@ -80,4 +80,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_pose_cov_stamped_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_pose_cov_stamped_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_pose_cov_stamped_type/package.xml index 3a231c1..968c159 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_pose_cov_stamped_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_pose_cov_stamped_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_pose_cov_stamped_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Pose With Covariance Stamped Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_std_msg_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_std_msg_type/CMakeLists.txt index 15cec13..902506d 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_std_msg_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_std_msg_type/CMakeLists.txt @@ -76,4 +76,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_int64_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_std_msg_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_std_msg_type/package.xml index 24e2973..b65afa7 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_std_msg_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_std_msg_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_std_msg_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Std Msg Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/CMakeLists.txt index 1b33e6e..d669273 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/CMakeLists.txt @@ -84,4 +84,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_tensor_list_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/include/isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.hpp b/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/include/isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.hpp index 627665a..a17bd50 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/include/isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.hpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/include/isaac_ros_nitros_tensor_list_type/nitros_tensor_list_view.hpp @@ -50,23 +50,34 @@ MARK_PUBLIC_SECTION() class NitrosTensorView { public: - explicit NitrosTensorView(const gxf::Tensor & tensor) - : tensor_{tensor} {} + explicit NitrosTensorView(const gxf::Tensor & tensor, const std::string & name = "") + : tensor_{tensor}, name_{name} {FillStrides();} inline const unsigned char * GetBuffer() const {return tensor_.pointer();} + inline const std::string GetName() const {return name_;} inline uint32_t GetRank() const {return tensor_.rank();} inline uint64_t GetBytesPerElement() const {return tensor_.bytes_per_element();} inline uint64_t GetElementCount() const {return tensor_.element_count();} inline size_t GetTensorSize() const {return tensor_.size();} inline NitrosTensorShape GetShape() const {return NitrosTensorShape(tensor_.shape());} inline PrimitiveType GetElementType() const {return tensor_.element_type();} + inline std::vector GetStrides() const {return strides_;} private: const gxf::Tensor & tensor_{}; + const std::string name_{}; + std::vector strides_{}; + inline void FillStrides() + { + for (size_t i = 0; i < tensor_.shape().rank(); i++) { + strides_.push_back(tensor_.stride(i)); + } + } }; MARK_PUBLIC_SECTION() // Public methods size_t GetTensorCount() const; +const std::vector GetAllTensor() const; const NitrosTensorView GetAnyNamedTensor(std::string tensor_name) const; const NitrosTensorView GetNamedTensor(std::string tensor_name) const; diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/package.xml index dc395ec..9d01746 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_tensor_list_type - 3.1.0 + 3.2.0 Isaac ROS Nitros Tensor List Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/src/nitros_tensor_list_view.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/src/nitros_tensor_list_view.cpp index b1df63d..fe69ac9 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/src/nitros_tensor_list_view.cpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_tensor_list_type/src/nitros_tensor_list_view.cpp @@ -52,6 +52,27 @@ size_t NitrosTensorListView::GetTensorCount() const return tensor_list_.size(); } +const std::vector NitrosTensorListView::GetAllTensor() const +{ + std::vector tensor_view_list; + auto gxf_tensors = msg_entity_->findAll(); + if (!gxf_tensors) { + std::stringstream error_msg; + error_msg << + "[GetTensorCount] failed to get all GXF tensors: " << + GxfResultStr(gxf_tensors.error()); + RCLCPP_ERROR( + rclcpp::get_logger("NitrosTensorListView"), error_msg.str().c_str()); + throw std::runtime_error(error_msg.str().c_str()); + } + + for (auto gxf_tensor : gxf_tensors.value()) { + tensor_view_list.push_back( + NitrosTensorListView::NitrosTensorView(*(gxf_tensor.value()), gxf_tensor.value().name())); + } + return tensor_view_list; +} + const NitrosTensorListView::NitrosTensorView NitrosTensorListView::GetAnyNamedTensor( std::string tensor_name) const { @@ -65,7 +86,7 @@ const NitrosTensorListView::NitrosTensorView NitrosTensorListView::GetAnyNamedTe rclcpp::get_logger("NitrosTensorListView"), error_msg.str().c_str()); throw std::runtime_error(error_msg.str().c_str()); } - return NitrosTensorListView::NitrosTensorView(*(gxf_tensor.value())); + return NitrosTensorListView::NitrosTensorView(*(gxf_tensor.value()), tensor_name); } const NitrosTensorListView::NitrosTensorView NitrosTensorListView::GetNamedTensor( diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/CMakeLists.txt b/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/CMakeLists.txt index 4b517bc..833e808 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/CMakeLists.txt +++ b/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/CMakeLists.txt @@ -80,4 +80,10 @@ if(BUILD_TESTING) add_launch_test(test/isaac_ros_nitros_twist_type_test_pol.py TIMEOUT "15") endif() + +# Embed versioning information into installed files +ament_index_get_resource(ISAAC_ROS_COMMON_CMAKE_PATH isaac_ros_common_cmake_path isaac_ros_common) +include("${ISAAC_ROS_COMMON_CMAKE_PATH}/isaac_ros_common-version-info.cmake") +generate_version_info(${PROJECT_NAME}) + ament_auto_package() diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/package.xml b/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/package.xml index 5530a2a..6e385cd 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/package.xml +++ b/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/package.xml @@ -13,7 +13,7 @@ license agreement from NVIDIA CORPORATION is strictly prohibited. isaac_ros_nitros_twist_type - 3.1.0 + 3.2.0 Isaac ROS NITROS Twist Type Isaac ROS Maintainers diff --git a/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/src/nitros_twist.cpp b/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/src/nitros_twist.cpp index 44854b0..e3fb094 100644 --- a/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/src/nitros_twist.cpp +++ b/isaac_ros_nitros_type/isaac_ros_nitros_twist_type/src/nitros_twist.cpp @@ -110,7 +110,7 @@ void rclcpp::TypeAdapter< "[convert_to_custom] Failed to get allocator's handle: " << GxfResultStr(maybe_allocator_handle.error()); RCLCPP_ERROR( - rclcpp::get_logger("NitrosAprilTagDetectionArray"), error_msg.str().c_str()); + rclcpp::get_logger("NitrosTwist"), error_msg.str().c_str()); throw std::runtime_error(error_msg.str().c_str()); } auto allocator_handle = maybe_allocator_handle.value(); diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/__init__.py b/isaac_ros_pynitros/isaac_ros_pynitros/__init__.py new file mode 100644 index 0000000..34d9bfe --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/__init__.py @@ -0,0 +1,16 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/examples/__init__.py b/isaac_ros_pynitros/isaac_ros_pynitros/examples/__init__.py new file mode 100644 index 0000000..34d9bfe --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/examples/__init__.py @@ -0,0 +1,16 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_dnn_image_encoder_node.py b/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_dnn_image_encoder_node.py new file mode 100644 index 0000000..8e6549a --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_dnn_image_encoder_node.py @@ -0,0 +1,126 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeImage, NitrosBridgeTensorList +from isaac_ros_pynitros.isaac_ros_pynitros_publisher import PyNitrosPublisher +from isaac_ros_pynitros.isaac_ros_pynitros_subscriber import PyNitrosSubscriber +from isaac_ros_pynitros.pynitros_type_builders.pynitros_tensor_list_builder \ + import PyNitrosTensorListBuilder + + +import rclpy +from rclpy.node import Node +from std_msgs.msg import Header + +import torch +import torchvision.transforms as T + + +class PyNITROSDNNImageEncoderNode(Node): + """A PyNITROS node listens to image message and publish it again.""" + + def __init__(self, name='pynitros_image_forward_node'): + super().__init__(name) + self.declare_parameter('enable_ros_subscribe', False) + self.declare_parameter('enable_ros_publish', False) + self.declare_parameter('network_image_width', 960) + self.declare_parameter('network_image_height', 544) + self.declare_parameter('image_mean', [0.5, 0.5, 0.5]) + self.declare_parameter('image_std', [0.5, 0.5, 0.5]) + + self.enable_ros_subscribe = \ + self.get_parameter('enable_ros_subscribe').get_parameter_value().bool_value + self.enable_ros_publish = \ + self.get_parameter('enable_ros_publish').get_parameter_value().bool_value + + self.network_image_width = \ + self.get_parameter('network_image_width').get_parameter_value().integer_value + self.network_image_height = \ + self.get_parameter('network_image_height').get_parameter_value().integer_value + + self.image_mean = \ + self.get_parameter('image_mean').get_parameter_value().double_array_value + self.image_std = \ + self.get_parameter('image_std').get_parameter_value().double_array_value + + self.pynitros_subscriber = PyNitrosSubscriber( + self, NitrosBridgeImage, 'pynitros_input_msg', + enable_ros_subscribe=self.enable_ros_subscribe) + self.pynitros_subscriber.create_subscription(self.listener_callback) + + self.pynitros_publisher = PyNitrosPublisher( + self, NitrosBridgeTensorList, 'pynitros_output_msg', 'pynitros_output_msg_ros') + + self.pynitros_tensor_list_builder = PyNitrosTensorListBuilder( + num_buffer=40, timeout=5) + + def listener_callback(self, pynitros_image_view): + header = Header() + header.frame_id = pynitros_image_view.get_frame_id() + header.stamp.sec = pynitros_image_view.get_timestamp_seconds() + header.stamp.nanosec = pynitros_image_view.get_timestamp_nanoseconds() + + tensor_image = torch.as_tensor(pynitros_image_view, device='cuda', dtype=torch.uint8) + reshaped_image = tensor_image.reshape(pynitros_image_view.get_height(), + pynitros_image_view.get_width(), + 3) + + # Switch from interleaved to planar + planar_tensor = reshaped_image.permute(2, 0, 1) + + transforms = T.Compose([ + T.Resize((self.network_image_height, self.network_image_width)), + T.ConvertImageDtype(torch.float), + T.Normalize(self.image_mean, self.image_std) + ] + ) + norm_tensor = transforms(planar_tensor) + out_tensor = norm_tensor.contiguous() + + tensor_list = [] + pynitros_tensor = self.pynitros_tensor_list_builder.build_tensor( + out_tensor.data_ptr(), + 'input_tensor', + out_tensor.shape, + 9) + tensor_list.append(pynitros_tensor) + + # # Build TensorList + pynitros_tensor_list = self.pynitros_tensor_list_builder.build(tensor_list, + header, + 0, + self.enable_ros_publish) + + self.pynitros_publisher.publish(pynitros_tensor_list) + + +def main(args=None): + try: + rclpy.init(args=args) + node = PyNITROSDNNImageEncoderNode() + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + # only shut down if context is active + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_image_forward_node.py b/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_image_forward_node.py new file mode 100644 index 0000000..1c6640e --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_image_forward_node.py @@ -0,0 +1,87 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeImage +from isaac_ros_pynitros.isaac_ros_pynitros_publisher import PyNitrosPublisher +from isaac_ros_pynitros.isaac_ros_pynitros_subscriber import PyNitrosSubscriber +from isaac_ros_pynitros.pynitros_type_builders.pynitros_image_builder import PyNitrosImageBuilder + +import rclpy +from rclpy.node import Node +from std_msgs.msg import Header + + +class PyNITROSImageForwardNode(Node): + """A PyNITROS node listens to image message and publish it again.""" + + def __init__(self, name='pynitros_image_forward_node'): + super().__init__(name) + self.declare_parameter('enable_ros_subscribe', False) + self.declare_parameter('enable_ros_publish', False) + + self.enable_ros_subscribe = \ + self.get_parameter('enable_ros_subscribe').get_parameter_value().bool_value + self.enable_ros_publish = \ + self.get_parameter('enable_ros_publish').get_parameter_value().bool_value + + self.pynitros_subscriber = PyNitrosSubscriber( + self, NitrosBridgeImage, 'pynitros_input_msg', + enable_ros_subscribe=self.enable_ros_subscribe) + + self.pynitros_subscriber.create_subscription(self.listener_callback) + + self.pynitros_publisher = PyNitrosPublisher( + self, NitrosBridgeImage, 'pynitros_output_msg', 'pynitros_output_msg_ros') + + self.pynitros_image_builder = PyNitrosImageBuilder( + num_buffer=40, timeout=5) + + def listener_callback(self, pynitros_image_view): + # Build Image + header = Header() + header.frame_id = pynitros_image_view.get_frame_id() + header.stamp.sec = pynitros_image_view.get_timestamp_seconds() + header.stamp.nanosec = pynitros_image_view.get_timestamp_nanoseconds() + built_image = self.pynitros_image_builder.build(pynitros_image_view.get_buffer(), + pynitros_image_view.get_height(), + pynitros_image_view.get_width(), + pynitros_image_view.get_stride(), + pynitros_image_view.get_encoding(), + header, + 0, + self.enable_ros_publish) + + # Publish + self.pynitros_publisher.publish(built_image) + + +def main(args=None): + try: + rclpy.init(args=args) + node = PyNITROSImageForwardNode() + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + # only shut down if context is active + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_message_filter_sync_node.py b/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_message_filter_sync_node.py new file mode 100644 index 0000000..1cee486 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_message_filter_sync_node.py @@ -0,0 +1,101 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeImage +from isaac_ros_pynitros.isaac_ros_pynitros_message_filter import PyNitrosMessageFilter +from isaac_ros_pynitros.isaac_ros_pynitros_publisher import PyNitrosPublisher +from isaac_ros_pynitros.isaac_ros_pynitros_subscriber import PyNitrosSubscriber +from isaac_ros_pynitros.pynitros_type_builders.pynitros_image_builder import PyNitrosImageBuilder +from message_filters import Subscriber, TimeSynchronizer + +import rclpy +from rclpy.node import Node +from sensor_msgs.msg import CameraInfo +from std_msgs.msg import Header + + +class PyNITROSMessageFilterSyncNode(Node): + """A PyNITROS node listen to synced image and camera info.""" + + def __init__(self, name='pynitros_message_filter_sync_node'): + super().__init__(name) + self.declare_parameter('enable_ros_subscribe', False) + self.declare_parameter('enable_ros_publish', False) + + self.enable_ros_subscribe = \ + self.get_parameter('enable_ros_subscribe').get_parameter_value().bool_value + self.enable_ros_publish = \ + self.get_parameter('enable_ros_publish').get_parameter_value().bool_value + + self.pynitros_subscriber = PyNitrosSubscriber( + self, NitrosBridgeImage, 'image', + enable_ros_subscribe=self.enable_ros_subscribe) + self.camera_info_sub = Subscriber(self, CameraInfo, 'camera_info') + + self.message_filter = PyNitrosMessageFilter(self, + [self.pynitros_subscriber, + self.camera_info_sub], + TimeSynchronizer, + self.listener_callback, + queue_size=1) + + self.pynitros_publisher = PyNitrosPublisher( + self, NitrosBridgeImage, 'synced_output', 'synced_output_ros') + + self.pynitros_image_builder = PyNitrosImageBuilder( + num_buffer=40, timeout=5) + + def listener_callback(self, pynitros_image_view, camera_info): + header = Header() + header.frame_id = pynitros_image_view.get_frame_id() + header.stamp.sec = pynitros_image_view.get_timestamp_seconds() + header.stamp.nanosec = pynitros_image_view.get_timestamp_nanoseconds() + # Check if image and camera info are in sync + if (header.stamp == camera_info.header.stamp): + self.get_logger().info('Image and Camera Info are in sync') + else: + self.get_logger().error('Image and Camera Info are not in sync') + # Build Image + built_image = self.pynitros_image_builder.build(pynitros_image_view.get_buffer(), + pynitros_image_view.get_height(), + pynitros_image_view.get_width(), + pynitros_image_view.get_stride(), + pynitros_image_view.get_encoding(), + header, + 0, + self.enable_ros_publish) + + # Publish + self.pynitros_publisher.publish(built_image) + + +def main(args=None): + try: + rclpy.init(args=args) + node = PyNITROSMessageFilterSyncNode() + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + # only shut down if context is active + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_tensor_list_forward_node.py b/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_tensor_list_forward_node.py new file mode 100644 index 0000000..df53675 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/examples/pynitros_tensor_list_forward_node.py @@ -0,0 +1,94 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeTensorList +from isaac_ros_pynitros.isaac_ros_pynitros_publisher import PyNitrosPublisher +from isaac_ros_pynitros.isaac_ros_pynitros_subscriber import PyNitrosSubscriber +from isaac_ros_pynitros.pynitros_type_builders.pynitros_tensor_list_builder \ + import PyNitrosTensorListBuilder + +import rclpy +from rclpy.node import Node +from std_msgs.msg import Header + + +class PyNITROSTensorListForwardNode(Node): + """A PyNITROS node listens to tensor list message and publish it again.""" + + def __init__(self, name='pynitros_tensor_list_forward_node'): + super().__init__(name) + self.declare_parameter('enable_ros_subscribe', False) + self.declare_parameter('enable_ros_publish', False) + + self.enable_ros_subscribe = \ + self.get_parameter('enable_ros_subscribe').get_parameter_value().bool_value + self.enable_ros_publish = \ + self.get_parameter('enable_ros_publish').get_parameter_value().bool_value + + self.pynitros_subscriber = PyNitrosSubscriber( + self, NitrosBridgeTensorList, 'pynitros_input_msg', + enable_ros_subscribe=self.enable_ros_subscribe) + self.pynitros_subscriber.create_subscription(self.listener_callback) + + self.pynitros_publisher = PyNitrosPublisher( + self, NitrosBridgeTensorList, 'pynitros_output_msg', 'pynitros_output_msg_ros') + + self.pynitros_tensor_list_builder = PyNitrosTensorListBuilder(num_buffer=20) + + def listener_callback(self, pynitros_tensor_list_view): + tensor_list_view = pynitros_tensor_list_view.get_all_tensors() + tensor_list = [] + + # Build Tensors + for tensor_view in tensor_list_view: + tensor = self.pynitros_tensor_list_builder.build_tensor( + tensor_view.get_buffer(), + tensor_view.get_name(), + tensor_view.get_shape(), + tensor_view.get_element_type()) + tensor_list.append(tensor) + + # Build TensorList + header = Header() + header.frame_id = pynitros_tensor_list_view.get_frame_id() + header.stamp.sec = pynitros_tensor_list_view.get_timestamp_seconds() + header.stamp.nanosec = pynitros_tensor_list_view.get_timestamp_nanoseconds() + pynitros_tensors = self.pynitros_tensor_list_builder.build(tensor_list, + header, + 0, + self.enable_ros_publish) + + # Publish + self.pynitros_publisher.publish(pynitros_tensors) + + +def main(args=None): + try: + rclpy.init(args=args) + node = PyNITROSTensorListForwardNode() + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + # only shut down if context is active + if rclpy.ok(): + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_message_filter.py b/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_message_filter.py new file mode 100644 index 0000000..448474f --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_message_filter.py @@ -0,0 +1,153 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from cuda import cuda, cudart +from isaac_ros_pynitros.isaac_ros_pynitros_subscriber import PyNitrosSubscriber +from isaac_ros_pynitros.pynitros_type_views.pynitros_type_view_base import PyNitrosTypeViewBase + +from message_filters import ApproximateTimeSynchronizer, Subscriber, TimeSynchronizer + + +class PyNitrosMessageFilter(): + """The PyNITROS Message filter synchronize to multiple subscribed topics.""" + + def __init__(self, node, subscribers, synchronizer, callback, queue_size=10, slop=0.1): + """ + Initialize PyNitrosSubscriber. + + Parameters + ---------- + node : rclpy.node.Node + ROS2 node creates this message filter. + subscribers : list of PyNitrosSubscriber or rclpy.subscription.Subscriber + List of subscribers to synchronize. + synchronizer : TimeSynchronizer or ApproximateTimeSynchronizer + Synchronizer type to use. + callback : function + User-defined callback function to process synchronized messages. + queue_size : int + Queue size of the synchronizer. + slop : float + Slop of the ApproximateTimeSynchronizer. + + """ + rclpy_subs = [] + self.subscribers = subscribers + self.node = node + for sub in subscribers: + if (isinstance(sub, PyNitrosSubscriber)): + if (sub.enable_ros_subscribe): + raw_msg_type = PyNitrosSubscriber.BRIDGE_TYPE_TO_RAW_TYPE[sub.message_type] + rclpy_subs.append(Subscriber(self.node, raw_msg_type, sub.sub_topic_name)) + else: + rclpy_subs.append(Subscriber(self.node, sub.message_type, sub.sub_topic_name)) + else: + rclpy_subs.append(sub) + + self._cuda_memblock_fd_to_ptr = {} + self._event_handle_to_event = {} + self._cuda_memblock_handle = [] + self.input_callback = callback + + if (synchronizer is TimeSynchronizer): + rclpy_synchronizer = TimeSynchronizer(rclpy_subs, queue_size) + elif (synchronizer is ApproximateTimeSynchronizer): + rclpy_synchronizer = ApproximateTimeSynchronizer(rclpy_subs, queue_size, slop) + else: + raise ValueError('Unsupported synchronizer type') + rclpy_synchronizer.registerCallback(self.filter_callback) + + def filter_callback(self, *args): + msg_views = [] + for index in range(len(args)): + cur_message = args[index] + cur_subscriber = self.subscribers[index] + + if (isinstance(cur_subscriber, PyNitrosSubscriber)): + # Create PyNITROS view from bridge msg + bridge_message_type = cur_subscriber.message_type + if (cur_subscriber.enable_ros_subscribe): + pynitros_view = PyNitrosSubscriber.BRIDGE_TYPE_TO_PYNITROS_VIEW[ + bridge_message_type](cur_message) + else: + if cur_message.cuda_event_handle: + event_handle_tuple = tuple(cur_message.cuda_event_handle) + if event_handle_tuple not in self._event_handle_to_event: + # Save event handle to local map + event_handle = cudart.cudaIpcEventHandle_t() + event_handle.reserved = cur_message.cuda_event_handle + + err, cuda_event = cudart.cudaIpcOpenEventHandle(event_handle) + self._event_handle_to_event[event_handle_tuple] = cuda_event + self.ASSERT_CUDA_SUCCESS(err) + else: + cuda_event = self._event_handle_to_event[event_handle_tuple] + # Synchronize to upstream Event + err, = cudart.cudaEventSynchronize(cuda_event) + self.ASSERT_CUDA_SUCCESS(err) + + # Create PyNITROS view + sender_pid, memblock_fd = \ + PyNitrosSubscriber.BRIDGE_TYPE_TO_PYNITROS_VIEW[ + bridge_message_type].get_pid_fd(cur_message) + if (sender_pid, memblock_fd) not in self._cuda_memblock_fd_to_ptr: + try: + pynitros_view = PyNitrosSubscriber.BRIDGE_TYPE_TO_PYNITROS_VIEW[ + bridge_message_type](cur_message) + except ValueError: + self.node.get_logger().warn( + 'Failed to create PyNITROS view from bridge msg') + return + gpu_ptr = pynitros_view.get_buffer() + gpu_handle = pynitros_view.get_handle() + self._cuda_memblock_fd_to_ptr[(sender_pid, memblock_fd)] = gpu_ptr + self._cuda_memblock_handle.append(gpu_handle) + else: + # Found gpu_ptr from map and create PyNITROS view + gpu_ptr = self._cuda_memblock_fd_to_ptr[(sender_pid, memblock_fd)] + try: + pynitros_view = PyNitrosSubscriber.BRIDGE_TYPE_TO_PYNITROS_VIEW[ + bridge_message_type](cur_message, gpu_ptr) + except ValueError: + self.node.get_logger().warn( + 'Failed to create PyNITROS view from bridge msg') + return + msg_views.append(pynitros_view) + else: + # Passthrough raw message + msg_views.append(cur_message) + + self.input_callback(*msg_views) + for pynitros_view in msg_views: + if isinstance(pynitros_view, PyNitrosTypeViewBase): + pynitros_view.postprocess() + + def ASSERT_CUDA_SUCCESS(self, err): + if isinstance(err, cuda.CUresult): + if err != cuda.CUresult.CUDA_SUCCESS: + raise RuntimeError( + f'[Cuda Error: {err}], {cuda.cuGetErrorString(err)}') + elif isinstance(err, cudart.cudaError_t): + if (err != 0): + raise RuntimeError(f'CudaRT Error: {err}') + else: + raise RuntimeError('Unknown error type: {}'.format(err)) + + def __del__(self): + for gpu_handle in self._cuda_memblock_handle: + err, = cuda.cuMemRelease(gpu_handle) + self.ASSERT_CUDA_SUCCESS(err) diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_publisher.py b/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_publisher.py new file mode 100644 index 0000000..85ba3e1 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_publisher.py @@ -0,0 +1,70 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeImage +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeTensorList +from isaac_ros_tensor_list_interfaces.msg import TensorList +from sensor_msgs.msg import Image + + +class PyNitrosPublisher(): + """Publish built messages from PyNITROS Builder.""" + + def __init__(self, node, message_type, pub_topic, pub_topic_raw): + """ + Initialize PyNitrosPublisher. + + Parameters + ---------- + node : rclpy.node.Node + ROS2 node creates this publisher. + message_type : PyNitros message type + NITROS Bridge message type to publish. + pub_topic : str + ROS2 topic name of NITROS bridge message. + pub_topic_raw : str + ROS2 topic name of raw ROS message. + + """ + self.node = node + self.msg_map = {NitrosBridgeImage: Image, + NitrosBridgeTensorList: TensorList} + + # Regular PyNITROS Pub + self.message_type = message_type + self.pub_topic = pub_topic + + # If enable_ros_publish == True + self.pub_topic_raw = pub_topic_raw + + # Setup both publishers + self.publisher_ = self.node.create_publisher( + self.message_type, self.pub_topic, 10) + self.publisher_raw_ = self.node.create_publisher( + self.msg_map[self.message_type], self.pub_topic_raw, 10) + + def publish(self, pynitros_built_msg): + """Publish PyNITROS built messages.""" + bridge_msg = pynitros_built_msg[0] + msg_raw = pynitros_built_msg[1] + + # Publish PyNITROS bridge msg + self.publisher_.publish(bridge_msg) + + # Publish raw image if enable_ros_publish is true + if msg_raw: + self.publisher_raw_.publish(msg_raw) diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_subscriber.py b/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_subscriber.py new file mode 100644 index 0000000..c66f4cb --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/isaac_ros_pynitros_subscriber.py @@ -0,0 +1,160 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from cuda import cuda, cudart +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeImage, NitrosBridgeTensorList +from isaac_ros_pynitros.pynitros_type_views.pynitros_image_view import PyNitrosImageView +from isaac_ros_pynitros.pynitros_type_views.pynitros_tensor_list_view import PyNitrosTensorListView +from isaac_ros_tensor_list_interfaces.msg import TensorList +from sensor_msgs.msg import Image + + +class PyNitrosSubscriber(): + """ + The PyNITROS Subscriber listens to PyNITROS Publisher or the NITROS Bridge node. + + When a message arrives, an internal callback is triggered to convert the GPU data handle + back into a valid GPU pointer. The internal callback will wrap the incoming message + into a PyNITROS View and invoke the user-defined callback. + If enable_ros_subscribe is set to True, the subscriber will exclusively subscribe to + ROS messages. In this case, the internal callback will perform CPU->GPU data transfer + to wrap the message into a PyNITROS View. + """ + + BRIDGE_TYPE_TO_PYNITROS_VIEW = { + NitrosBridgeImage: PyNitrosImageView, + NitrosBridgeTensorList: PyNitrosTensorListView + } + + BRIDGE_TYPE_TO_RAW_TYPE = { + NitrosBridgeImage: Image, + NitrosBridgeTensorList: TensorList + } + + def __init__( + self, node, message_type, sub_topic_name, enable_ros_subscribe=True): + """ + Initialize PyNitrosSubscriber. + + Parameters + ---------- + node : rclpy.node.Node + ROS2 node creates this subscriber. + message_type : PyNitros message type + NITROS Bridge message type to subscribe. + sub_topic_name : str + Topic name of the subscribed message. + enable_ros_subscribe : bool + If True, the subscriber will exclusively subscribe to ROS messages. + + """ + self.node = node + self.message_type = message_type + self.sub_topic_name = sub_topic_name + self.enable_ros_subscribe = enable_ros_subscribe + + self.event = None + self._cuda_memblock_fd_to_ptr = {} + self._cuda_memblock_handle = [] + + # Initialize the CUDA driver API + err, = cuda.cuInit(0) + self.ASSERT_CUDA_SUCCESS(err) + + def create_subscription(self, input_callback): + namespaced_sub_topic_name = '' + if (self.node.get_namespace() == '/'): + namespaced_sub_topic_name = self.sub_topic_name + else: + namespaced_sub_topic_name = '/'.join( + [self.node.get_namespace(), self.sub_topic_name.strip('/')]) + + if self.enable_ros_subscribe: + self.subscription = self.node.create_subscription( + self.BRIDGE_TYPE_TO_RAW_TYPE[self.message_type], + namespaced_sub_topic_name, + self.listener_callback_ros, 10) + else: + self.subscription = self.node.create_subscription( + self.message_type, + namespaced_sub_topic_name, + self.listener_callback, 10) + + self.input_callback = input_callback + + def listener_callback_ros(self, raw_msg): + pynitros_view = self.BRIDGE_TYPE_TO_PYNITROS_VIEW[self.message_type](raw_msg) + self.input_callback(pynitros_view) + pynitros_view.postprocess() + + def listener_callback(self, nitros_bridge_msg): + if nitros_bridge_msg.cuda_event_handle and not self.event: + self.event_handle = cudart.cudaIpcEventHandle_t() + self.event_handle.reserved = nitros_bridge_msg.cuda_event_handle + + err, self.event = cudart.cudaIpcOpenEventHandle(self.event_handle) + self.ASSERT_CUDA_SUCCESS(err) + + # Synchronize to upstream Event + if self.event: + err, = cudart.cudaEventSynchronize(self.event) + self.ASSERT_CUDA_SUCCESS(err) + + sender_pid, memblock_fd = \ + self.BRIDGE_TYPE_TO_PYNITROS_VIEW[self.message_type].get_pid_fd(nitros_bridge_msg) + if (sender_pid, memblock_fd) not in self._cuda_memblock_fd_to_ptr: + # Get PyNITROS view from bridge message + try: + pynitros_view = self.BRIDGE_TYPE_TO_PYNITROS_VIEW[ + self.message_type](nitros_bridge_msg) + except ValueError: + self.node.get_logger().warn('Failed to create PyNITROS view from bridge msg') + return + gpu_ptr = pynitros_view.get_buffer() + gpu_handle = pynitros_view.get_handle() + self._cuda_memblock_fd_to_ptr[(sender_pid, memblock_fd)] = gpu_ptr + self._cuda_memblock_handle.append(gpu_handle) + else: + gpu_ptr = self._cuda_memblock_fd_to_ptr[(sender_pid, memblock_fd)] + try: + pynitros_view = self.BRIDGE_TYPE_TO_PYNITROS_VIEW[ + self.message_type](nitros_bridge_msg, gpu_ptr) + except ValueError: + self.node.get_logger().warn('Failed to create PyNITROS view from bridge msg') + return + + # Invoke user-defined callback + self.input_callback(pynitros_view) + + # Decrease Refcount + pynitros_view.postprocess() + + def ASSERT_CUDA_SUCCESS(self, err): + if isinstance(err, cuda.CUresult): + if err != cuda.CUresult.CUDA_SUCCESS: + raise RuntimeError( + f'[Cuda Error: {err}], {cuda.cuGetErrorString(err)}') + elif isinstance(err, cudart.cudaError_t): + if (err != 0): + raise RuntimeError(f'CudaRT Error: {err}') + else: + raise RuntimeError('Unknown error type: {}'.format(err)) + + def __del__(self): + for gpu_handle in self._cuda_memblock_handle: + err, = cuda.cuMemRelease(gpu_handle) + self.ASSERT_CUDA_SUCCESS(err) diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/__init__.py b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/__init__.py new file mode 100644 index 0000000..34d9bfe --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/__init__.py @@ -0,0 +1,16 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_image_builder.py b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_image_builder.py new file mode 100644 index 0000000..55b0ba9 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_image_builder.py @@ -0,0 +1,150 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import uuid + +from cuda import cuda, cudart +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeImage +import numpy as np +from sensor_msgs.msg import Image + +from .pynitros_type_builder_base import PyNitrosTypeBuilder + + +class PyNitrosImageBuilder(PyNitrosTypeBuilder): + """Class to build NitrosBridgeImage messages.""" + + def __init__(self, num_buffer=10, timeout=1): + """ + Initialize the PyNitrosTensorListBuilder. + + Parameters + ---------- + num_buffer: int + Number of buffers to create + timeout: int + Timeout in ms for recycling buffers with refcount 0 + + """ + super().__init__(num_buffer, timeout) + + def build(self, image_data, image_height, image_width, image_step, + image_encoding, image_header, + device_id, enable_ros_publish, event=None): + """ + Build NITROS Image message. + + Parameters + ---------- + image_data: cuda.CUdeviceptr + Device pointer to image data + image_height: int + Height of the image + image_width: int + Width of the image + image_step: int + Step of the image in bytes + image_encoding: str + Encoding of the image + image_header: Header + Header for the image + device_id: int + Device id the tensors are residing on + enable_ros_publish: bool + Enable ROS publishing + event: cudaEvent + Event with unfinished CUDA operations to synchronize on + + Returns + ------- + tuple: (NitrosBridgeImage, Image) + NitrosBridgeImage: NitrosBridgeImage message + Image: Image message, None if enable_ros_publish is False + + """ + if self._first_frame: + buffer_size = image_step * image_height + super().create_memblock_pool(buffer_size) + self._first_frame = False + + # Synchronize to user Event + if event: + err, = cudart.cudaEventSynchronize(self.event) + super().ASSERT_CUDA_SUCCESS(err) + + # Create Nitros Bridge Image + nitros_bridge_image_msg = NitrosBridgeImage() + nitros_bridge_image_msg.header = image_header + nitros_bridge_image_msg.height = image_height + nitros_bridge_image_msg.width = image_width + nitros_bridge_image_msg.encoding = image_encoding + nitros_bridge_image_msg.is_bigendian = 0 + nitros_bridge_image_msg.step = image_step + + memblock_fd, new_memblock_uuid, image_event_handle = self._setup_image_memblock( + image_data) + nitros_bridge_image_msg.data = [os.getpid(), memblock_fd] + nitros_bridge_image_msg.cuda_event_handle = image_event_handle.reserved + nitros_bridge_image_msg.device_id = device_id + nitros_bridge_image_msg.uid = str(new_memblock_uuid) + + # Setup Shareable Memory To Transport Image + image_msg_raw = None + + if enable_ros_publish: + image_msg_raw = Image() + image_size = image_step * image_height + # Set image properties + image_msg_raw.header = image_header + image_msg_raw.height = image_height + image_msg_raw.width = image_width + image_msg_raw.encoding = image_encoding + image_msg_raw.is_bigendian = 0 + image_msg_raw.step = image_step + # Assign to the private data field to reduce overhead of msg data assignment + image_msg_raw._data = np.zeros((image_height, image_width, 3), dtype=np.uint8) + err, = cudart.cudaMemcpy(image_msg_raw.data, image_data, image_size, + cudart.cudaMemcpyKind.cudaMemcpyDeviceToHost) + super().ASSERT_CUDA_SUCCESS(err) + + # Return Nitros Bridge Image + return (nitros_bridge_image_msg, image_msg_raw) + + def _setup_image_memblock(self, image_tensor_ptr): + """Set up shareable CUDA memblocks for images.""" + cuda_memblock_fd, cuda_memblock_uuid, cuda_memblock_refcount = super().get_free_memblock() + cuda_memblock_virtual_ptr = self._cuda_memblock_fd_to_ptr[cuda_memblock_fd] + cuda_event, cuda_event_handle = self._cuda_memblock_event[cuda_memblock_fd] + + # Update memblock uuid header + new_cuda_memblock_uuid = uuid.uuid4() + cuda_memblock_cpu_mem = self._cuda_memblock_to_cpu_mem[cuda_memblock_fd] + + cuda_memblock_cpu_mem.lock.acquire() + cuda_memblock_cpu_mem.put_value( + (cuda_memblock_refcount, new_cuda_memblock_uuid)) + cuda_memblock_cpu_mem.lock.release() + + err, = cuda.cuMemcpyDtoDAsync(cuda.CUdeviceptr( + cuda_memblock_virtual_ptr), image_tensor_ptr, self.buffer_size, self._stream) + super().ASSERT_CUDA_SUCCESS(err) + + err, = cudart.cudaEventRecord(cuda_event, self._stream) + super().ASSERT_CUDA_SUCCESS(err) + + return (cuda_memblock_fd, new_cuda_memblock_uuid, cuda_event_handle) diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_tensor_list_builder.py b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_tensor_list_builder.py new file mode 100644 index 0000000..5835465 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_tensor_list_builder.py @@ -0,0 +1,202 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import math +import os +import uuid + +from cuda import cuda, cudart + +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeTensorList +from isaac_ros_pynitros.utils.tensor_data_type import TensorDataTypeUtils +from isaac_ros_tensor_list_interfaces.msg import Tensor, TensorList, TensorShape +import numpy as np + +from .pynitros_type_builder_base import PyNitrosTypeBuilder + + +class PyNitrosTensorListBuilder(PyNitrosTypeBuilder): + """Class to build NitrosBridgeTensorList messages.""" + + def __init__(self, num_buffer=10, timeout=1): + """ + Initialize the PyNitrosTensorListBuilder. + + Parameters + ---------- + buffer_size: int + Size of each buffer in bytes + num_buffer: int + Number of buffers to create + timeout: int + Timeout in ms for recycling buffers with refcount 0 + + """ + super().__init__(num_buffer, timeout) + + def build(self, built_tensors, tensors_header, + device_id, enable_ros_publish, event=None): + """ + Build NitrosBridgeTensorList message. + + Parameters + ---------- + built_tensors: list + List of built tensors + tensors_header: Header + Header for the tensor list + device_id: int + device id the tensors are residing on + enable_ros_publish: bool + enable ROS publishing + event: cudaEvent + event with unfinished CUDA operations to synchronize on + + Returns + ------- + tuple: (NitrosBridgeTensorList, TensorList) + NitrosBridgeTensorList: NitrosBridgeTensorList message + TensorList: TensorList message, None if enable_ros_publish is False + + """ + nitros_bridge_tensor_list_msg = NitrosBridgeTensorList() + nitros_bridge_tensor_list_msg.header = tensors_header + nitros_bridge_tensor_list_msg.tensors = [] + + tensor_ptrs_sizes = [] + tensor_list_msg_raw = None + if enable_ros_publish: + tensor_list_msg_raw = TensorList() + tensor_list_msg_raw.header = tensors_header + tensor_list_msg_raw.tensors = [] + + if self._first_frame: + total_tensor_size = 0 + for tensor in built_tensors: + total_tensor_size += tensor.strides[0] * tensor.shape.dims[0] + super().create_memblock_pool(total_tensor_size) + self._first_frame = False + + # Synchronize to upstream Event + if event: + err, = cudart.cudaEventSynchronize(self.event) + super().ASSERT_CUDA_SUCCESS(err) + + # Set the data field + index = 0 + for tensor in built_tensors: + nitros_bridge_tensor_list_msg.tensors.append(tensor) + tensor_size = tensor.strides[0] * tensor.shape.dims[0] + + tensor_gpu_ptr = int.from_bytes(tensor.data, byteorder='big') + tensor_ptrs_sizes.append((tensor_gpu_ptr, tensor_size)) + if enable_ros_publish: + raw_tensor = Tensor() + raw_tensor.name = tensor.name + raw_tensor.shape = tensor.shape + raw_tensor.data_type = tensor.data_type + raw_tensor.strides = tensor.strides + # Assign to the private data field to reduce overhead of msg data assignment + raw_tensor._data = np.empty(tensor_size, dtype=np.uint8).tobytes() + err, = cudart.cudaMemcpy(raw_tensor.data, tensor_gpu_ptr, tensor_size, + cudart.cudaMemcpyKind.cudaMemcpyDeviceToHost) + super().ASSERT_CUDA_SUCCESS(err) + tensor_list_msg_raw.tensors.append(raw_tensor) + index += 1 + + memblock_fd, new_memblock_uuid, tensor_event_handle = self._setup_tensors_memblock( + tensor_ptrs_sizes) + nitros_bridge_tensor_list_msg.pid = os.getpid() + nitros_bridge_tensor_list_msg.fd = memblock_fd + nitros_bridge_tensor_list_msg.cuda_event_handle = tensor_event_handle.reserved + nitros_bridge_tensor_list_msg.device_id = device_id + nitros_bridge_tensor_list_msg.uid = str(new_memblock_uuid) + + return (nitros_bridge_tensor_list_msg, tensor_list_msg_raw) + + def build_tensor(self, tensor_data, tensor_name, tensor_shape, tensor_data_type): + """ + Build a NitrosBridgeTensor message. + + Parameters + ---------- + tensor_data: device ptr + Device pointer to the tensor data + tensor_name: str + Name of the tensor + tensor_shape: list + Shape of the tensor + tensor_data_type: int + Data type of the tensor + + Returns + ------- + tensor: NitrosBridgeTensor message + + """ + # Build Tensor Messages + tensor_shape_msg = TensorShape() + tensor_shape_msg.rank = len(tensor_shape) + tensor_shape_msg.dims = tensor_shape + + nitros_bridge_tensor_msg = Tensor() + nitros_bridge_tensor_msg.name = tensor_name + nitros_bridge_tensor_msg.shape = tensor_shape_msg + nitros_bridge_tensor_msg.data_type = tensor_data_type + + strides = [] + element_size = TensorDataTypeUtils.get_size_in_bytes(tensor_data_type) + for i in range(len(tensor_shape)): + if i == (len(tensor_shape)-1): + strides.append(element_size) + else: + strides.append(math.prod(tensor_shape[i+1:])*element_size) + + nitros_bridge_tensor_msg.strides = strides + nitros_bridge_tensor_msg.data = tensor_data.to_bytes(8, byteorder='big') + + return nitros_bridge_tensor_msg + + def _setup_tensors_memblock(self, tensor_ptrs_sizes): + """Set up sharable device memory blocks.""" + cuda_memblock_fd, cuda_memblock_uuid, cuda_memblock_refcount = super().get_free_memblock() + cuda_memblock_virtual_ptr = self._cuda_memblock_fd_to_ptr[cuda_memblock_fd] + cuda_event, cuda_event_handle = self._cuda_memblock_event[cuda_memblock_fd] + + # Update memblock uuid header + new_cuda_memblock_uuid = uuid.uuid4() + cuda_memblock_cpu_mem = self._cuda_memblock_to_cpu_mem[cuda_memblock_fd] + + cuda_memblock_cpu_mem.lock.acquire() + cuda_memblock_cpu_mem.put_value( + (cuda_memblock_refcount, new_cuda_memblock_uuid)) + cuda_memblock_cpu_mem.lock.release() + + # Copy tensors back-to-back into cuda mem space + offset = 0 + for cur_tensor_ptr, cur_tensor_size in tensor_ptrs_sizes: + cur_gpu_ptr = cuda.CUdeviceptr(cuda_memblock_virtual_ptr + offset) + err, = cuda.cuMemcpyDtoDAsync( + cur_gpu_ptr, cur_tensor_ptr, cur_tensor_size, self._stream) + super().ASSERT_CUDA_SUCCESS(err) + + offset += cur_tensor_size + + err, = cudart.cudaEventRecord(cuda_event, self._stream) + super().ASSERT_CUDA_SUCCESS(err) + + return (cuda_memblock_fd, new_cuda_memblock_uuid, cuda_event_handle) diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_type_builder_base.py b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_type_builder_base.py new file mode 100644 index 0000000..de47a9a --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_builders/pynitros_type_builder_base.py @@ -0,0 +1,238 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + + +import math +import os +import time +import uuid + +from cuda import cuda, cudart +from isaac_ros_pynitros.utils.cpu_shared_mem import CPUSharedMem +import rclpy + + +class PyNitrosTypeBuilder(): + """ + Base class of PyNITROS message builders. + + The builder creates a pool of sharable GPU memory buffers during initialization. + to hold the GPU data of the message. The inherited class should implement + the build method to build different type of NITROS Bridge messages. + """ + + def __init__(self, num_buffer=10, timeout=1): + """ + Initialize the PyNitrosTypeBuilder. + + Parameters + ---------- + num_buffer: int + Number of buffers to create + timeout: int + Timeout in ms for recycling buffers with refcount 0 + + """ + self.num_buffer = num_buffer + self.timeout = timeout + + err, = cuda.cuInit(0) + self.ASSERT_CUDA_SUCCESS(err) + + # Create CUDA Stream + err, self._stream = cudart.cudaStreamCreate() + self.ASSERT_CUDA_SUCCESS(err) + + # Maps CUDA Memblocks to their respective shared CPU memory + self._cuda_memblock_to_cpu_mem = {} + self._cuda_memblock_event = {} + + # Cuda MemBlock Housekeeping + self._cuda_memblock_fd_to_ptr = {} + self._cuda_memblock_info = [] + self._cuda_memblock_start_time = {} + self._mem_block_index = 0 + + self._first_frame = True + + def create_memblock_pool(self, buffer_size): + """ + Create a pool of CUDA IPC memory blocks. + + This pool is created the first time message is built. + """ + self.buffer_size = buffer_size + for _ in range(self.num_buffer): + # Create memory block + cuda_memblock_fd, cuda_memblock_virtual_ptr = self._create_cuda_memblock() + + # Add to mem pool mapping + cpu_memblock_info = CPUSharedMem() + cpu_memblock_info.create_shm(str(os.getpid()) + str(cuda_memblock_fd)) + + cpu_memblock_info.lock.acquire() + cpu_memblock_info.put_value((0, uuid.uuid4())) + cpu_memblock_info.lock.release() + + self._cuda_memblock_to_cpu_mem[cuda_memblock_fd] = cpu_memblock_info + + # Add fd, ptr info + self._cuda_memblock_fd_to_ptr[cuda_memblock_fd] = int( + cuda_memblock_virtual_ptr) + + # Set timeout value + self._cuda_memblock_start_time[cuda_memblock_fd] = 0 + + # Setup event, record stream, and perform copy + err, event = cudart.cudaEventCreateWithFlags( + cudart.cudaEventInterprocess | cudart.cudaEventDisableTiming) + self.ASSERT_CUDA_SUCCESS(err) + + err, event_handle = cudart.cudaIpcGetEventHandle(event) + self.ASSERT_CUDA_SUCCESS(err) + self._cuda_memblock_event[cuda_memblock_fd] = (event, event_handle) + + def get_free_memblock(self): + """ + Get a free CUDA memblock from the pool. + + If no free memblock is available, it will keep looping until a + free memblock is available. + + Returns + ------- + Tuple of (memblock_fd, memblock_uuid, memblock_refcount) + memblock_fd: int + File descriptor of the memblock + memblock_uuid: uuid + UID of the memblock, updated everytime the memblock is reused + memblock_refcount: int + Reference count of the memblock + + """ + cuda_memblock_list = list(self._cuda_memblock_to_cpu_mem.items()) + last_used_index = self._mem_block_index + while True: + cuda_memblock_fd, cuda_memblock = cuda_memblock_list[self._mem_block_index] + start_time = self._cuda_memblock_start_time[cuda_memblock_fd] + current_time = time.time() * 1000 + + # TODO(yuankunz): Reset timeout everytime refcount is decreased to 0 + if current_time - start_time > self.timeout: + cuda_memblock.lock.acquire() + cuda_memblock_refcount, cuda_memblock_uuid = cuda_memblock.get_value() + if cuda_memblock_refcount == 0: + self._cuda_memblock_start_time[cuda_memblock_fd] = time.time() * 1000 + cuda_memblock.lock.release() + self._mem_block_index = (self._mem_block_index + 1) % len(cuda_memblock_list) + return cuda_memblock_fd, cuda_memblock_uuid, cuda_memblock_refcount + else: + cuda_memblock.lock.release() + self._mem_block_index = (self._mem_block_index + 1) % len(cuda_memblock_list) + if self._mem_block_index == last_used_index: + rclpy.logging.get_logger('PyNITROSBuilder').info( + 'No free memblock available, retry after 1ms...') + time.sleep(0.001) + + def _create_cuda_memblock(self): + """Create an IPC CUDA memory pool with the given buffer size and number of buffers.""" + # Allocate GPU Space -> CUmemGenericAllocationHandle + allocProp = cuda.CUmemAllocationProp() + allocProp.type = cuda.CUmemAllocationType.CU_MEM_ALLOCATION_TYPE_PINNED + allocProp.location.type = cuda.CUmemLocationType.CU_MEM_LOCATION_TYPE_DEVICE + allocProp.requestedHandleTypes = \ + cuda.CUmemAllocationHandleType.CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR + allocProp.location.id = 0 + + # Get granularity + err, granularity = cuda.cuMemGetAllocationGranularity( + allocProp, cuda.CUmemAllocationGranularity_flags.CU_MEM_ALLOC_GRANULARITY_MINIMUM) + self.ASSERT_CUDA_SUCCESS(err) + + # Call cuMemCreate with the address of allocProp + rounded_data_size = self._round_up(self.buffer_size, granularity) + + err, handle = cuda.cuMemCreate(rounded_data_size, allocProp, 0) + self.ASSERT_CUDA_SUCCESS(err) + + # Reserve Virtual Address Range + err, memblock_virtual_ptr = cuda.cuMemAddressReserve( + rounded_data_size, 0, 0, 0) + self.ASSERT_CUDA_SUCCESS(err) + + # Map Handle to Virtual Address Range, Set RW Access + err, = cuda.cuMemMap(memblock_virtual_ptr, + rounded_data_size, 0, handle, 0) + self.ASSERT_CUDA_SUCCESS(err) + + self._cuda_memblock_info.append( + (handle, memblock_virtual_ptr, rounded_data_size)) + + accessDesc = cuda.CUmemAccessDesc() + accessDesc.location = allocProp.location + accessDesc.flags = cuda.CUmemAccess_flags.CU_MEM_ACCESS_FLAGS_PROT_READWRITE + + err, = cuda.cuMemSetAccess( + memblock_virtual_ptr, rounded_data_size, [accessDesc], 1) + self.ASSERT_CUDA_SUCCESS(err) + + # Export Shareable Handle + err, memblock_fd = cuda.cuMemExportToShareableHandle( + handle, cuda.CUmemAllocationHandleType.CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR, 0) + self.ASSERT_CUDA_SUCCESS(err) + + return (memblock_fd, memblock_virtual_ptr) + + def _round_up(self, size, granularity): + """Round up the size to the nearest multiple of granularity.""" + mult = math.ceil(size / float(granularity)) + return mult * granularity + + def ASSERT_CUDA_SUCCESS(self, err): + """Assert if the CUDA operation is successful.""" + if isinstance(err, cuda.CUresult): + if err != cuda.CUresult.CUDA_SUCCESS: + raise RuntimeError( + f'[Cuda Error: {err}], {cuda.cuGetErrorString(err)}') + elif isinstance(err, cudart.cudaError_t): + if (err != 0): + raise RuntimeError(f'CudaRT Error: {err}') + else: + raise RuntimeError('Unknown error type: {}'.format(err)) + + def __del__(self): + """Destructor to free all the allocated resources.""" + for cpu_memblock in self._cuda_memblock_to_cpu_mem.values(): + cpu_memblock.close() + + for cuda_event, _ in self._cuda_memblock_event.values(): + err, = cudart.cudaEventDestroy(cuda_event) + self.ASSERT_CUDA_SUCCESS(err) + + err, = cuda.cuStreamDestroy(self._stream) + self.ASSERT_CUDA_SUCCESS(err) + + # Free shared cuda memblocks + for cuda_memblock_handle, cuda_memblock_virtual_ptr, data_size in self._cuda_memblock_info: + err, = cuda.cuMemUnmap(cuda_memblock_virtual_ptr, data_size) + self.ASSERT_CUDA_SUCCESS(err) + + err, = cuda.cuMemAddressFree(cuda_memblock_virtual_ptr, data_size) + self.ASSERT_CUDA_SUCCESS(err) + + err, = cuda.cuMemRelease(cuda_memblock_handle) + self.ASSERT_CUDA_SUCCESS(err) diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/__init__.py b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/__init__.py new file mode 100644 index 0000000..34d9bfe --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/__init__.py @@ -0,0 +1,16 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_image_view.py b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_image_view.py new file mode 100644 index 0000000..4833364 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_image_view.py @@ -0,0 +1,88 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from cuda import cudart +import torch + +from .pynitros_type_view_base import PyNitrosTypeViewBase + + +class PyNitrosImageView(PyNitrosTypeViewBase): + """PyNITROS View for NITROSBridgeImage.""" + + def __init__(self, raw_msg, gpu_ptr=None): + super().__init__(raw_msg, gpu_ptr) + + if (isinstance(self.raw_msg, self.nitros_bridge_msg_types)): + sender_pid, memblock_fd = self.get_pid_fd(self.raw_msg) + if (self._open_shm_and_check_uid(sender_pid, memblock_fd) is not True): + raise ValueError('UID match failed') + + if (self.gpu_ptr is None): + if (isinstance(self.raw_msg, self.nitros_bridge_msg_types)): + self.gpu_ptr = self._from_bridge_msg() + elif (isinstance(self.raw_msg, self.raw_msg_types)): + self.gpu_ptr = self._from_raw_msg() + else: + raise RuntimeError('Invalid message type') + + self.gpu_ptr = int(self.gpu_ptr) + self.shape = torch.Size( + [raw_msg.height * raw_msg.step]) + self.__cuda_array_interface__ = { + 'shape': self.shape, + 'typestr': '|u1', + 'data': (self.gpu_ptr, False), + 'version': 0 + } + + @staticmethod + def get_pid_fd(bridge_msg): + return bridge_msg.data[0], bridge_msg.data[1] + + def _from_bridge_msg(self): + sender_pid, memblock_fd = self.get_pid_fd(self.raw_msg) + data_size = self.raw_msg.height * self.raw_msg.step + return self._import_gpu_ptr_from_fd(sender_pid, memblock_fd, data_size) + + def _from_raw_msg(self): + image_size = len(self.raw_msg.data) + err, device_ptr = cudart.cudaMalloc(image_size) + self.ASSERT_CUDA_SUCCESS(err) + + err, = cudart.cudaMemcpy(device_ptr, self.raw_msg.data, image_size, + cudart.cudaMemcpyKind.cudaMemcpyHostToDevice) + self.ASSERT_CUDA_SUCCESS(err) + return device_ptr + + def get_size_in_bytes(self): + return self.raw_msg.step * self.raw_msg.height + + def get_width(self): + return self.raw_msg.width + + def get_height(self): + return self.raw_msg.height + + def get_stride(self): + return self.raw_msg.step + + def get_buffer(self): + return self.gpu_ptr + + def get_encoding(self): + return self.raw_msg.encoding diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_tensor_list_view.py b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_tensor_list_view.py new file mode 100644 index 0000000..dde533d --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_tensor_list_view.py @@ -0,0 +1,152 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import math + +from cuda import cuda, cudart +from isaac_ros_pynitros.utils.tensor_data_type import TensorDataTypeUtils +import torch + +from .pynitros_type_view_base import PyNitrosTypeViewBase + + +class PyNitrosTensorListView(PyNitrosTypeViewBase): + """PyNITROS view for NitrosBridgeTensorList.""" + + def __init__(self, raw_msg, gpu_ptr=None): + super().__init__(raw_msg, gpu_ptr) + self._tensor_map = {} + self._tensors = [] + self._total_tensor_size = 0 + + if (isinstance(self.raw_msg, self.nitros_bridge_msg_types)): + sender_pid, memblock_fd = self.get_pid_fd(self.raw_msg) + if (self._open_shm_and_check_uid(sender_pid, memblock_fd) is not True): + raise ValueError('UID match failed') + + if (self.gpu_ptr is None): + if (isinstance(self.raw_msg, self.nitros_bridge_msg_types)): + self.gpu_ptr = self._from_bridge_msg() + elif (isinstance(self.raw_msg, self.raw_msg_types)): + self.gpu_ptr = self._from_raw_msg() + else: + raise RuntimeError('Invalid message type') + self.gpu_ptr = int(self.gpu_ptr) + self._prepare_tensor_view() + + @staticmethod + def get_pid_fd(bridge_msg): + return bridge_msg.pid, bridge_msg.fd + + def _prepare_tensor_view(self): + if (not self.gpu_ptr): + raise RuntimeError('Invalid GPU pointer') + for nitros_bridge_tensor_msg in self.raw_msg.tensors: + cur_gpu_ptr = cuda.CUdeviceptr(int(self.gpu_ptr) + self._total_tensor_size) + pynitros_tensor_view = PyNitrosTensorView( + nitros_bridge_tensor_msg, cur_gpu_ptr) + tensor_size = pynitros_tensor_view.get_tensor_size() + self._total_tensor_size += tensor_size + + self._tensor_map[nitros_bridge_tensor_msg.name] = pynitros_tensor_view + self._tensors.append(pynitros_tensor_view) + + def _from_bridge_msg(self): + sending_pid = self.raw_msg.pid + memblock_fd = self.raw_msg.fd + data_size = 0 + for tensor in self.raw_msg.tensors: + data_size += \ + math.prod(tensor.shape.dims) * \ + TensorDataTypeUtils.get_size_in_bytes(tensor.data_type) + virtual_ptr = self._import_gpu_ptr_from_fd(sending_pid, memblock_fd, data_size) + return virtual_ptr + + def _from_raw_msg(self): + total_tensor_size, offset = 0, 0 + for tensor in self.raw_msg.tensors: + total_tensor_size += \ + math.prod(tensor.shape.dims) * \ + TensorDataTypeUtils.get_size_in_bytes(tensor.data_type) + err, device_ptr = cudart.cudaMalloc(total_tensor_size) + self.ASSERT_CUDA_SUCCESS(err) + + for tensor in self.raw_msg.tensors: + tensor_size = \ + math.prod(tensor.shape.dims) * \ + TensorDataTypeUtils.get_size_in_bytes(tensor.data_type) + err, = cudart.cudaMemcpy(device_ptr+offset, tensor.data, tensor_size, + cudart.cudaMemcpyKind.cudaMemcpyHostToDevice) + self.ASSERT_CUDA_SUCCESS(err) + offset += tensor_size + return device_ptr + + def get_buffer(self): + return self.gpu_ptr + + def get_tensor_count(self): + return len(self.tensors) + + def get_named_tensor(self, name): + return self._tensor_map[name] + + def get_all_tensors(self): + return self._tensors + + def get_size_in_bytes(self): + return self._total_tensor_size + + +class PyNitrosTensorView(PyNitrosTypeViewBase): + """PyNITROS view for NitrosBridgeTensor.""" + + def __init__(self, raw_msg, gpu_ptr): + super().__init__(raw_msg, gpu_ptr) + self.shape = torch.Size(self.raw_msg.shape.dims) + self.gpu_ptr = int(self.gpu_ptr) + self.element_count = math.prod(self.raw_msg.shape.dims) + self.__cuda_array_interface__ = { + 'shape': self.shape, + 'strides': self.raw_msg.strides, + 'typestr': TensorDataTypeUtils.get_typestr(self.raw_msg.data_type), + 'data': (self.gpu_ptr, False), + 'version': 0 + } + + def get_name(self): + return self.raw_msg.name + + def get_buffer(self): + return self.gpu_ptr + + def get_rank(self): + return self.raw_msg.shape.rank + + def get_bytes_per_element(self): + return TensorDataTypeUtils.get_size_in_bytes(self.raw_msg.data_type) + + def get_element_count(self): + return self.element_count + + def get_tensor_size(self): + return self.get_element_count() * self.get_bytes_per_element() + + def get_shape(self): + return tuple(self.raw_msg.shape.dims) + + def get_element_type(self): + return self.raw_msg.data_type diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_type_view_base.py b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_type_view_base.py new file mode 100644 index 0000000..5b10b82 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/pynitros_type_views/pynitros_type_view_base.py @@ -0,0 +1,190 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import ctypes +from ctypes import c_long +import math + +from cuda import cuda, cudart +from isaac_ros_nitros_bridge_interfaces.msg import NitrosBridgeImage, NitrosBridgeTensorList +from isaac_ros_pynitros.utils.cpu_shared_mem import CPUSharedMem +from isaac_ros_tensor_list_interfaces.msg import TensorList +import rclpy +from sensor_msgs.msg import Image + + +class PyNitrosTypeViewBase(): + """ + Base class of PyNITROS message view. + + PyNITROS message view provides functionalities to access the metadata + and the GPU pointer of the underlying NITROS Bridge message. It can + also be converted to other data type such as PyTorch tensor or cupy array. + """ + + # Define the syscall numbers for pidfd_open and pidfd_getfd + SYS_pidfd_open = 434 + SYS_pidfd_getfd = 438 + + # Define the syscall function + syscall = ctypes.CDLL(None).syscall + syscall.restype = c_long + syscall.argtypes = [c_long, c_long, + c_long, c_long, c_long, c_long] + + nitros_bridge_msg_types = ( + NitrosBridgeImage, + NitrosBridgeTensorList + ) + + raw_msg_types = ( + Image, + TensorList + ) + + def __init__(self, raw_msg, gpu_ptr): + self.gpu_ptr = gpu_ptr + self.raw_msg = raw_msg + self.cuda_stream = None + self.handle = None + self._cpu_shared_mem = None + + def _open_shm_and_check_uid(self, sender_pid, memblock_fd): + self._cpu_shared_mem = CPUSharedMem() + # If UID presents (for backward compatibility), + # compare UID with it in shared mem and update refcount + if (self.raw_msg.uid): + # Create instance of shared cpu mem pool + self._cpu_shared_mem.open_shm(str(sender_pid) + str(memblock_fd)) + + # Acquire lock, check UID, increase refcount if UID match + self._cpu_shared_mem.lock.acquire() + memblock_refcount, memblock_uuid = self._cpu_shared_mem.get_value() + if str(memblock_uuid) != str(self.raw_msg.uid): + self._cpu_shared_mem.lock.release() + rclpy.logging.get_logger('PyNITROS Subscriber').info( + f'MEMBLOCK UID: {memblock_uuid} != \ + MSG UID: {self.raw_msg.uid}, dropping message' + ) + return False + else: + self._cpu_shared_mem.update_refcount(1) + self._cpu_shared_mem.lock.release() + return True + + def _import_gpu_ptr_from_fd(self, sender_pid, memblock_fd, data_size): + """Import the shared memory from file descriptor.""" + # FD -> Handle + pidfd = self._pidfd_open(sender_pid, 0) + if pidfd == -1: + raise RuntimeError('pidfd_open failed') + + new_fd = self._pidfd_getfd(pidfd, memblock_fd, 0) + if new_fd == -1: + raise RuntimeError('pidfd_getfd failed') + + err, self.handle = cuda.cuMemImportFromShareableHandle( + new_fd, + cuda.CUmemAllocationHandleType.CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR) + self.ASSERT_CUDA_SUCCESS(err) + + # Allocate GPU Space -> CUmemGenericAllocationHandle + allocProp = cuda.CUmemAllocationProp() + allocProp.type = cuda.CUmemAllocationType.CU_MEM_ALLOCATION_TYPE_PINNED + allocProp.location.type = cuda.CUmemLocationType.CU_MEM_LOCATION_TYPE_DEVICE + allocProp.requestedHandleTypes = \ + cuda.CUmemAllocationHandleType.CU_MEM_HANDLE_TYPE_POSIX_FILE_DESCRIPTOR + allocProp.location.id = 0 + + # Get memory alloc granularity + err, granularity = cuda.cuMemGetAllocationGranularity( + allocProp, + cuda.CUmemAllocationGranularity_flags.CU_MEM_ALLOC_GRANULARITY_MINIMUM) + self.ASSERT_CUDA_SUCCESS(err) + + rounded_data_size = self._round_up(data_size, granularity) + + # Handle -> Tensor Reconstruction + res, virtual_ptr = cuda.cuMemAddressReserve( + rounded_data_size, 0, 0, 0) + self.ASSERT_CUDA_SUCCESS(res) + + # Map Handle to Virtual Address Range, Set Access + res, = cuda.cuMemMap(virtual_ptr, rounded_data_size, 0, self.handle, 0) + self.ASSERT_CUDA_SUCCESS(res) + + accessDesc = cuda.CUmemAccessDesc() + accessDesc.location = allocProp.location + accessDesc.flags = cuda.CUmemAccess_flags.CU_MEM_ACCESS_FLAGS_PROT_READWRITE + + res, = cuda.cuMemSetAccess( + virtual_ptr, rounded_data_size, [accessDesc], 1) + self.ASSERT_CUDA_SUCCESS(res) + + return virtual_ptr + + def _round_up(self, size, granularity): + mult = math.ceil(size / float(granularity)) + return mult * granularity + + def _pidfd_open(self, pid, flags): + return self.syscall(self.SYS_pidfd_open, pid, flags, 0, 0, 0, 0) + + def _pidfd_getfd(self, pidfd, targetfd, flags): + return self.syscall(self.SYS_pidfd_getfd, pidfd, targetfd, flags, 0, 0, 0) + + def ASSERT_CUDA_SUCCESS(self, err): + if isinstance(err, cuda.CUresult): + if err != cuda.CUresult.CUDA_SUCCESS: + raise RuntimeError( + f'[Cuda Error: {err}], {cuda.cuGetErrorString(err)}') + elif isinstance(err, cudart.cudaError_t): + if (err != 0): + raise RuntimeError(f'CudaRT Error: {err}') + else: + raise RuntimeError('Unknown error type: {}'.format(err)) + + def set_stream(self, stream): + """Fill the CUDA stream if async CUDA operations are in the fly.""" + self.cuda_stream = stream + + def postprocess(self): + """Postprocess the view.""" + if self.cuda_stream: + err, = cudart.cudaStreamSynchronize(self.cuda_stream) + self.ASSERT_CUDA_SUCCESS(err) + if (type(self.raw_msg) in self.nitros_bridge_msg_types): + # Decrease the refcount + if (self.raw_msg.uid): + self._cpu_shared_mem.lock.acquire() + self._cpu_shared_mem.update_refcount(-1) + self._cpu_shared_mem.lock.release() + else: + # Free the memory + cudart.cudaFree(self.gpu_ptr) + + def get_handle(self): + return self.handle + + def get_frame_id(self): + return self.raw_msg.header.frame_id + + def get_timestamp_seconds(self): + return self.raw_msg.header.stamp.sec + + def get_timestamp_nanoseconds(self): + return self.raw_msg.header.stamp.nanosec diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/utils/__init__.py b/isaac_ros_pynitros/isaac_ros_pynitros/utils/__init__.py new file mode 100644 index 0000000..34d9bfe --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/utils/__init__.py @@ -0,0 +1,16 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/utils/cpu_shared_mem.py b/isaac_ros_pynitros/isaac_ros_pynitros/utils/cpu_shared_mem.py new file mode 100644 index 0000000..e565682 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/utils/cpu_shared_mem.py @@ -0,0 +1,88 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +import mmap +import struct +import uuid + +import posix_ipc + + +class CPUSharedMem(): + """Shared CPU Mem for tracking CUDA Mem Block Info.""" + + def __init__(self): + self.map_element_size = struct.calcsize('i16s') + self.cpu_shared_mem = None + self.cpu_shared_mem_obj = None + self.lock = None + + def create_shm(self, name): + """Create a shared memory object with a given name.""" + self.cpu_shared_mem = posix_ipc.SharedMemory( + name, posix_ipc.O_CREAT, size=self.map_element_size) + + # Attach the shared memory to a byte array + self.cpu_shared_mem_obj = mmap.mmap( + self.cpu_shared_mem.fd, self.map_element_size) + self.lock = posix_ipc.Semaphore( + name, posix_ipc.O_CREAT, initial_value=1) + + def open_shm(self, name): + """Open a shared memory object with a given name.""" + self.cpu_shared_mem = posix_ipc.SharedMemory(name) + + # Attach the shared memory to a byte array + self.cpu_shared_mem_obj = mmap.mmap( + self.cpu_shared_mem.fd, self.map_element_size) + self.lock = posix_ipc.Semaphore(name) + + def update_refcount(self, val): + """Update the reference count of the shared memory.""" + memblock_refcount, memblock_uuid = self.get_value() + self.put_value((memblock_refcount + val, memblock_uuid)) + + def put_value(self, value): + """Write a value to the shared memory.""" + packed_value = struct.pack('i16s', value[0], value[1].bytes) + + self.cpu_shared_mem_obj.seek(0) + self.cpu_shared_mem_obj.write(packed_value) + self.cpu_shared_mem_obj.flush() + + def get_value(self): + """Read a value from the shared memory.""" + self.cpu_shared_mem_obj.seek(0) + packed_value = self.cpu_shared_mem_obj.read() + + unpacked_value = struct.unpack('i16s', packed_value) + + # Extract relevant parts of the unpacked value + memblock_refcount = unpacked_value[0] + memblock_uuid_bytes = unpacked_value[1] + + # Convert UUID bytes to UUID object + memblock_uuid = uuid.UUID(bytes=memblock_uuid_bytes) + + return memblock_refcount, memblock_uuid + + def close(self): + """Close the shared memory object.""" + self.cpu_shared_mem_obj.close() + self.cpu_shared_mem.close_fd() + self.cpu_shared_mem.unlink() + self.lock.unlink() diff --git a/isaac_ros_pynitros/isaac_ros_pynitros/utils/tensor_data_type.py b/isaac_ros_pynitros/isaac_ros_pynitros/utils/tensor_data_type.py new file mode 100644 index 0000000..decf027 --- /dev/null +++ b/isaac_ros_pynitros/isaac_ros_pynitros/utils/tensor_data_type.py @@ -0,0 +1,55 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + + +class TensorDataTypeUtils(): + """ + Helper class to provide utility functions for tensor data types. + + Use the following int values to represent tensor data types: + - 1: "int8" + - 2: "uint8" + - 3: "int16" + - 4: "uint16" + - 5: "int32" + - 6: "uint32" + - 7: "int64" + - 8: "uint64" + - 9: "float32" + - 10: "float64" + """ + + data_type_map = { + 1: ('|i1', 1), + 2: ('|u1', 1), + 3: ('|i2', 2), + 4: ('|u2', 2), + 5: ('|i4', 4), + 6: ('|u4', 4), + 7: ('|i8', 8), + 8: ('|u8', 8), + 9: ('|f4', 4), + 10: ('|f8', 8) + } + + @classmethod + def get_typestr(cls, data_type): + return cls.data_type_map[data_type][0] + + @classmethod + def get_size_in_bytes(cls, data_type): + return cls.data_type_map[data_type][1] diff --git a/isaac_ros_pynitros/launch/isaac_ros_pynitros_dnn_image_encoder.launch.py b/isaac_ros_pynitros/launch/isaac_ros_pynitros_dnn_image_encoder.launch.py new file mode 100644 index 0000000..5d1f7d7 --- /dev/null +++ b/isaac_ros_pynitros/launch/isaac_ros_pynitros_dnn_image_encoder.launch.py @@ -0,0 +1,71 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +"""DNN image encoder launch file using PyNITROS.""" + +import launch + +from launch.actions import DeclareLaunchArgument, ExecuteProcess, OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node +import launch_testing.actions + + +def launch_setup(context): + rosbag_path = LaunchConfiguration('rosbag_path').perform(context) + + rosbag_play = ExecuteProcess( + cmd=['ros2', 'bag', 'play', rosbag_path, '--loop'], + output='screen') + + dnn_image_encoder = Node(name='dnn_image_encoder', + package='isaac_ros_pynitros', + executable='pynitros_dnn_image_encoder_node', + parameters=[{ + 'enable_ros_subscribe': True, + 'enable_ros_publish': True, + 'network_image_width': 960, + 'network_image_height': 544, + 'image_mean': [0.5, 0.5, 0.5], + 'image_std': [0.5, 0.5, 0.5] + }], + remappings=[ + ('pynitros_input_msg', '/image_rect'), + ('pynitros_output_msg', 'pynitros1_output_msg'), + ('pynitros_output_msg_ros', 'tensor_pub') + ], + output='screen') + + return [rosbag_play, + dnn_image_encoder] + + +def generate_launch_description(): + launch_args = [ + DeclareLaunchArgument( + 'rosbag_path', + description='Remapped publish image name of NITROS Bridge ROS2'), + ] + + nodes = launch_args + [OpaqueFunction(function=launch_setup)] + return launch.LaunchDescription( + nodes + [ + # Start tests after a fixed delay for node startup + launch.actions.TimerAction( + period=30.0, + actions=[launch_testing.actions.ReadyToTest()]) + ] + ) diff --git a/isaac_ros_pynitros/launch/isaac_ros_pynitros_quickstart.launch.py b/isaac_ros_pynitros/launch/isaac_ros_pynitros_quickstart.launch.py new file mode 100644 index 0000000..73e3fc2 --- /dev/null +++ b/isaac_ros_pynitros/launch/isaac_ros_pynitros_quickstart.launch.py @@ -0,0 +1,91 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Quickstart launch file for PyNITROS. + +This launch file use two image forward nodes built with PyNITROS to demonstrate +the zero-copy interop between PyNITROS nodes. +""" + +import launch + +from launch.actions import DeclareLaunchArgument, ExecuteProcess, OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node +import launch_testing.actions + + +def launch_setup(context): + rosbag_path = LaunchConfiguration('rosbag_path').perform(context) + + rosbag_play = ExecuteProcess( + cmd=['ros2', 'bag', 'play', rosbag_path, '--loop', '--remap', + '/hawk_0_left_rgb_image:=/pynitros1_input_msg'], + output='screen') + + pynitros_image_forward_node_1 = Node( + name='pynitros_image_forward_node_1', + package='isaac_ros_pynitros', + executable='pynitros_image_forward_node', + parameters=[{ + 'enable_ros_subscribe': True, + 'enable_ros_publish': False + }], + remappings=[ + ('pynitros_input_msg', 'pynitros1_input_msg'), + ('pynitros_output_msg', 'pynitros1_output_msg'), + ('pynitros_output_msg_ros', 'pynitros1_output_msg_ros') + ], + output='screen' + ) + + pynitros_image_forward_node_2 = Node( + name='pynitros_image_forward_node_2', + package='isaac_ros_pynitros', + executable='pynitros_image_forward_node', + parameters=[{ + 'enable_ros_subscribe': False, + 'enable_ros_publish': True + }], + remappings=[ + ('pynitros_input_msg', 'pynitros1_output_msg'), + ('pynitros_output_msg', 'pynitros2_output_msg'), + ('pynitros_output_msg_ros', 'pynitros2_output_msg_ros') + ], + output='screen' + ) + return [rosbag_play, + pynitros_image_forward_node_1, + pynitros_image_forward_node_2] + + +def generate_launch_description(): + launch_args = [ + DeclareLaunchArgument( + 'rosbag_path', + description='Remapped publish image name of NITROS Bridge ROS2'), + ] + + nodes = launch_args + [OpaqueFunction(function=launch_setup)] + return launch.LaunchDescription( + nodes + [ + # Start tests after a fixed delay for node startup + launch.actions.TimerAction( + period=30.0, + actions=[launch_testing.actions.ReadyToTest()]) + ] + ) diff --git a/isaac_ros_pynitros/launch/isaac_ros_pynitros_to_nitros.launch.py b/isaac_ros_pynitros/launch/isaac_ros_pynitros_to_nitros.launch.py new file mode 100644 index 0000000..0a5f113 --- /dev/null +++ b/isaac_ros_pynitros/launch/isaac_ros_pynitros_to_nitros.launch.py @@ -0,0 +1,90 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2023-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +""" +Launch file for PyNITROS and NITROS interop. + +This launch file use one PyNITROS image forward node +and one NITROS bridge node to demonstrate the zero-copy interop PyNITROS and NITROS. +""" + +import launch + +from launch.actions import DeclareLaunchArgument, ExecuteProcess, OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import ComposableNodeContainer, Node +from launch_ros.descriptions import ComposableNode +import launch_testing.actions + + +def launch_setup(context): + rosbag_path = LaunchConfiguration('rosbag_path').perform(context) + + rosbag_play = ExecuteProcess( + cmd=['ros2', 'bag', 'play', rosbag_path, '--loop', '--remap', + '/hawk_0_left_rgb_image:=/pynitros_input_msg'], + output='screen') + + # Image forward node implemented with PyNITROS + pynitros_image_forward_node = Node( + name='pynitros_image_forward_node', + package='isaac_ros_pynitros', + executable='pynitros_image_forward_node', + parameters=[{ + 'enable_ros_subscribe': True, + 'enable_ros_publish': False + }], + output='screen' + ) + + # NITROS bridge node converts NITROS Bridge msg to NITROS msg + nitros_bridge_node = ComposableNode( + name='nitros_bridge_node', + package='isaac_ros_nitros_bridge_ros2', + plugin='nvidia::isaac_ros::nitros_bridge::ImageConverterNode', + remappings=[ + ('ros2_input_bridge_image', 'pynitros_output_msg'), + ('ros2_output_image', 'output'), + ]) + + container = ComposableNodeContainer( + name='ros2_converter_container', + namespace='', + package='rclcpp_components', + executable='component_container_mt', + composable_node_descriptions=[nitros_bridge_node], + output='screen', + arguments=['--ros-args', '--log-level', 'info'] + ) + return [rosbag_play, pynitros_image_forward_node, container] + + +def generate_launch_description(): + launch_args = [ + DeclareLaunchArgument( + 'rosbag_path', + description='Remapped publish image name of NITROS Bridge ROS2'), + ] + + nodes = launch_args + [OpaqueFunction(function=launch_setup)] + return launch.LaunchDescription( + nodes + [ + # Start tests after a fixed delay for node startup + launch.actions.TimerAction( + period=30.0, + actions=[launch_testing.actions.ReadyToTest()]) + ] + ) diff --git a/isaac_ros_pynitros/package.xml b/isaac_ros_pynitros/package.xml new file mode 100644 index 0000000..dbdeef1 --- /dev/null +++ b/isaac_ros_pynitros/package.xml @@ -0,0 +1,32 @@ + + + + isaac_ros_pynitros + 3.2.0 + PyNITROS + Isaac ROS Maintainers + Apache License 2.0 + Mihir Rao + Yuankun Zhu + isaac_ros_common + + + cuda_python + posix_ipc + rclpy + std_msgs + isaac_ros_nitros_bridge_interfaces + isaac_ros_tensor_list_interfaces + + isaac_ros_test + ament_copyright + ament_flake8 + ament_pep257 + ament_lint_auto + ament_lint_common + python3-pytest + + + ament_python + + diff --git a/isaac_ros_pynitros/resource/isaac_ros_pynitros b/isaac_ros_pynitros/resource/isaac_ros_pynitros new file mode 100644 index 0000000..e69de29 diff --git a/isaac_ros_pynitros/setup.cfg b/isaac_ros_pynitros/setup.cfg new file mode 100644 index 0000000..9ab4834 --- /dev/null +++ b/isaac_ros_pynitros/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/isaac_ros_pynitros +[install] +install_scripts=$base/lib/isaac_ros_pynitros diff --git a/isaac_ros_pynitros/setup.py b/isaac_ros_pynitros/setup.py new file mode 100644 index 0000000..7994d45 --- /dev/null +++ b/isaac_ros_pynitros/setup.py @@ -0,0 +1,62 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from glob import glob +from os import path + +from setuptools import find_packages, setup + +package_name = 'isaac_ros_pynitros' + +setup( + name=package_name, + version='3.0.0', + packages=find_packages(), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + (path.join('share', package_name, 'launch'), glob('launch/*.launch.py')) + ], + install_requires=[ + 'cuda_python', + 'posix_ipc', + 'setuptools' + ], + zip_safe=True, + maintainer='Isaac ROS Maintainers', + maintainer_email='isaac-ros-maintainers@nvidia.com', + description='Execute the control graph in isaac ros integration test', + license='Apache-2.0', + extras_require={ + 'test': [ + 'pytest', + ], + }, + entry_points={ + 'console_scripts': [ + 'pynitros_image_forward_node = \ + isaac_ros_pynitros.examples.pynitros_image_forward_node:main', + 'pynitros_tensor_list_forward_node = \ + isaac_ros_pynitros.examples.pynitros_tensor_list_forward_node:main', + 'pynitros_dnn_image_encoder_node = \ + isaac_ros_pynitros.examples.pynitros_dnn_image_encoder_node:main', + 'pynitros_message_filter_sync_node = \ + isaac_ros_pynitros.examples.pynitros_message_filter_sync_node:main', + ], + }, +) diff --git a/isaac_ros_pynitros/test/isaac_ros_pynitros_dnn_image_encoder.py b/isaac_ros_pynitros/test/isaac_ros_pynitros_dnn_image_encoder.py new file mode 100644 index 0000000..bd6e837 --- /dev/null +++ b/isaac_ros_pynitros/test/isaac_ros_pynitros_dnn_image_encoder.py @@ -0,0 +1,127 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +"""Proof-of-Life test for the PyNITROS.""" + +import os +import pathlib +import subprocess +import time + +from isaac_ros_tensor_list_interfaces.msg import TensorList +from isaac_ros_test import IsaacROSBaseTest, JSONConversion +import launch + +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy + +from sensor_msgs.msg import Image + + +@pytest.mark.rostest +def generate_test_description(): + """Generate launch description with all ROS 2 nodes for testing.""" + ptace_result = subprocess.run(['cat', '/proc/sys/kernel/yama/ptrace_scope'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + pidfd_getfd_result = subprocess.run(['grep', 'pidfd_getfd', '/proc/kallsyms'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + if (ptace_result.stdout.strip() == '0' and pidfd_getfd_result.returncode == 0): + IsaacROSPyNitrosTest.skip_test = False + dnn_image_encoder = Node(name='dnn_image_encoder', + package='isaac_ros_pynitros', + namespace='pynitros', + executable='pynitros_dnn_image_encoder_node', + parameters=[{ + 'enable_ros_subscribe': True, + 'enable_ros_publish': True, + 'network_image_width': 960, + 'network_image_height': 544, + 'image_mean': [0.5, 0.5, 0.5], + 'image_std': [0.5, 0.5, 0.5] + }], + remappings=[ + ('pynitros_input_msg', 'pynitros1_input_msg'), + ('pynitros_output_msg', 'pynitros1_output_msg'), + ('pynitros_output_msg_ros', 'pynitros1_output_msg_ros') + ], + output='screen') + + return IsaacROSPyNitrosTest.generate_test_description([ + dnn_image_encoder, + launch.actions.TimerAction(period=2.5, actions=[launch_testing.actions.ReadyToTest()]) + ]) + else: + IsaacROSPyNitrosTest.skip_test = True + return IsaacROSPyNitrosTest.generate_test_description( + [launch_testing.actions.ReadyToTest()]) + + +class IsaacROSPyNitrosTest(IsaacROSBaseTest): + """Validate Nitros Bridge on Image type.""" + + filepath = pathlib.Path(os.path.dirname(__file__)) + + @IsaacROSBaseTest.for_each_test_case(subfolder='nitros_image') + def test_pynitros_image(self, test_folder) -> None: + if self.skip_test: + self.skipTest('No ptrace permission! Skipping test.') + else: + IsaacROSPyNitrosTest.DEFAULT_NAMESPACE = 'pynitros' + self.generate_namespace_lookup(['pynitros1_input_msg', 'pynitros1_output_msg_ros']) + received_messages = {} + + received_image_sub = self.create_logging_subscribers( + subscription_requests=[('pynitros1_output_msg_ros', TensorList)], + received_messages=received_messages) + + image_pub = self.node.create_publisher(Image, self.namespaces['pynitros1_input_msg'], + self.DEFAULT_QOS) + + try: + image = JSONConversion.load_image_from_json(test_folder / 'image.json') + timestamp = self.node.get_clock().now().to_msg() + image.header.stamp = timestamp + + # Wait at most TIMEOUT seconds for subscriber to respond + TIMEOUT = 30 + end_time = time.time() + TIMEOUT + + done = False + while time.time() < end_time: + image_pub.publish(image) + rclpy.spin_once(self.node, timeout_sec=0.1) + + # If we have received a message on the output topic, break + if 'pynitros1_output_msg_ros' in received_messages: + done = True + break + + self.assertTrue(done, "Didn't receive output on pynitros1_output_msg_ros topic!") + + received_image = received_messages['pynitros1_output_msg_ros'] + + self.assertEqual(str(timestamp), str(received_image.header.stamp), + 'Timestamps do not match.') + + finally: + self.node.destroy_subscription(received_image_sub) + self.node.destroy_publisher(image_pub) diff --git a/isaac_ros_pynitros/test/isaac_ros_pynitros_image_test.py b/isaac_ros_pynitros/test/isaac_ros_pynitros_image_test.py new file mode 100644 index 0000000..b649ea5 --- /dev/null +++ b/isaac_ros_pynitros/test/isaac_ros_pynitros_image_test.py @@ -0,0 +1,158 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +"""Proof-of-Life test for the PyNITROS image type.""" + +import os +import pathlib +import subprocess +import time + +from isaac_ros_test import IsaacROSBaseTest, JSONConversion +import launch + +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy + +from sensor_msgs.msg import Image + + +@pytest.mark.rostest +def generate_test_description(): + """Generate launch description with all ROS 2 nodes for testing.""" + ptace_result = subprocess.run(['cat', '/proc/sys/kernel/yama/ptrace_scope'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + pidfd_getfd_result = subprocess.run(['grep', 'pidfd_getfd', '/proc/kallsyms'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + if (ptace_result.stdout.strip() == '0' and pidfd_getfd_result.returncode == 0): + IsaacROSPyNitrosTest.skip_test = False + pynitros_image_forward_node_1 = Node(name='pynitros_image_forward_node_1', + package='isaac_ros_pynitros', + namespace='pynitros', + executable='pynitros_image_forward_node', + parameters=[{ + 'enable_ros_subscribe': True, + 'enable_ros_publish': False + }], + remappings=[ + ('pynitros_input_msg', 'pynitros1_input_msg'), + ('pynitros_output_msg', 'pynitros1_output_msg'), + ('pynitros_output_msg_ros', + 'pynitros1_output_msg_ros') + ], + output='screen') + + pynitros_image_forward_node_2 = Node(name='pynitros_image_forward_node_2', + package='isaac_ros_pynitros', + executable='pynitros_image_forward_node', + namespace='pynitros', + parameters=[{ + 'enable_ros_subscribe': False, + 'enable_ros_publish': True + }], + remappings=[ + ('pynitros_input_msg', 'pynitros1_output_msg'), + ('pynitros_output_msg', 'pynitros2_output_msg'), + ('pynitros_output_msg_ros', + 'pynitros2_output_msg_ros') + ], + output='screen') + + return IsaacROSPyNitrosTest.generate_test_description([ + pynitros_image_forward_node_1, pynitros_image_forward_node_2, + launch.actions.TimerAction(period=2.5, actions=[launch_testing.actions.ReadyToTest()]) + ]) + else: + IsaacROSPyNitrosTest.skip_test = True + return IsaacROSPyNitrosTest.generate_test_description( + [launch_testing.actions.ReadyToTest()]) + + +class IsaacROSPyNitrosTest(IsaacROSBaseTest): + """Validate Nitros Bridge on Image type.""" + + filepath = pathlib.Path(os.path.dirname(__file__)) + + @IsaacROSBaseTest.for_each_test_case(subfolder='nitros_image') + def test_pynitros_image(self, test_folder) -> None: + if self.skip_test: + self.skipTest('No ptrace permission! Skipping test.') + else: + IsaacROSPyNitrosTest.DEFAULT_NAMESPACE = 'pynitros' + self.generate_namespace_lookup(['pynitros1_input_msg', 'pynitros2_output_msg_ros']) + received_messages = {} + + received_image_sub = self.create_logging_subscribers( + subscription_requests=[('pynitros2_output_msg_ros', Image)], + received_messages=received_messages) + + image_pub = self.node.create_publisher(Image, self.namespaces['pynitros1_input_msg'], + self.DEFAULT_QOS) + + try: + image = JSONConversion.load_image_from_json(test_folder / 'image.json') + timestamp = self.node.get_clock().now().to_msg() + image.header.stamp = timestamp + + # Wait at most TIMEOUT seconds for subscriber to respond + TIMEOUT = 30 + end_time = time.time() + TIMEOUT + + done = False + while time.time() < end_time: + image_pub.publish(image) + rclpy.spin_once(self.node, timeout_sec=0.1) + + # If we have received a message on the output topic, break + if 'pynitros2_output_msg_ros' in received_messages: + done = True + break + + self.assertTrue(done, "Didn't receive output on output_image topic!") + + received_image = received_messages['pynitros2_output_msg_ros'] + + self.assertEqual(str(timestamp), str(received_image.header.stamp), + 'Timestamps do not match.') + + self.assertEqual( + len(image.data), len(received_image.data), + 'Source and received image sizes do not match: ' + + f'{len(image.data)} != {len(received_image.data)}') + + # Make sure that the source and received images are the same + self.assertEqual( + received_image.height, image.height, + 'Source and received image heights do not match: ' + + f'{image.height} != {received_image.height}') + self.assertEqual( + received_image.width, image.width, + 'Source and received image widths do not match: ' + + f'{image.width} != {received_image.width}') + + for i in range(len(image.data)): + self.assertEqual(image.data[i], received_image.data[i], + 'Source and received image pixels do not match') + + finally: + self.node.destroy_subscription(received_image_sub) + self.node.destroy_publisher(image_pub) diff --git a/isaac_ros_pynitros/test/isaac_ros_pynitros_sync_test.py b/isaac_ros_pynitros/test/isaac_ros_pynitros_sync_test.py new file mode 100644 index 0000000..ea8db93 --- /dev/null +++ b/isaac_ros_pynitros/test/isaac_ros_pynitros_sync_test.py @@ -0,0 +1,161 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +"""Proof-of-Life test for the PyNITROS message filter.""" + +import os +import pathlib +import subprocess +import time + +from isaac_ros_test import IsaacROSBaseTest, JSONConversion +import launch + +from launch_ros.actions import Node +import launch_testing +import pytest +import rclpy + +from sensor_msgs.msg import CameraInfo, Image + + +@pytest.mark.rostest +def generate_test_description(): + """Generate launch description with all ROS 2 nodes for testing.""" + ptace_result = subprocess.run(['cat', '/proc/sys/kernel/yama/ptrace_scope'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + pidfd_getfd_result = subprocess.run(['grep', 'pidfd_getfd', '/proc/kallsyms'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + if (ptace_result.stdout.strip() == '0' and pidfd_getfd_result.returncode == 0): + IsaacROSPyNitrosTest.skip_test = False + pynitros_image_forward_node = Node(name='pynitros_image_forward_node', + package='isaac_ros_pynitros', + namespace='pynitros', + executable='pynitros_image_forward_node', + parameters=[{ + 'enable_ros_subscribe': True, + 'enable_ros_publish': False + }], + remappings=[ + ('pynitros_input_msg', 'pynitros1_input_msg'), + ('pynitros_output_msg', 'pynitros1_output_msg'), + ], + output='screen') + pynitros_sync_node = Node(name='pynitros_sync_node', + package='isaac_ros_pynitros', + namespace='pynitros', + executable='pynitros_message_filter_sync_node', + parameters=[{ + 'enable_ros_subscribe': False, + 'enable_ros_publish': True + }], + remappings=[ + ('image', 'pynitros1_output_msg') + ], + output='screen') + + return IsaacROSPyNitrosTest.generate_test_description([ + pynitros_image_forward_node, + pynitros_sync_node, + launch.actions.TimerAction(period=2.5, actions=[launch_testing.actions.ReadyToTest()]) + ]) + else: + IsaacROSPyNitrosTest.skip_test = True + return IsaacROSPyNitrosTest.generate_test_description( + [launch_testing.actions.ReadyToTest()]) + + +class IsaacROSPyNitrosTest(IsaacROSBaseTest): + """Validate Nitros Bridge on Image type.""" + + filepath = pathlib.Path(os.path.dirname(__file__)) + + @IsaacROSBaseTest.for_each_test_case(subfolder='nitros_image') + def test_pynitros_image(self, test_folder) -> None: + if self.skip_test: + self.skipTest('No ptrace permission! Skipping test.') + else: + IsaacROSPyNitrosTest.DEFAULT_NAMESPACE = 'pynitros' + self.generate_namespace_lookup(['pynitros1_input_msg', + 'camera_info', + 'synced_output_ros']) + received_messages = {} + + received_image_sub = self.create_logging_subscribers( + subscription_requests=[('synced_output_ros', Image)], + received_messages=received_messages) + + image_pub = self.node.create_publisher(Image, + self.namespaces['pynitros1_input_msg'], + self.DEFAULT_QOS) + camera_info_pub = self.node.create_publisher(CameraInfo, + self.namespaces['camera_info'], + self.DEFAULT_QOS) + try: + image = JSONConversion.load_image_from_json(test_folder / 'image.json') + timestamp = self.node.get_clock().now().to_msg() + image.header.stamp = timestamp + + camera_info = CameraInfo() + camera_info.header.stamp = timestamp + # Wait at most TIMEOUT seconds for subscriber to respond + TIMEOUT = 30 + end_time = time.time() + TIMEOUT + + done = False + while time.time() < end_time: + image_pub.publish(image) + camera_info_pub.publish(camera_info) + rclpy.spin_once(self.node, timeout_sec=0.1) + + # If we have received a message on the output topic, break + if 'synced_output_ros' in received_messages: + done = True + break + + self.assertTrue(done, "Didn't receive output on output_image topic!") + + received_image = received_messages['synced_output_ros'] + + self.assertEqual(str(timestamp), str(received_image.header.stamp), + 'Timestamps do not match.') + + self.assertEqual( + len(image.data), len(received_image.data), + 'Source and received image sizes do not match: ' + + f'{len(image.data)} != {len(received_image.data)}') + + # Make sure that the source and received images are the same + self.assertEqual( + received_image.height, image.height, + 'Source and received image heights do not match: ' + + f'{image.height} != {received_image.height}') + self.assertEqual( + received_image.width, image.width, + 'Source and received image widths do not match: ' + + f'{image.width} != {received_image.width}') + + for i in range(len(image.data)): + self.assertEqual(image.data[i], received_image.data[i], + 'Source and received image pixels do not match') + + finally: + self.node.destroy_subscription(received_image_sub) + self.node.destroy_publisher(image_pub) diff --git a/isaac_ros_pynitros/test/isaac_ros_pynitros_tensor_list_test.py b/isaac_ros_pynitros/test/isaac_ros_pynitros_tensor_list_test.py new file mode 100644 index 0000000..d9b6cb4 --- /dev/null +++ b/isaac_ros_pynitros/test/isaac_ros_pynitros_tensor_list_test.py @@ -0,0 +1,175 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 +"""Proof-of-Life test for the PyNITROS tensor list type.""" + +import os +import pathlib +import subprocess +import time + +from isaac_ros_tensor_list_interfaces.msg import Tensor, TensorList, TensorShape +from isaac_ros_test import IsaacROSBaseTest +import launch + +from launch_ros.actions import Node +import launch_testing +import numpy as np +import pytest +import rclpy + + +@pytest.mark.rostest +def generate_test_description(): + """Generate launch description with all ROS 2 nodes for testing.""" + ptace_result = subprocess.run(['cat', '/proc/sys/kernel/yama/ptrace_scope'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + pidfd_getfd_result = subprocess.run(['grep', 'pidfd_getfd', '/proc/kallsyms'], + stdout=subprocess.PIPE, + stderr=subprocess.PIPE, + text=True) + if (ptace_result.stdout.strip() == '0' and pidfd_getfd_result.returncode == 0): + IsaacROSPyNitrosTest.skip_test = False + pynitros_tensor_list_forward_node_1 = Node( + name='pynitros_tensor_list_forward_node_1', + package='isaac_ros_pynitros', + namespace='pynitros', + executable='pynitros_tensor_list_forward_node', + parameters=[{ + 'enable_ros_subscribe': True, + 'enable_ros_publish': False + }], + remappings=[('pynitros_input_msg', 'pynitros1_input_msg'), + ('pynitros_output_msg', 'pynitros1_output_msg'), + ('pynitros_output_msg_ros', 'pynitros1_output_msg_ros')], + output='screen') + + pynitros_tensor_list_forward_node_2 = Node( + name='pynitros_tensor_list_forward_node_2', + package='isaac_ros_pynitros', + executable='pynitros_tensor_list_forward_node', + namespace='pynitros', + parameters=[{ + 'enable_ros_subscribe': False, + 'enable_ros_publish': True + }], + remappings=[('pynitros_input_msg', 'pynitros1_output_msg'), + ('pynitros_output_msg', 'pynitros2_output_msg'), + ('pynitros_output_msg_ros', 'pynitros2_output_msg_ros')], + output='screen') + + return IsaacROSPyNitrosTest.generate_test_description([ + pynitros_tensor_list_forward_node_1, pynitros_tensor_list_forward_node_2, + launch.actions.TimerAction(period=2.5, actions=[launch_testing.actions.ReadyToTest()]) + ]) + else: + IsaacROSPyNitrosTest.skip_test = True + return IsaacROSPyNitrosTest.generate_test_description( + [launch_testing.actions.ReadyToTest()]) + + +class IsaacROSPyNitrosTest(IsaacROSBaseTest): + """Validate Nitros Bridge on Tensor List type.""" + + filepath = pathlib.Path(os.path.dirname(__file__)) + + @IsaacROSBaseTest.for_each_test_case(subfolder='nitros_image') + def test_pynitros_tensor_list(self, test_folder) -> None: + if self.skip_test: + self.skipTest('No ptrace permission! Skipping test.') + else: + IsaacROSPyNitrosTest.DEFAULT_NAMESPACE = 'pynitros' + self.generate_namespace_lookup(['pynitros1_input_msg', 'pynitros2_output_msg_ros']) + received_messages = {} + + received_tensor_list_sub = self.create_logging_subscribers( + subscription_requests=[('pynitros2_output_msg_ros', TensorList)], + received_messages=received_messages) + + tensor_list_pub = self.node.create_publisher(TensorList, + self.namespaces['pynitros1_input_msg'], + self.DEFAULT_QOS) + + try: + DATA_TYPE = 9 + INPUT_TENSOR_DIMENSIONS = [1, 3, 100, 100] + INPUT_TENSOR_NAME = 'input' + INPUT_TENSOR_STRIDE = 4 + + tensor_list = TensorList() + tensor = Tensor() + tensor_shape = TensorShape() + + tensor_shape.rank = len(INPUT_TENSOR_DIMENSIONS) + tensor_shape.dims = INPUT_TENSOR_DIMENSIONS + + tensor.shape = tensor_shape + tensor.name = INPUT_TENSOR_NAME + tensor.data_type = DATA_TYPE + data_length = INPUT_TENSOR_STRIDE * np.prod(INPUT_TENSOR_DIMENSIONS) + tensor.data = np.random.randint(256, size=data_length).tolist() + + tensor_list.tensors = [tensor, tensor] + timestamp = self.node.get_clock().now().to_msg() + tensor_list.header.stamp = timestamp + + # Wait at most TIMEOUT seconds for subscriber to respond + TIMEOUT = 30 + end_time = time.time() + TIMEOUT + + done = False + while time.time() < end_time: + tensor_list_pub.publish(tensor_list) + rclpy.spin_once(self.node, timeout_sec=0.1) + + # If we have received a message on the output topic, break + if 'pynitros2_output_msg_ros' in received_messages: + done = True + break + + self.assertTrue(done, "Didn't receive output on output tensor list topic!") + + received_tensor_list = received_messages['pynitros2_output_msg_ros'] + self.assertEqual(len(tensor_list.tensors), len(received_tensor_list.tensors), + 'Source and received tensor list size do not match') + + for i in range(len(tensor_list.tensors)): + source_tensor = tensor_list.tensors[i] + received_tensor = received_tensor_list.tensors[i] + self.assertEqual(source_tensor.name, received_tensor.name, + 'Source and received tensor names do not match') + self.assertEqual(source_tensor.name, received_tensor.name, + 'Source and received tensor names do not match') + self.assertEqual(source_tensor.data_type, received_tensor.data_type, + 'Source and received tensor data types do not match') + self.assertEqual(source_tensor.shape.rank, received_tensor.shape.rank, + 'Source and received tensor ranks do not match') + self.assertEqual(source_tensor.shape.dims, received_tensor.shape.dims, + 'Source and received tensor dimensions do not match') + self.assertEqual(len(source_tensor.data), len(received_tensor.data), + 'Source and received tensor data do not match') + self.assertEqual(str(timestamp), str(received_tensor_list.header.stamp), + 'Timestamps do not match.') + + for j in range(len(source_tensor.data)): + self.assertEqual(source_tensor.data[j], received_tensor.data[j], + 'Source and received tensor pixels do not match') + + finally: + self.node.destroy_subscription(received_tensor_list_sub) + self.node.destroy_publisher(tensor_list_pub) diff --git a/isaac_ros_pynitros/test/test_cases/nitros_image/profile/NVIDIAprofile.png b/isaac_ros_pynitros/test/test_cases/nitros_image/profile/NVIDIAprofile.png new file mode 100644 index 0000000..0e0ae64 --- /dev/null +++ b/isaac_ros_pynitros/test/test_cases/nitros_image/profile/NVIDIAprofile.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aa345be1c5972fa1ad601db83ec2fd56c5fb428e09de166b76b72d266c4cb346 +size 94919 diff --git a/isaac_ros_pynitros/test/test_cases/nitros_image/profile/image.json b/isaac_ros_pynitros/test/test_cases/nitros_image/profile/image.json new file mode 100644 index 0000000..faaec9d --- /dev/null +++ b/isaac_ros_pynitros/test/test_cases/nitros_image/profile/image.json @@ -0,0 +1,4 @@ +{ + "image": "NVIDIAprofile.png", + "encoding": "bgr8" +} \ No newline at end of file diff --git a/isaac_ros_pynitros/test/test_copyright.py b/isaac_ros_pynitros/test/test_copyright.py new file mode 100644 index 0000000..4670f4c --- /dev/null +++ b/isaac_ros_pynitros/test/test_copyright.py @@ -0,0 +1,26 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from ament_copyright.main import main +import pytest + + +@pytest.mark.copyright +@pytest.mark.linter +def test_copyright(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found errors' diff --git a/isaac_ros_pynitros/test/test_flake8.py b/isaac_ros_pynitros/test/test_flake8.py new file mode 100644 index 0000000..e8f313a --- /dev/null +++ b/isaac_ros_pynitros/test/test_flake8.py @@ -0,0 +1,28 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from ament_flake8.main import main_with_errors +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + rc, errors = main_with_errors(argv=[]) + assert rc == 0, \ + 'Found %d code style errors / warnings:\n' % len(errors) + \ + '\n'.join(errors) diff --git a/isaac_ros_pynitros/test/test_pep257.py b/isaac_ros_pynitros/test/test_pep257.py new file mode 100644 index 0000000..179e592 --- /dev/null +++ b/isaac_ros_pynitros/test/test_pep257.py @@ -0,0 +1,26 @@ +# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES +# Copyright (c) 2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# SPDX-License-Identifier: Apache-2.0 + +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found code style errors / warnings'