diff --git a/rviz_common/src/rviz_common/load_resource.cpp b/rviz_common/src/rviz_common/load_resource.cpp index 34938504d..7198f18e9 100644 --- a/rviz_common/src/rviz_common/load_resource.cpp +++ b/rviz_common/src/rviz_common/load_resource.cpp @@ -47,18 +47,11 @@ namespace rviz_common { -resource_retriever::MemoryResource getResource(const std::string & resource_path) +resource_retriever::ResourceSharedPtr getResource(const std::string & resource_path) { + RVIZ_COMMON_LOG_DEBUG("rviz_common::getResource() loading resource: " + resource_path); resource_retriever::Retriever retriever; - resource_retriever::MemoryResource res; - try { - res = retriever.get(resource_path); - } catch (resource_retriever::Exception & e) { - RVIZ_COMMON_LOG_DEBUG(e.what()); - return resource_retriever::MemoryResource(); - } - - return res; + return retriever.get_shared(resource_path); } QPixmap loadPixmap(QString url, bool fill_cache) @@ -73,8 +66,8 @@ QPixmap loadPixmap(QString url, bool fill_cache) RVIZ_COMMON_LOG_DEBUG("Load pixmap at " + url.toStdString()); auto image = getResource(url.toStdString()); - if (image.size != 0) { - if (!pixmap.loadFromData(image.data.get(), static_cast(image.size))) { + if (image != nullptr && !image->data.empty()) { + if (!pixmap.loadFromData(image->data.data(), static_cast(image->data.size()))) { RVIZ_COMMON_LOG_ERROR("Could not load pixmap " + url.toStdString()); } } diff --git a/rviz_default_plugins/CMakeLists.txt b/rviz_default_plugins/CMakeLists.txt index 1bdc96b17..89cf4f72e 100644 --- a/rviz_default_plugins/CMakeLists.txt +++ b/rviz_default_plugins/CMakeLists.txt @@ -73,6 +73,7 @@ find_package(pluginlib REQUIRED) find_package(point_cloud_transport REQUIRED) find_package(rclcpp REQUIRED) find_package(resource_retriever REQUIRED) +find_package(rviz_resource_interfaces REQUIRED) find_package(sensor_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) @@ -230,6 +231,7 @@ set(rviz_default_plugins_source_files src/rviz_default_plugins/view_controllers/orbit/orbit_view_controller.cpp src/rviz_default_plugins/view_controllers/ortho/fixed_orientation_ortho_view_controller.cpp src/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller.cpp + src/rviz_default_plugins/ros_resource_retriever.cpp ) add_library(rviz_default_plugins SHARED @@ -262,11 +264,12 @@ target_link_libraries(rviz_default_plugins PUBLIC tf2_ros::tf2_ros urdf::urdf ${visualization_msgs_TARGETS} + resource_retriever::resource_retriever + ${rviz_resource_interfaces_TARGETS} ) target_link_libraries(rviz_default_plugins PRIVATE gz-math::core - resource_retriever::resource_retriever ) # Causes the visibility macros to use dllexport rather than dllimport, diff --git a/rviz_default_plugins/icons/classes/AxesColor.svg b/rviz_default_plugins/icons/classes/AxesColor.svg new file mode 100644 index 000000000..1400b5e46 --- /dev/null +++ b/rviz_default_plugins/icons/classes/AxesColor.svg @@ -0,0 +1,6 @@ + + + + + + diff --git a/rviz_default_plugins/icons/classes/AxisColor.svg b/rviz_default_plugins/icons/classes/AxisColor.svg new file mode 100644 index 000000000..1400b5e46 --- /dev/null +++ b/rviz_default_plugins/icons/classes/AxisColor.svg @@ -0,0 +1,6 @@ + + + + + + diff --git a/rviz_default_plugins/icons/classes/FlatColor.svg b/rviz_default_plugins/icons/classes/FlatColor.svg new file mode 100644 index 000000000..3f059a1c5 --- /dev/null +++ b/rviz_default_plugins/icons/classes/FlatColor.svg @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/rviz_default_plugins/icons/classes/Intensity.svg b/rviz_default_plugins/icons/classes/Intensity.svg new file mode 100644 index 000000000..f17b607af --- /dev/null +++ b/rviz_default_plugins/icons/classes/Intensity.svg @@ -0,0 +1,6 @@ + + + + + + \ No newline at end of file diff --git a/rviz_default_plugins/icons/classes/RGB8.svg b/rviz_default_plugins/icons/classes/RGB8.svg new file mode 100644 index 000000000..3f059a1c5 --- /dev/null +++ b/rviz_default_plugins/icons/classes/RGB8.svg @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/rviz_default_plugins/icons/classes/RGBF32.svg b/rviz_default_plugins/icons/classes/RGBF32.svg new file mode 100644 index 000000000..3f059a1c5 --- /dev/null +++ b/rviz_default_plugins/icons/classes/RGBF32.svg @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/rviz_default_plugins/icons/classes/XYZ.svg b/rviz_default_plugins/icons/classes/XYZ.svg new file mode 100644 index 000000000..1400b5e46 --- /dev/null +++ b/rviz_default_plugins/icons/classes/XYZ.svg @@ -0,0 +1,6 @@ + + + + + + diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/marker/marker_common.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/marker/marker_common.hpp index f1e883ba0..b01cc5cbb 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/marker/marker_common.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/marker/marker_common.hpp @@ -44,6 +44,7 @@ #include // NOLINT: cpplint is unable to handle the include order here +#include "resource_retriever/retriever.hpp" #include "visualization_msgs/msg/marker.hpp" #include "visualization_msgs/msg/marker_array.hpp" @@ -122,6 +123,8 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC MarkerCommon void setMarkerStatus(MarkerID id, StatusLevel level, const std::string & text); void deleteMarkerStatus(MarkerID id); + resource_retriever::Retriever * getResourceRetriever(); + private: /** @brief Delete all the markers within the given namespace. */ void deleteMarkersInNamespace(const std::string & ns); @@ -175,6 +178,8 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC MarkerCommon rviz_common::DisplayContext * context_; Ogre::SceneNode * scene_node_; + resource_retriever::Retriever retriever_; + friend class MarkerNamespace; }; diff --git a/rviz_default_plugins/include/rviz_default_plugins/robot/robot_link.hpp b/rviz_default_plugins/include/rviz_default_plugins/robot/robot_link.hpp index 0ab185838..8733e4b05 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/robot/robot_link.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/robot/robot_link.hpp @@ -53,8 +53,9 @@ #include // can be replaced later by urdf_model/types.h -#include "rviz_rendering/objects/object.hpp" +#include "resource_retriever/retriever.hpp" #include "rviz_common/interaction/forwards.hpp" +#include "rviz_rendering/objects/object.hpp" #include "rviz_default_plugins/robot/robot_element_base_class.hpp" #include "rviz_default_plugins/visibility_control.hpp" @@ -235,6 +236,8 @@ private Q_SLOTS: Ogre::SceneManager * scene_manager_; rviz_common::DisplayContext * context_; + mutable resource_retriever::Retriever retriever_; + std::string parent_joint_name_; std::vector child_joint_names_; diff --git a/rviz_default_plugins/include/rviz_default_plugins/ros_resource_retriever.hpp b/rviz_default_plugins/include/rviz_default_plugins/ros_resource_retriever.hpp new file mode 100644 index 000000000..f6c62220b --- /dev/null +++ b/rviz_default_plugins/include/rviz_default_plugins/ros_resource_retriever.hpp @@ -0,0 +1,88 @@ +// Copyright 2025 Open Source Robotics Foundation, Inc. +// 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 copyright holder 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 HOLDER 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. + +#ifndef RVIZ_DEFAULT_PLUGINS__ROS_RESOURCE_RETRIEVER_HPP_ +#define RVIZ_DEFAULT_PLUGINS__ROS_RESOURCE_RETRIEVER_HPP_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/// Plugin for resource_retriever that loads resources from a ROS interface. +class RosResourceRetriever : public resource_retriever::plugins::RetrieverPlugin +{ + using GetResource = rviz_resource_interfaces::srv::GetResource; + + RosResourceRetriever() = delete; + + static constexpr std::string_view service_name = "/rviz/get_resource"; + +public: + explicit RosResourceRetriever( + rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr weak_ros_iface); + + ~RosResourceRetriever() override = default; + + std::string name() override; + + bool can_handle(const std::string & url) override; + + resource_retriever::ResourceSharedPtr get_shared(const std::string & url) override; + +private: + // It should be safe to keep a shared pointer to the node here, because this + // plugin will be destroyed with the resource retriever in the marker display, + // which should be destroyed along before the node abstraction is destroyed. + // Also, since we're keeping callback groups and clients around, we need to + // ensure the node stays around too. + rclcpp::Node::SharedPtr ros_node_; + rclcpp::CallbackGroup::SharedPtr callback_group_; + rclcpp::Client::SharedPtr client_; + rclcpp::executors::SingleThreadedExecutor executor_; + rclcpp::Logger logger_; + + // Map of the resource path to a pair with the etag value and the memory resource that is cached. + std::unordered_map< + std::string, + std::pair + > cached_resources_; +}; + +#endif // RVIZ_DEFAULT_PLUGINS__ROS_RESOURCE_RETRIEVER_HPP_ diff --git a/rviz_default_plugins/package.xml b/rviz_default_plugins/package.xml index 3aae1cbe8..d9db2662f 100644 --- a/rviz_default_plugins/package.xml +++ b/rviz_default_plugins/package.xml @@ -48,6 +48,7 @@ point_cloud_transport rclcpp resource_retriever + rviz_resource_interfaces rviz_common rviz_rendering tf2 diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/marker_common.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/marker_common.cpp index 3c7211629..ace8969be 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/marker_common.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/marker_common.cpp @@ -28,17 +28,18 @@ // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. - #include "rviz_default_plugins/displays/marker/marker_common.hpp" +#include #include #include #include #include +#include #include #include -#include // NOLINT: cpplint is unable to handle the include order here +#include "QString" #include "rclcpp/duration.hpp" @@ -49,6 +50,8 @@ #include "rviz_default_plugins/displays/marker/markers/marker_factory.hpp" +#include "rviz_default_plugins/ros_resource_retriever.hpp" + namespace rviz_default_plugins { namespace displays @@ -72,6 +75,13 @@ void MarkerCommon::initialize(rviz_common::DisplayContext * context, Ogre::Scene context_ = context; scene_node_ = scene_node; + resource_retriever::RetrieverVec plugins; + plugins.push_back(std::make_shared(context_->getRosNodeAbstraction())); + for (const auto & plugin : resource_retriever::default_plugins()) { + plugins.push_back(plugin); + } + retriever_ = resource_retriever::Retriever(plugins); + namespace_config_enabled_state_.clear(); marker_factory_->initialize(this, context_, scene_node_); @@ -148,6 +158,11 @@ void MarkerCommon::deleteMarkerStatus(MarkerID id) display_->deleteStatusStd(marker_name); } +resource_retriever::Retriever * MarkerCommon::getResourceRetriever() +{ + return &this->retriever_; +} + void MarkerCommon::addMessage(const visualization_msgs::msg::Marker::ConstSharedPtr marker) { std::unique_lock lock(queue_mutex_); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/mesh_resource_marker.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/mesh_resource_marker.cpp index 8f92c7cee..8a0eaa2d8 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/mesh_resource_marker.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/mesh_resource_marker.cpp @@ -109,7 +109,11 @@ void MeshResourceMarker::onNewMessage( return; } - if (!rviz_rendering::loadMeshFromResource(new_message->mesh_resource)) { + if ( + !rviz_rendering::loadMeshFromResource( + owner_->getResourceRetriever(), + new_message->mesh_resource)) + { printMeshLoadingError(new_message); return; } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/triangle_list_marker.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/triangle_list_marker.cpp index 4034e51d5..c9b88c6c0 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/triangle_list_marker.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/triangle_list_marker.cpp @@ -44,7 +44,6 @@ #include #include -#include "resource_retriever/retriever.hpp" #include "rviz_rendering/mesh_loader.hpp" #include "rviz_rendering/material_manager.hpp" #include "rviz_common/display_context.hpp" diff --git a/rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp b/rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp index d6bc91445..f84d4b306 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp @@ -78,6 +78,8 @@ #include "rviz_common/properties/vector_property.hpp" #include "rviz_common/interaction/selection_manager.hpp" +#include "rviz_default_plugins/ros_resource_retriever.hpp" + #define RVIZ_RESOURCE_GROUP "rviz_rendering" using rviz_rendering::Axes; @@ -226,6 +228,18 @@ RobotLink::RobotLink( color_material_ = rviz_rendering::MaterialManager::createMaterialWithLighting(color_material_name); + resource_retriever::RetrieverVec plugins; + if (context_ != nullptr) { + std::shared_ptr node_ptr = context_->getRosNodeAbstraction().lock(); + if (node_ptr != nullptr) { + plugins.push_back(std::make_shared(context_->getRosNodeAbstraction())); + } + } + for (const auto & plugin : resource_retriever::default_plugins()) { + plugins.push_back(plugin); + } + retriever_ = resource_retriever::Retriever(plugins); + // create the ogre objects to display if (visual) { createVisual(link); @@ -673,7 +687,7 @@ Ogre::Entity * RobotLink::createEntityForGeometryElement( const std::string & model_name = mesh.filename; try { - if (rviz_rendering::loadMeshFromResource(model_name) == nullptr) { + if (rviz_rendering::loadMeshFromResource(&retriever_, model_name) == nullptr) { addError("Could not load mesh resource '%s'", model_name.c_str()); } else { entity = scene_manager_->createEntity(entity_name, model_name); @@ -801,16 +815,10 @@ void RobotLink::loadMaterialFromTexture( { std::string filename = visual->material->texture_filename; if (!Ogre::TextureManager::getSingleton().resourceExists(filename, RVIZ_RESOURCE_GROUP)) { - resource_retriever::Retriever retriever; - resource_retriever::MemoryResource res; - try { - res = retriever.get(filename); - } catch (resource_retriever::Exception & e) { - RVIZ_COMMON_LOG_ERROR(e.what()); - } - - if (res.size != 0) { - Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size)); + auto res = retriever_.get_shared(filename); + if (nullptr != res && !res->data.empty()) { + Ogre::DataStreamPtr stream( + new Ogre::MemoryDataStream(const_cast(res->data.data()), res->data.size())); Ogre::Image image; std::string extension = QFileInfo(QString::fromStdString(filename)).completeSuffix().toStdString(); diff --git a/rviz_default_plugins/src/rviz_default_plugins/ros_resource_retriever.cpp b/rviz_default_plugins/src/rviz_default_plugins/ros_resource_retriever.cpp new file mode 100644 index 000000000..206248e0e --- /dev/null +++ b/rviz_default_plugins/src/rviz_default_plugins/ros_resource_retriever.cpp @@ -0,0 +1,180 @@ +// Copyright 2025 Open Source Robotics Foundation, Inc. +// 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 copyright holder 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 HOLDER 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. + +#include "rviz_default_plugins/ros_resource_retriever.hpp" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +rclcpp::Node::SharedPtr +get_ros_node_from( + const rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr & weak_ros_iface) +{ + auto ros_iface = weak_ros_iface.lock(); + if (!ros_iface) { + throw std::invalid_argument("ROS node abstraction interface not valid"); + } + return ros_iface->get_raw_node(); +} + +RosResourceRetriever::RosResourceRetriever( + rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr weak_ros_iface) +: ros_node_(get_ros_node_from(weak_ros_iface)), + logger_(ros_node_->get_logger().get_child("ros_resource_retriever")) +{ + this->logger_ = ros_node_->get_logger().get_child("ros_resource_retriever"); + + // Create a client with a custom callback group that will not be included in the main executor. + callback_group_ = ros_node_->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive, + false); + this->client_ = ros_node_->create_client( + service_name.data(), + rclcpp::ServicesQoS(), + callback_group_); + + // Add the callback group to the executor so we can spin on it later. + executor_.add_callback_group(callback_group_, ros_node_->get_node_base_interface()); +} + +std::string RosResourceRetriever::name() +{ + return "rviz_default_plugins::RosResourceRetriever"; +} + +bool RosResourceRetriever::can_handle(const std::string & url) +{ + return !url.empty(); +} + +resource_retriever::ResourceSharedPtr +RosResourceRetriever::get_shared(const std::string & url) +{ + RCLCPP_DEBUG(this->logger_, "Getting resource: %s", url.c_str()); + + // First check for a cache hit. + std::string etag; + auto it = cached_resources_.find(url); + if (it != cached_resources_.end()) { + etag = it->second.first; + // If the etag was not set, then the server doesn't do caching, just return what we have. + if (etag.empty()) { + RCLCPP_DEBUG(this->logger_, "Resource '%s' cached without etag, returning.", url.c_str()); + return it->second.second; + } + } + + // Request the resource with an etag, if it is set. + RCLCPP_DEBUG( + this->logger_, + "Requesting resource '%s'%s.", + url.c_str(), + etag.empty() ? "" : (" with etag '" + etag + "'").c_str()); + auto req = std::make_shared(); + req->path = url; + req->etag = etag; + auto result = this->client_->async_send_request(req); + + using namespace std::chrono_literals; + auto maximum_wait_time = 3s; + + if (executor_.spin_until_future_complete(result, maximum_wait_time) != + rclcpp::FutureReturnCode::SUCCESS) + { + RCLCPP_ERROR(this->logger_, "Timeout: Not able to call the service %s", service_name.data()); + this->client_->remove_pending_request(result); + return nullptr; + } + + auto res = result.get(); + std::shared_ptr memory_resource = nullptr; + switch (res->status_code) { + case rviz_resource_interfaces::srv::GetResource::Response::OK: + RCLCPP_DEBUG( + this->logger_, + "Received resource '%s' with etag '%s', caching and returning %zu bytes.", + res->expanded_path.c_str(), + res->etag.c_str(), + res->body.size()); + memory_resource = + std::make_shared(url, res->expanded_path, res->body); + cached_resources_.insert({url, {res->etag, memory_resource}}); + return memory_resource; + case rviz_resource_interfaces::srv::GetResource::Response::NOT_MODIFIED: + RCLCPP_DEBUG( + this->logger_, + "Resource '%s' with etag '%s' was not modified, returning cached value.", + res->expanded_path.c_str(), + res->etag.c_str()); + if (etag != res->etag) { + RCLCPP_WARN( + this->logger_, + "Unexpectedly got a different etag values ('%s' vs '%s') for resource '%s' " + "with a NOT_MODIFIED status_code. This will not stop the resource " + "from loading, but indicates some issue with the caching logic.", + res->expanded_path.c_str(), + etag.c_str(), + res->etag.c_str()); + } + return it->second.second; + break; + case rviz_resource_interfaces::srv::GetResource::Response::ERROR: + RCLCPP_DEBUG( + this->logger_, + "Received an unexpected error when getting resource '%s': %s", + url.c_str(), + res->error_reason.c_str()); + return nullptr; + break; + default: + RCLCPP_ERROR( + this->logger_, + "Unexpected status_code from resource ROS Service '%s' for resource '%s': %" PRId32, + service_name.data(), + url.c_str(), + res->status_code); + return nullptr; + break; + } +} diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.hpp b/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.hpp index c6b0c7f60..fd211df6e 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.hpp @@ -49,6 +49,10 @@ #include "../mock_selection_manager.hpp" #include "../mock_handler_manager.hpp" +#include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp" +#include "rviz_common/ros_integration/ros_client_abstraction_iface.hpp" +#include "rviz_common/ros_integration/ros_client_abstraction.hpp" + class DisplayTestFixture : public testing::Test { public: @@ -73,7 +77,7 @@ class DisplayTestFixture : public testing::Test std::shared_ptr handler_manager_; std::shared_ptr clock_; - std::string fixed_frame = "fixed_frame"; + std::string fixed_frame{"fixed_frame"}; }; diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp index 12aaca5e3..731af3d4f 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp @@ -60,14 +60,42 @@ class MarkerCommonFixture : public DisplayTestFixture { public: MarkerCommonFixture() + : DisplayTestFixture() { + EXPECT_CALL(*context_, getRosNodeAbstraction()).WillRepeatedly( + testing::Invoke([]() { + return rviz_ros_node_; + })); + display_ = std::make_unique(); + scene_manager_ = Ogre::Root::getSingletonPtr()->createSceneManager(); + auto scene_node = scene_manager_->getRootSceneNode()->createChildSceneNode(); common_ = std::make_unique(display_.get()); common_->initialize(context_.get(), scene_node); } + static void TearDownTestCase() + { + DisplayTestFixture::TearDownTestCase(); + rclcpp::shutdown(); + } + + static void SetUpTestCase() + { + testing_environment_ = std::make_shared(); + testing_environment_->setUpOgreTestEnvironment(); + + ros_client_abstraction_ = + std::make_unique(); + int argc = 1; + const auto arg0 = "MockDisplayContext"; + char * argv0 = const_cast(arg0); + char ** argv = &argv0; + rviz_ros_node_ = ros_client_abstraction_->init(argc, argv, "rviz", false /* anonymous_name */); + } + ~MarkerCommonFixture() override { common_.reset(); @@ -75,8 +103,15 @@ class MarkerCommonFixture : public DisplayTestFixture std::unique_ptr common_; std::unique_ptr display_; + static rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr rviz_ros_node_; + static std::unique_ptr + ros_client_abstraction_; }; +rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr MarkerCommonFixture::rviz_ros_node_; +std::unique_ptr MarkerCommonFixture:: +ros_client_abstraction_ = nullptr; + visualization_msgs::msg::Marker::SharedPtr createSharedPtrMessage( int32_t action, int32_t type, int id = 0) { diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.cpp index 03f9050fd..bb85720dc 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.cpp @@ -34,10 +34,36 @@ #include MarkersTestFixture::MarkersTestFixture() +: DisplayTestFixture() { + EXPECT_CALL(*context_, getRosNodeAbstraction()).WillRepeatedly( + testing::Invoke([]() { + return rviz_ros_node_; + })); display_ = std::make_unique(); scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); marker_common_ = std::make_unique(display_.get()); marker_common_->initialize(context_.get(), scene_node_); } + +void MarkersTestFixture::SetUpTestCase() +{ + DisplayTestFixture::SetUpTestCase(); + ros_client_abstraction_ = std::make_unique(); + int argc = 1; + const auto arg0 = "MockDisplayContext"; + char * argv0 = const_cast(arg0); + char ** argv = &argv0; + rviz_ros_node_ = ros_client_abstraction_->init(argc, argv, "rviz", false /* anonymous_name */); +} + +void MarkersTestFixture::TearDownTestCase() +{ + DisplayTestFixture::TearDownTestCase(); + rclcpp::shutdown(); +} + +rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr MarkersTestFixture::rviz_ros_node_; +std::unique_ptr MarkersTestFixture:: +ros_client_abstraction_ = nullptr; diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.hpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.hpp index 1f5025ecc..d0842253c 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.hpp @@ -63,10 +63,15 @@ class MarkersTestFixture : public DisplayTestFixture scene_node_); } + static void TearDownTestCase(); + static void SetUpTestCase(); + std::unique_ptr display_; std::unique_ptr marker_common_; Ogre::SceneNode * scene_node_; - + static rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr rviz_ros_node_; + static std::unique_ptr + ros_client_abstraction_; std::unique_ptr marker_; }; diff --git a/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp index de0b08be2..41da87cb2 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp @@ -84,8 +84,10 @@ class RobotTestFixture : public Test EXPECT_CALL(*context_, getHandlerManager()).WillRepeatedly(Return(handle_manager_)); resource_retriever::Retriever retriever; - auto file = retriever.get("package://rviz_default_plugins/test_meshes/test.urdf"); - std::string string(reinterpret_cast(file.data.get()), file.size); + auto res = retriever.get_shared("package://rviz_default_plugins/test_meshes/test.urdf"); + std::string string( + reinterpret_cast(const_cast(res->data.data())), + res->data.size()); urdf_model_.initString(string); parent_ = std::make_shared(); diff --git a/rviz_rendering/include/rviz_rendering/mesh_loader.hpp b/rviz_rendering/include/rviz_rendering/mesh_loader.hpp index c8c3187aa..d382dfe64 100644 --- a/rviz_rendering/include/rviz_rendering/mesh_loader.hpp +++ b/rviz_rendering/include/rviz_rendering/mesh_loader.hpp @@ -37,10 +37,15 @@ #include "rviz_rendering/visibility_control.hpp" +#include "resource_retriever/retriever.hpp" + namespace rviz_rendering { + RVIZ_RENDERING_PUBLIC -Ogre::MeshPtr loadMeshFromResource(const std::string & resource_path); +Ogre::MeshPtr loadMeshFromResource( + resource_retriever::Retriever * retriever, + const std::string & resource_uri); } // namespace rviz_rendering diff --git a/rviz_rendering/src/rviz_rendering/mesh_loader.cpp b/rviz_rendering/src/rviz_rendering/mesh_loader.cpp index 4c8658eb0..cde4337e3 100644 --- a/rviz_rendering/src/rviz_rendering/mesh_loader.cpp +++ b/rviz_rendering/src/rviz_rendering/mesh_loader.cpp @@ -63,6 +63,8 @@ #include "assimp/IOSystem.h" #endif +#include "resource_retriever/memory_resource.hpp" +#include "resource_retriever/plugins/retriever_plugin.hpp" #include "resource_retriever/retriever.hpp" #include "mesh_loader_helpers/assimp_loader.hpp" @@ -71,55 +73,49 @@ namespace rviz_rendering { -resource_retriever::MemoryResource getResource(const std::string & resource_path) +Ogre::MeshPtr loadMeshFromResource( + resource_retriever::Retriever * retriever, + const std::string & resource_uri) { - resource_retriever::Retriever retriever; - resource_retriever::MemoryResource res; - try { - res = retriever.get(resource_path); - } catch (resource_retriever::Exception & e) { - RVIZ_RENDERING_LOG_ERROR(e.what()); - return resource_retriever::MemoryResource(); + // Early exit with empty retriever + if (nullptr == retriever) { + RVIZ_RENDERING_LOG_ERROR("retriever is unexpectedly nullptr"); + return nullptr; } - return res; -} - -Ogre::MeshPtr loadMeshFromResource(const std::string & resource_path) -{ - if (Ogre::MeshManager::getSingleton().resourceExists(resource_path, ROS_PACKAGE_NAME)) { - return Ogre::MeshManager::getSingleton().getByName(resource_path, ROS_PACKAGE_NAME); - } else { - QFileInfo model_path(QString::fromStdString(resource_path)); - std::string ext = model_path.completeSuffix().toStdString(); - if (ext == "mesh" || ext == "MESH") { - auto res = getResource(resource_path); - - if (res.size == 0) { - return Ogre::MeshPtr(); - } - - Ogre::MeshSerializer ser; - Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size)); - Ogre::MeshPtr mesh = Ogre::MeshManager::getSingleton().createManual( - resource_path, ROS_PACKAGE_NAME); - ser.importMesh(stream, mesh.get()); - stream->close(); - - return mesh; - } else { - AssimpLoader assimp_loader; + // Check for cached resources + if (Ogre::MeshManager::getSingleton().resourceExists(resource_uri, ROS_PACKAGE_NAME)) { + return Ogre::MeshManager::getSingleton().getByName(resource_uri, ROS_PACKAGE_NAME); + } - const aiScene * scene = assimp_loader.getScene(resource_path); - if (!scene) { - RVIZ_RENDERING_LOG_ERROR_STREAM( - "Could not load resource [" << resource_path.c_str() << "]: " << - assimp_loader.getErrorMessage()); - return Ogre::MeshPtr(); - } + // Check for ".mesh" resources, which OGRE can load directly + QFileInfo model_path(QString::fromStdString(resource_uri)); + std::string ext = model_path.completeSuffix().toStdString(); + if (ext == "mesh" || ext == "MESH") { + auto res = retriever->get_shared(resource_uri); + if (res == nullptr || res->data.empty()) { + return nullptr; + } + Ogre::MeshSerializer ser; + Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream( + const_cast(reinterpret_cast(res->data.data())), res->data.size())); + Ogre::MeshPtr mesh = Ogre::MeshManager::getSingleton().createManual(resource_uri, + ROS_PACKAGE_NAME); + ser.importMesh(stream, mesh.get()); + stream->close(); + return mesh; + } - return assimp_loader.meshFromAssimpScene(resource_path, scene); + { + AssimpLoader assimp_loader(retriever); + const aiScene * scene = assimp_loader.getScene(resource_uri); + if (scene == nullptr) { + RVIZ_RENDERING_LOG_ERROR_STREAM( + "Could not load resource [" << resource_uri.c_str() << "]: " << + assimp_loader.getErrorMessage()); + return nullptr; } + return assimp_loader.meshFromAssimpScene(resource_uri, scene); } } diff --git a/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.cpp b/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.cpp index cb9f889ff..e1028fc79 100644 --- a/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.cpp +++ b/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.cpp @@ -71,9 +71,9 @@ namespace rviz_rendering class ResourceIOStream : public Assimp::IOStream { public: - explicit ResourceIOStream(const resource_retriever::MemoryResource & res) + explicit ResourceIOStream(resource_retriever::ResourceSharedPtr res) : res_(res), - pos_(res.data.get()) + pos_(res->data.data()) {} ~ResourceIOStream() override = default; @@ -81,8 +81,8 @@ class ResourceIOStream : public Assimp::IOStream size_t Read(void * buffer, size_t size, size_t count) override { size_t to_read = size * count; - if (pos_ + to_read > res_.data.get() + res_.size) { - to_read = res_.size - (pos_ - res_.data.get()); + if (pos_ + to_read > res_->data.data() + res_->data.size()) { + to_read = res_->data.size() - (pos_ - res_->data.data()); } memcpy(buffer, pos_, to_read); @@ -101,22 +101,22 @@ class ResourceIOStream : public Assimp::IOStream aiReturn Seek(size_t offset, aiOrigin origin) override { - uint8_t * new_pos = nullptr; + const uint8_t * new_pos = nullptr; switch (origin) { case aiOrigin_SET: - new_pos = res_.data.get() + offset; + new_pos = res_->data.data() + offset; break; case aiOrigin_CUR: new_pos = pos_ + offset; // TODO(anyone): is this right? Can offset really not be negative break; case aiOrigin_END: - new_pos = res_.data.get() + res_.size - offset; // TODO(anyone): is this right? + new_pos = res_->data.data() + res_->data.size() - offset; // TODO(anyone): is this right? break; default: throw std::runtime_error("unexpected default in switch statement"); } - if (new_pos < res_.data.get() || new_pos > res_.data.get() + res_.size) { + if (new_pos < res_->data.data() || new_pos > res_->data.data() + res_->data.size()) { return aiReturn_FAILURE; } @@ -126,26 +126,28 @@ class ResourceIOStream : public Assimp::IOStream size_t Tell() const override { - return pos_ - res_.data.get(); + return pos_ - res_->data.data(); } size_t FileSize() const override { - return res_.size; + return res_->data.size(); } void Flush() override {} private: - resource_retriever::MemoryResource res_; - uint8_t * pos_; + resource_retriever::ResourceSharedPtr res_; + const uint8_t * pos_; }; class ResourceIOSystem final : public Assimp::IOSystem { public: - ResourceIOSystem() = default; + explicit ResourceIOSystem(resource_retriever::Retriever * retriever) + : retriever_(retriever) + {} ~ResourceIOSystem() override = default; @@ -158,32 +160,24 @@ class ResourceIOSystem final : public Assimp::IOSystem // Check whether a specific file exists bool Exists(const char * file) const override { - try { - resource_retriever::MemoryResource res = retriever_.get(file); - } catch (const resource_retriever::Exception & e) { - (void) e; // do nothing on exception - return false; - } - - return true; + auto res = retriever_->get_shared(file); + return res != nullptr; } // ... and finally a method to open a custom stream - Assimp::IOStream * Open(const char * file, const char * mode = "rb") override + Assimp::IOStream * Open(const char * file, const char * mode) override { (void) mode; assert(mode == std::string("r") || mode == std::string("rb")); - resource_retriever::MemoryResource res; - try { - res = retriever_.get(file); - } catch (const resource_retriever::Exception & e) { - (void) e; // do nothing on exception - return nullptr; + auto res = retriever_->get_shared(file); + + if (res != nullptr) { + // This will get freed when 'Close' is called + return new ResourceIOStream(res); } - // This will get freed when 'Close' is called - return new ResourceIOStream(res); + return nullptr; } void Close(Assimp::IOStream * stream) override @@ -192,13 +186,14 @@ class ResourceIOSystem final : public Assimp::IOSystem } private: - mutable resource_retriever::Retriever retriever_; + resource_retriever::Retriever * retriever_; }; -AssimpLoader::AssimpLoader() +AssimpLoader::AssimpLoader(resource_retriever::Retriever * retriever) +: retriever_(retriever), + importer_(std::make_unique()) { - importer_ = std::make_unique(); - importer_->SetIOHandler(new ResourceIOSystem()); + importer_->SetIOHandler(new ResourceIOSystem(retriever_)); // ASSIMP wants to change the orientation of the axis, but that's wrong for rviz. importer_->SetPropertyBool(AI_CONFIG_IMPORT_COLLADA_IGNORE_UP_DIRECTION, true); } @@ -399,31 +394,28 @@ void AssimpLoader::loadEmbeddedTexture( void AssimpLoader::loadTexture(const std::string & resource_path) { if (!Ogre::TextureManager::getSingleton().resourceExists(resource_path, ROS_PACKAGE_NAME)) { - resource_retriever::Retriever retriever; - resource_retriever::MemoryResource res; - try { - res = retriever.get(resource_path); - } catch (resource_retriever::Exception & e) { - RVIZ_RENDERING_LOG_ERROR(e.what()); + auto res = retriever_->get_shared(resource_path); + + if (res == nullptr || res->data.empty()) { + return; } - if (res.size != 0) { - Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size)); - Ogre::Image image; - QFileInfo resource_path_finfo(QString::fromStdString(resource_path)); - std::string extension = resource_path_finfo.completeSuffix().toStdString(); + Ogre::DataStreamPtr stream( + new Ogre::MemoryDataStream(const_cast(res->data.data()), res->data.size())); + Ogre::Image image; + QFileInfo resource_path_finfo(QString::fromStdString(resource_path)); + std::string extension = resource_path_finfo.completeSuffix().toStdString(); - if (extension[0] == '.') { - extension = extension.substr(1, extension.size() - 1); - } + if (extension[0] == '.') { + extension = extension.substr(1, extension.size() - 1); + } - try { - image.load(stream, extension); - Ogre::TextureManager::getSingleton().loadImage(resource_path, ROS_PACKAGE_NAME, image); - } catch (Ogre::Exception & e) { - RVIZ_RENDERING_LOG_ERROR_STREAM( - "Could not load texture [" << resource_path.c_str() << "]: " << e.what()); - } + try { + image.load(stream, extension); + Ogre::TextureManager::getSingleton().loadImage(resource_path, ROS_PACKAGE_NAME, image); + } catch (Ogre::Exception & e) { + RVIZ_RENDERING_LOG_ERROR_STREAM( + "Could not load texture [" << resource_path.c_str() << "]: " << e.what()); } } } diff --git a/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.hpp b/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.hpp index 5737dfb69..a27b07b87 100644 --- a/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.hpp +++ b/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.hpp @@ -60,7 +60,7 @@ namespace rviz_rendering class AssimpLoader { public: - AssimpLoader(); + explicit AssimpLoader(resource_retriever::Retriever * retriever = nullptr); Ogre::MeshPtr meshFromAssimpScene(const std::string & name, const aiScene * scene); const aiScene * getScene(const std::string & resource_path); std::string getErrorMessage(); @@ -151,6 +151,7 @@ class AssimpLoader index_buffer->unlock(); } + resource_retriever::Retriever * retriever_; std::unique_ptr importer_; }; diff --git a/rviz_rendering_tests/test/mesh_loader_test.cpp b/rviz_rendering_tests/test/mesh_loader_test.cpp index 507559de9..86a743d31 100644 --- a/rviz_rendering_tests/test/mesh_loader_test.cpp +++ b/rviz_rendering_tests/test/mesh_loader_test.cpp @@ -54,6 +54,7 @@ class MeshLoaderTestFixture : public ::testing::Test } std::shared_ptr testing_environment_; + resource_retriever::Retriever retriever_; }; void assertVector3Equality(Ogre::Vector3 actual, Ogre::Vector3 expected) @@ -70,18 +71,16 @@ void assertBoundingBoxEquality(Ogre::AxisAlignedBox actual, Ogre::AxisAlignedBox TEST_F(MeshLoaderTestFixture, throws_reasonable_exception_for_missing_files) { std::string mesh_path = "package://rviz_rendering/ogre_media/MISSING.mesh"; - testing::internal::CaptureStderr(); - auto mesh = rviz_rendering::loadMeshFromResource(mesh_path); - - std::string output = testing::internal::GetCapturedStderr(); - ASSERT_THAT(output, HasSubstr("Error retrieving file")); + EXPECT_THROW( + rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path), + resource_retriever::Exception); } TEST_F(MeshLoaderTestFixture, can_load_ogre_mesh_files) { std::string mesh_path = "package://rviz_rendering/ogre_media/models/rviz_sphere.mesh"; - auto mesh = rviz_rendering::loadMeshFromResource(mesh_path); + auto mesh = rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path); ASSERT_TRUE(mesh->isManuallyLoaded()); ASSERT_EQ(mesh_path, mesh->getName()); @@ -90,7 +89,7 @@ TEST_F(MeshLoaderTestFixture, can_load_ogre_mesh_files) { TEST_F(MeshLoaderTestFixture, can_load_stl_files) { std::string mesh_path = "package://rviz_rendering_tests/test_meshes/F2.stl"; - auto mesh = rviz_rendering::loadMeshFromResource(mesh_path); + auto mesh = rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path); float expected_bound_radius = 34.920441f; size_t expected_vertex_count = 35532; @@ -108,21 +107,21 @@ TEST_F(MeshLoaderTestFixture, loading_invalid_short_stl_files_fail) { /// Load an invalid STL binary file (size < 84 bytes). std::string mesh_path = "package://rviz_rendering_tests/test_meshes/invalid_short.stl"; - ASSERT_FALSE(rviz_rendering::loadMeshFromResource(mesh_path)); + ASSERT_FALSE(rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path)); } TEST_F(MeshLoaderTestFixture, loading_invalid_stl_files_fail) { /// Load an invalid STL binary file (size does not match the expected size). std::string mesh_path = "package://rviz_rendering_tests/test_meshes/invalid.stl"; - ASSERT_FALSE(rviz_rendering::loadMeshFromResource(mesh_path)); + ASSERT_FALSE(rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path)); } TEST_F(MeshLoaderTestFixture, loading_invalid_ascii_stl_file) { /// Load an invalid STL binary file (size does not match the expected size). std::string mesh_path = "package://rviz_rendering_tests/test_meshes/invalid_ascii.stl"; - ASSERT_FALSE(rviz_rendering::loadMeshFromResource(mesh_path)); + ASSERT_FALSE(rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path)); } TEST_F(MeshLoaderTestFixture, loading_invalid_stl_files_should_fail) { @@ -131,7 +130,7 @@ TEST_F(MeshLoaderTestFixture, loading_invalid_stl_files_should_fail) { std::string mesh_path = "package://rviz_rendering_tests/test_meshes/16bit_vs_32bit_should_fail.stl"; - ASSERT_FALSE(rviz_rendering::loadMeshFromResource(mesh_path)); + ASSERT_FALSE(rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path)); } TEST_F(MeshLoaderTestFixture, loading_almost_invalid_stl_files_should_fail) { @@ -139,20 +138,20 @@ TEST_F(MeshLoaderTestFixture, loading_almost_invalid_stl_files_should_fail) { /// expected. The file will not load. std::string mesh_path = "package://rviz_rendering_tests/test_meshes/invalid_extra.stl"; - EXPECT_FALSE(rviz_rendering::loadMeshFromResource(mesh_path)); + EXPECT_FALSE(rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path)); } TEST_F(MeshLoaderTestFixture, loading_stl_mesh_twice_should_not_fail) { std::string mesh_path = "package://rviz_rendering_tests/test_meshes/F2.stl"; - ASSERT_TRUE(rviz_rendering::loadMeshFromResource(mesh_path)); - ASSERT_TRUE(rviz_rendering::loadMeshFromResource(mesh_path)); + ASSERT_TRUE(rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path)); + ASSERT_TRUE(rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path)); } TEST_F(MeshLoaderTestFixture, can_load_assimp_mesh_files) { std::string mesh_path = "package://rviz_rendering_tests/test_meshes/pr2-base.dae"; - auto mesh = rviz_rendering::loadMeshFromResource(mesh_path); + auto mesh = rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path); size_t expected_vertex_number = 3600; size_t actual_vertex_number = mesh->getSubMesh(0)->vertexData->vertexCount; @@ -170,7 +169,7 @@ TEST_F(MeshLoaderTestFixture, can_load_assimp_mesh_files) { TEST_F(MeshLoaderTestFixture, assimp_loader_reads_size_correctly) { std::string mesh_path = "package://rviz_rendering_tests/test_meshes/pr2-base_large.dae"; - auto mesh = rviz_rendering::loadMeshFromResource(mesh_path); + auto mesh = rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path); // The pr2-base_large.dae mesh should be 6 times larger than pr2-base.dae. float expected_bounding_radius = 6 * 0.754754f; @@ -193,5 +192,5 @@ TEST_F(MeshLoaderTestFixture, loading_solidworks_binary_stl) { // as ASCII STL files. std::string mesh_path = "package://rviz_rendering_tests/test_meshes/solidworks.stl"; - ASSERT_TRUE(rviz_rendering::loadMeshFromResource(mesh_path)); + ASSERT_TRUE(rviz_rendering::loadMeshFromResource(&this->retriever_, mesh_path)); } diff --git a/rviz_resource_interfaces/CMakeLists.txt b/rviz_resource_interfaces/CMakeLists.txt new file mode 100644 index 000000000..d96992016 --- /dev/null +++ b/rviz_resource_interfaces/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.8) +project(rviz_resource_interfaces) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + "srv/GetResource.srv" +) + +ament_export_dependencies(rosidl_default_runtime) +ament_package() diff --git a/rviz_resource_interfaces/package.xml b/rviz_resource_interfaces/package.xml new file mode 100644 index 000000000..cfca99c92 --- /dev/null +++ b/rviz_resource_interfaces/package.xml @@ -0,0 +1,28 @@ + + + + rviz_resource_interfaces + 14.3.3 + ROS interfaces for working with resources like meshes. + + Alejandro Hernandez Cordero + + William Woodall + Eloy BriceƱo + + Apache-2.0 + + ament_cmake + + rosidl_default_generators + + rosidl_default_runtime + + rosidl_interface_packages + + + ament_cmake + + diff --git a/rviz_resource_interfaces/srv/GetResource.srv b/rviz_resource_interfaces/srv/GetResource.srv new file mode 100644 index 000000000..4a0828174 --- /dev/null +++ b/rviz_resource_interfaces/srv/GetResource.srv @@ -0,0 +1,62 @@ +# Resource path of the requested resource. +string path + +# HTTP-style ETag value for the requested resource. +# See: https://en.wikipedia.org/wiki/HTTP_ETag +# +# If this value is empty, then the server shall respond with the current +# version of the resource and the ETag value, if it can be loaded. +# If this value is not-empty, then the server may respond with a new resource +# and ETag value. +# However, if the ETag value for the resource has not changed, then the server +# may respond with NOT_MODIFIED as the status_code, similar to +# "HTTP 304: Not Modified". +# See: https://en.wikipedia.org/wiki/List_of_HTTP_status_codes#304 +# The server may also ignore this value and always send the current version +# of the resource and its ETag value, if caching is not implemented. +string etag + +--- + +# An unspecified error occurred, check the error_reason string. +int32 ERROR=0 + +# The request was successful, etag and body will be set with valid values, +# though etag may be empty. +# The error_reason will be empty. +int32 OK=1 + +# The request was successful, but the etag value has not changed. +# The etag value will be set to the requested etag value, but the body value +# will be empty. +# The error_reason should also be empty. +int32 NOT_MODIFIED=2 + +# Status code for the request, can be one of the above options. +int32 status_code + +# Optionally set error reason string. +string error_reason + +# Expanded path, which may or may not be different from the given path. +# The Service may expand, extend, or otherwise further qualify the path as it +# resolves it, any of which would be reflected in this expanded path. +string expanded_path + +# HTTP-style ETag value for the requested resource. +# See: https://en.wikipedia.org/wiki/HTTP_ETag +# +# As with the HTTP ETag, the value is unspecified, but it is described as: +# +# > Common methods of ETag generation include using a collision-resistant hash +# > function of the resource's content, a hash of the last modification +# > timestamp, or even just a revision number. +# +# This value may be empty if the server does not implement cache checking. +# +# This can be sent on subsequent requests to avoid getting the same unchanged +# resource multiple times. +string etag + +# Opaque value of the resource. +uint8[] body