From 188eb9203d0fad3728cafb15503dc02101fbe8b6 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 10 Oct 2024 08:49:31 -0400 Subject: [PATCH 01/18] first draft and devcontainer --- .devcontainer/devcontainer.json | 28 ++++++ .../properties/ros_topic_multi_property.hpp | 69 +++++++++++++++ .../properties/ros_topic_property.hpp | 2 +- .../properties/ros_topic_multi_property.cpp | 70 +++++++++++++++ rviz_default_plugins/CMakeLists.txt | 3 + .../displays/image/image_display.hpp | 28 +++++- rviz_default_plugins/package.xml | 1 + .../displays/image/image_display.cpp | 86 ++++++++++++++++++- 8 files changed, 283 insertions(+), 4 deletions(-) create mode 100644 .devcontainer/devcontainer.json create mode 100644 rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp create mode 100644 rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json new file mode 100644 index 000000000..5885a6d63 --- /dev/null +++ b/.devcontainer/devcontainer.json @@ -0,0 +1,28 @@ +// For format details, see https://aka.ms/devcontainer.json. For config options, see the +// README at: https://github.com/devcontainers/templates/tree/main/src/docker-existing-dockerfile +{ + "name": "rviz_rolling", + "image": "ros:rolling-ros-base" + + // Features to add to the dev container. More info: https://containers.dev/features. + // "features": {}, + + // Use 'forwardPorts' to make a list of ports inside the container available locally. + // "forwardPorts": [], + + // Uncomment the next line to run commands after the container is created. + // "postCreateCommand": "cat /etc/os-release", + + // Configure tool-specific properties. + // "customizations": {} + + + // Uncomment to connect as an existing user other than the container default. More info: https://aka.ms/dev-containers-non-root. + // "remoteUser": "devcontainer" + "workspaceMount": "source=${~/ros2_rolling},target=/ros2_rolling,type=bind", + "workspaceFolder": "/ros2_rolling/src/ros2/rviz", + //"overrideCommand": false + "runArgs": [ + "--network=host" + ] +} diff --git a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp new file mode 100644 index 000000000..e65365126 --- /dev/null +++ b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp @@ -0,0 +1,69 @@ +// Copyright (c) 2012, Willow Garage, 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_COMMON__PROPERTIES__ROS_TOPIC_MULTI_PROPERTY_HPP_ +#define RVIZ_COMMON__PROPERTIES__ROS_TOPIC_MULTI_PROPERTY_HPP_ + +#include +#include + +#include "rviz_common/properties/ros_topic_property.hpp" +#include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp" +#include "rviz_common/visibility_control.hpp" + +namespace rviz_common +{ +namespace properties +{ + +class RVIZ_COMMON_PUBLIC RosTopicMultiProperty : public RosTopicProperty +{ + Q_OBJECT +public: + + void setMessageTypes(const std::unordered_set & message_types); + + std::unordered_set getMessageTypes() const + {return message_types_;} + +protected Q_SLOTS: + virtual void fillTopicList() override; + +private: + // hide the parent class methods which only take a single type + using RosTopicProperty::setMessageType; + using RosTopicProperty::getMessageType; + + std::unordered_set message_types_; // TODO is there a QT-friendly type? +}; + +} // end namespace properties +} // end namespace rviz_common + +#endif // RVIZ_COMMON__PROPERTIES__ROS_TOPIC_MULTI_PROPERTY_HPP_ diff --git a/rviz_common/include/rviz_common/properties/ros_topic_property.hpp b/rviz_common/include/rviz_common/properties/ros_topic_property.hpp index ede824a45..b52b2fbce 100644 --- a/rviz_common/include/rviz_common/properties/ros_topic_property.hpp +++ b/rviz_common/include/rviz_common/properties/ros_topic_property.hpp @@ -76,7 +76,7 @@ class RVIZ_COMMON_PUBLIC RosTopicProperty : public EditableEnumProperty protected Q_SLOTS: virtual void fillTopicList(); -private: +protected: ros_integration::RosNodeAbstractionIface::WeakPtr rviz_ros_node_; QString message_type_; }; diff --git a/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp b/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp new file mode 100644 index 000000000..53cd5a673 --- /dev/null +++ b/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp @@ -0,0 +1,70 @@ +// Copyright (c) 2012, Willow Garage, 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 +#include + +#include // NOLINT: cpplint can't handle Qt imports + +#include "rviz_common/properties/ros_topic_multi_property.hpp" +#include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp" + +namespace rviz_common +{ +namespace properties +{ + +void RosTopicMultiProperty::setMessageTypes(const std::unordered_set & message_types) +{ + message_types_ = message_types; +} + +void RosTopicMultiProperty::fillTopicList() +{ + QApplication::setOverrideCursor(QCursor(Qt::WaitCursor)); + clearOptions(); + + std::map> published_topics = + rviz_ros_node_.lock()->get_topic_names_and_types(); + + for (const auto & topic : published_topics) { + // Only add topics whose type matches. + for (const auto & type : topic.second) { + if (message_types_.find(QString::fromStdString(type)) != message_types_.end()) { + addOptionStd(topic.first); + } + } + } + sortOptions(); + QApplication::restoreOverrideCursor(); +} + +} // end namespace properties +} // end namespace rviz_common diff --git a/rviz_default_plugins/CMakeLists.txt b/rviz_default_plugins/CMakeLists.txt index 1bdc96b17..09f775a9a 100644 --- a/rviz_default_plugins/CMakeLists.txt +++ b/rviz_default_plugins/CMakeLists.txt @@ -65,6 +65,7 @@ find_package(gz_math_vendor REQUIRED) find_package(gz-math REQUIRED) find_package(image_transport REQUIRED) +find_package(image_transport_plugins REQUIRED) find_package(interactive_markers REQUIRED) find_package(laser_geometry REQUIRED) find_package(map_msgs REQUIRED) @@ -246,6 +247,7 @@ target_include_directories(rviz_default_plugins PUBLIC target_link_libraries(rviz_default_plugins PUBLIC ${geometry_msgs_TARGETS} image_transport::image_transport + ${image_transport_plugins_TARGETS} interactive_markers::interactive_markers laser_geometry::laser_geometry ${map_msgs_TARGETS} @@ -284,6 +286,7 @@ ament_export_targets(rviz_default_plugins HAS_LIBRARY_TARGET) ament_export_dependencies( geometry_msgs image_transport + image_transport_plugins interactive_markers laser_geometry map_msgs diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp index d29106434..4c4520d7b 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp @@ -48,10 +48,15 @@ # include "rviz_common/properties/bool_property.hpp" # include "rviz_common/properties/float_property.hpp" # include "rviz_common/properties/int_property.hpp" +# include "rviz_common/properties/enum_property.hpp" # include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" # include "rviz_default_plugins/visibility_control.hpp" -#include "rviz_default_plugins/displays/image/image_transport_display.hpp" +# include "rviz_default_plugins/displays/image/image_transport_display.hpp" + +# include +# include +//# include #endif @@ -85,17 +90,38 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay : public void update(float wall_dt, float ros_dt) override; void reset() override; + QString getTransport(); + std::string getTransportStd(); + public Q_SLOTS: virtual void updateNormalizeOptions(); + bool setTransport(const QString & str); + bool setTransportStd(const std::string & std_str); protected: // overrides from Display void onEnable() override; void onDisable() override; + void subscribe() override; + void unsubscribe() override; + + void incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg); /* This is called by incomingMessage(). */ void processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) override; + image_transport::Subscriber subscription_; + rviz_common::properties::EnumProperty* image_transport_property_; + const std::unordered_map transport_message_types_ = + { + {"raw", QString::fromStdString(rosidl_generator_traits::name())}, + {"compressed", QString::fromStdString(rosidl_generator_traits::name())}, + /*{"theora", QString::fromStdString(rosidl_generator_traits::name())}*/ + }; + +protected Q_SLOTS: + void updateTransport(); + private: void setupScreenRectangle(); void setupRenderPanel(); diff --git a/rviz_default_plugins/package.xml b/rviz_default_plugins/package.xml index f4fcf6444..77d4047cd 100644 --- a/rviz_default_plugins/package.xml +++ b/rviz_default_plugins/package.xml @@ -40,6 +40,7 @@ geometry_msgs gz_math_vendor image_transport + image_transport_plugins interactive_markers laser_geometry nav_msgs diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index afcae40a4..c9fe3ac38 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -48,6 +48,8 @@ #include // NOLINT: cpplint is unable to handle the include order here #include "sensor_msgs/image_encodings.hpp" +#include "image_transport/image_transport.hpp" +#include "image_transport/subscriber.hpp" #include "rviz_common/display_context.hpp" #include "rviz_common/frame_manager_iface.hpp" @@ -60,6 +62,7 @@ #include "rviz_default_plugins/displays/image/ros_image_texture.hpp" #include "rviz_default_plugins/displays/image/image_display.hpp" #include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" +#include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp" namespace rviz_default_plugins { @@ -72,6 +75,17 @@ ImageDisplay::ImageDisplay() ImageDisplay::ImageDisplay(std::unique_ptr texture) : texture_(std::move(texture)) { + + image_transport_property_ = new rviz_common::properties::EnumProperty( + "Image Transport Hint", + "raw", + "What type of image transport to use.", + topic_property_, SLOT(updateTransport()), + this); + + for (const auto& [key, value] : transport_message_types_) + image_transport_property_->addOption(key); + normalize_property_ = new rviz_common::properties::BoolProperty( "Normalize Range", true, @@ -122,15 +136,57 @@ ImageDisplay::~ImageDisplay() = default; void ImageDisplay::onEnable() { - ITDClass::subscribe(); + subscribe(); } void ImageDisplay::onDisable() { - ITDClass::unsubscribe(); + unsubscribe(); clear(); } +// Need a signature with pass by reference for image_transport_.subscribe +void ImageDisplay::incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg){ + ImageDisplay::incomingMessage(img_msg); +} + +void ImageDisplay::subscribe(){ + if (!isEnabled()) { + return; + } + if (topic_property_->isEmpty()) { + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", + QString("Error subscribing: Empty topic name")); + return; + } + + try { + rclcpp::Node::SharedPtr node = rviz_ros_node_.lock()->get_raw_node(); + image_transport::ImageTransport image_transport_(node); + // This part differs from the parent class. ImageTransportDisplay uses an + // image_transport::SubscriberFilter, which requires a different callback for each transport + // type. image_transport::Subscriber only requires one callback for "raw" and the other types + // are automatically converted. + subscription_ = image_transport_.subscribe( + rviz_default_plugins::displays::getBaseTopicFromTopic(topic_property_->getTopicStd()), + (uint32_t)qos_profile.get_rmw_qos_profile().depth, // TODO try without cast + &ImageDisplay::incomingMessage, + this, + new image_transport::TransportHints(node.get(),getTransportStd(),"image_transport")); + + setStatus(rviz_common::properties::StatusProperty::Ok, "Topic", "OK"); + } catch (rclcpp::exceptions::InvalidTopicNameError & e) { + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", + QString("Error subscribing: ") + e.what()); + } +} + +void ImageDisplay::unsubscribe(){ + subscription_.shutdown(); +} + void ImageDisplay::updateNormalizeOptions() { if (got_float_image_) { @@ -152,6 +208,14 @@ void ImageDisplay::updateNormalizeOptions() } } +bool ImageDisplay::setTransport(const QString & str){ + return image_transport_property_->setValue(str.toLower()); +} + +bool ImageDisplay::setTransportStd(const std::string & std_str){ + return image_transport_property_->setValue(QString::fromStdString(std_str).toLower()); +} + void ImageDisplay::clear() { texture_->clear(); @@ -194,6 +258,14 @@ void ImageDisplay::reset() clear(); } +QString ImageDisplay::getTransport(){ + return image_transport_property_->getString(); +} + +std::string ImageDisplay::getTransportStd(){ + return image_transport_property_->getStdString(); +} + /* This is called by incomingMessage(). */ void ImageDisplay::processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) { @@ -209,6 +281,16 @@ void ImageDisplay::processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) texture_->addMessage(msg); } +void ImageDisplay::updateTransport(){ + topic_property_->setMessageType( + transport_message_types_.at(image_transport_property_->getString())); + + // If topic does not match desired transport, clear it. + if (getTransportFromTopic(topic_property_->getStdString()) != + image_transport_property_->getStdString()) + topic_property_->setString(""); +} + void ImageDisplay::setupScreenRectangle() { static int count = 0; From d2e32898047ec440020eabb8f19f0e970af949be Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 10 Oct 2024 13:56:28 +0000 Subject: [PATCH 02/18] devcontainer working, compressed image working --- .devcontainer/Dockerfile | 24 +++++++++++++++++++ .devcontainer/devcontainer.json | 8 +++++-- .../displays/image/image_display.cpp | 2 +- 3 files changed, 31 insertions(+), 3 deletions(-) create mode 100644 .devcontainer/Dockerfile diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile new file mode 100644 index 000000000..70f2c8bb6 --- /dev/null +++ b/.devcontainer/Dockerfile @@ -0,0 +1,24 @@ +FROM ubuntu:noble +ENV DEBIAN_FRONTEND=noninteractive +RUN apt update && apt install -y locales && locale-gen en_US en_US.UTF-8 && update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 +ENV LANG=en_US.UTF-8 +RUN apt install -y software-properties-common && add-apt-repository universe +RUN apt update && apt install -y curl && 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/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" > /etc/apt/sources.list.d/ros2.list +RUN apt update && apt install -y \ + python3-flake8-blind-except \ + python3-flake8-class-newline \ + python3-flake8-deprecated \ + python3-mypy \ + python3-pip \ + python3-pytest \ + python3-pytest-cov \ + python3-pytest-mock \ + python3-pytest-repeat \ + python3-pytest-rerunfailures \ + python3-pytest-runner \ + python3-pytest-timeout \ + ros-dev-tools +WORKDIR /ros2_rolling +RUN mkdir src && vcs import --input https://raw.githubusercontent.com/ros2/ros2/rolling/ros2.repos src +RUN apt upgrade -y && rosdep init && rosdep update && rosdep install --from-paths src --ignore-src -y --skip-keys "fastcdr rti-connext-dds-6.0.1 urdfdom_headers" \ No newline at end of file diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json index 5885a6d63..a6e77dd6f 100644 --- a/.devcontainer/devcontainer.json +++ b/.devcontainer/devcontainer.json @@ -2,7 +2,11 @@ // README at: https://github.com/devcontainers/templates/tree/main/src/docker-existing-dockerfile { "name": "rviz_rolling", - "image": "ros:rolling-ros-base" + "build": { + // Sets the run context to one level up instead of the .devcontainer folder. + // Update the 'dockerFile' property if you aren't using the standard 'Dockerfile' filename. + "dockerfile": "Dockerfile" + }, // Features to add to the dev container. More info: https://containers.dev/features. // "features": {}, @@ -19,7 +23,7 @@ // Uncomment to connect as an existing user other than the container default. More info: https://aka.ms/dev-containers-non-root. // "remoteUser": "devcontainer" - "workspaceMount": "source=${~/ros2_rolling},target=/ros2_rolling,type=bind", + "workspaceMount": "source=${localWorkspaceFolder},target=/ros2_rolling/src/ros2/rviz,type=bind", "workspaceFolder": "/ros2_rolling/src/ros2/rviz", //"overrideCommand": false "runArgs": [ diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index c9fe3ac38..07e7fe2c5 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -147,7 +147,7 @@ void ImageDisplay::onDisable() // Need a signature with pass by reference for image_transport_.subscribe void ImageDisplay::incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg){ - ImageDisplay::incomingMessage(img_msg); + ImageTransportDisplay::incomingMessage(img_msg); } void ImageDisplay::subscribe(){ From 3f3296d9ed1cd81ee5502a9109a3f628f7e17cb3 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 10 Oct 2024 19:56:43 +0000 Subject: [PATCH 03/18] topic-multi property working (segfaults on close) --- rviz_common/CMakeLists.txt | 2 + .../properties/ros_topic_multi_property.hpp | 19 +++- .../properties/ros_topic_multi_property.cpp | 19 +++- .../displays/image/image_display.hpp | 15 --- .../displays/image/image_display.cpp | 94 ++++++++++++------- 5 files changed, 90 insertions(+), 59 deletions(-) diff --git a/rviz_common/CMakeLists.txt b/rviz_common/CMakeLists.txt index 7741c400b..b77a8a8e2 100644 --- a/rviz_common/CMakeLists.txt +++ b/rviz_common/CMakeLists.txt @@ -104,6 +104,7 @@ set(rviz_common_headers_to_moc include/rviz_common/properties/property_tree_with_help.hpp include/rviz_common/properties/qos_profile_property.hpp include/rviz_common/properties/ros_topic_property.hpp + include/rviz_common/properties/ros_topic_multi_property.hpp include/rviz_common/properties/status_list.hpp include/rviz_common/properties/status_property.hpp include/rviz_common/properties/string_property.hpp @@ -183,6 +184,7 @@ set(rviz_common_source_files src/rviz_common/properties/property_tree_with_help.cpp src/rviz_common/properties/property.cpp src/rviz_common/properties/ros_topic_property.cpp + src/rviz_common/properties/ros_topic_multi_property.cpp src/rviz_common/properties/quaternion_property.cpp src/rviz_common/properties/qos_profile_property.cpp src/rviz_common/properties/regex_filter_property.cpp diff --git a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp index e65365126..55a042523 100644 --- a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp +++ b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp @@ -31,7 +31,7 @@ #define RVIZ_COMMON__PROPERTIES__ROS_TOPIC_MULTI_PROPERTY_HPP_ #include -#include +#include #include "rviz_common/properties/ros_topic_property.hpp" #include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp" @@ -46,21 +46,30 @@ class RVIZ_COMMON_PUBLIC RosTopicMultiProperty : public RosTopicProperty { Q_OBJECT public: + explicit RosTopicMultiProperty( + const QString & name = QString(), + const QString & default_value = QString(), + const std::vector & message_types = std::vector(), + const QString & description = QString(), + Property * parent = nullptr, + const char * changed_slot = nullptr, + QObject * receiver = nullptr); - void setMessageTypes(const std::unordered_set & message_types); + void setMessageTypes(const std::vector & message_types); - std::unordered_set getMessageTypes() const + std::vector getMessageTypes() const {return message_types_;} protected Q_SLOTS: virtual void fillTopicList() override; private: - // hide the parent class methods which only take a single type + // Hide the parent class methods which only take a single type using RosTopicProperty::setMessageType; using RosTopicProperty::getMessageType; - std::unordered_set message_types_; // TODO is there a QT-friendly type? + // Instead of one message type, store a list of allowed types + std::vector message_types_; }; } // end namespace properties diff --git a/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp b/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp index 53cd5a673..c439dce11 100644 --- a/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp +++ b/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp @@ -30,6 +30,7 @@ #include #include +#include #include // NOLINT: cpplint can't handle Qt imports @@ -41,7 +42,19 @@ namespace rviz_common namespace properties { -void RosTopicMultiProperty::setMessageTypes(const std::unordered_set & message_types) +RosTopicMultiProperty::RosTopicMultiProperty( + const QString & name, + const QString & default_value, + const std::vector & message_types, + const QString & description, + Property * parent, + const char * changed_slot, + QObject * receiver) +: RosTopicProperty(name, default_value, "", description, parent, changed_slot, receiver), + message_types_(message_types) +{} + +void RosTopicMultiProperty::setMessageTypes(const std::vector & message_types) { message_types_ = message_types; } @@ -57,9 +70,9 @@ void RosTopicMultiProperty::fillTopicList() for (const auto & topic : published_topics) { // Only add topics whose type matches. for (const auto & type : topic.second) { - if (message_types_.find(QString::fromStdString(type)) != message_types_.end()) { + if (std::find(message_types_.begin(), message_types_.end(), QString::fromStdString(type)) + != message_types_.end()) addOptionStd(topic.first); - } } } sortOptions(); diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp index 4c4520d7b..c460c53f8 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp @@ -85,18 +85,13 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay : public ImageDisplay(); ~ImageDisplay() override; - // Overrides from Display void onInitialize() override; void update(float wall_dt, float ros_dt) override; void reset() override; - QString getTransport(); - std::string getTransportStd(); public Q_SLOTS: virtual void updateNormalizeOptions(); - bool setTransport(const QString & str); - bool setTransportStd(const std::string & std_str); protected: // overrides from Display @@ -111,16 +106,6 @@ public Q_SLOTS: void processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) override; image_transport::Subscriber subscription_; - rviz_common::properties::EnumProperty* image_transport_property_; - const std::unordered_map transport_message_types_ = - { - {"raw", QString::fromStdString(rosidl_generator_traits::name())}, - {"compressed", QString::fromStdString(rosidl_generator_traits::name())}, - /*{"theora", QString::fromStdString(rosidl_generator_traits::name())}*/ - }; - -protected Q_SLOTS: - void updateTransport(); private: void setupScreenRectangle(); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 07e7fe2c5..9b0352d76 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -32,6 +32,8 @@ #include #include #include +#include +#include #include #include @@ -56,6 +58,7 @@ #include "rviz_common/render_panel.hpp" #include "rviz_common/validate_floats.hpp" #include "rviz_common/uniform_string_stream.hpp" +#include "rviz_common/properties/ros_topic_multi_property.hpp" #include "rviz_rendering/material_manager.hpp" #include "rviz_rendering/render_window.hpp" @@ -64,6 +67,8 @@ #include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" #include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp" +#include // TODO remove when done + namespace rviz_default_plugins { namespace displays @@ -75,16 +80,17 @@ ImageDisplay::ImageDisplay() ImageDisplay::ImageDisplay(std::unique_ptr texture) : texture_(std::move(texture)) { + delete this->topic_property_; + this->topic_property_ = new rviz_common::properties::RosTopicMultiProperty( + "Topic", + "", + std::vector(), + "Image transport topic to subscribe to.", + this, + SLOT(updateTopic())); - image_transport_property_ = new rviz_common::properties::EnumProperty( - "Image Transport Hint", - "raw", - "What type of image transport to use.", - topic_property_, SLOT(updateTransport()), - this); - - for (const auto& [key, value] : transport_message_types_) - image_transport_property_->addOption(key); + delete this->qos_profile_property_; + this->qos_profile_property_ = new rviz_common::properties::QosProfileProperty(this->topic_property_, rclcpp::QoS(5)); normalize_property_ = new rviz_common::properties::BoolProperty( "Normalize Range", @@ -154,6 +160,45 @@ void ImageDisplay::subscribe(){ if (!isEnabled()) { return; } + + // TODO this should really be in onInitialize but setStatus does not work there + // Populate topic message types based on installed image_transport plugins + image_transport::ImageTransport image_transport_(rviz_ros_node_.lock()->get_raw_node()); + std::vector transports = image_transport_.getLoadableTransports(); + std::vector message_types; + // Map to message types + const std::unordered_map transport_message_types_ = + { + {"raw", "sensor_msgs/msg/Image"}, + {"compressed", "sensor_msgs/msg/CompressedImage"}, + {"compressedDepth", "sensor_msgs/msg/CompressedImage"}, + {"theora", "theora_image_transport/msg/Packet"}, + {"zstd", "sensor_msgs/msg/CompressedImage"}, + }; + std::string transports_str = ""; + rviz_common::properties::StatusProperty::Level transports_status_level = + rviz_common::properties::StatusProperty::Ok; + for (std::string & transport : transports){ + transport = transport.substr(transport.find_last_of('/') + 1); + try{ + message_types.push_back(QString::fromStdString(transport_message_types_.at(transport))); + transports_str += transport + ", "; + } + catch (const std::out_of_range & e){ + transports_status_level = rviz_common::properties::StatusProperty::Warn; + transports_str += "(unknown: " + transport + "), "; + } + } + setStatusStd( + transports_status_level, + "Image Transports", + transports_str); + // Remove duplicates + message_types.erase(std::unique(message_types.begin(), message_types.end() ), message_types.end()); + // Update the message types to allow in the topic_property_ + ((rviz_common::properties::RosTopicMultiProperty*)topic_property_)->setMessageTypes(message_types); + + RVIZ_COMMON_LOG_INFO("subscribe"); if (topic_property_->isEmpty()) { setStatus( rviz_common::properties::StatusProperty::Error, "Topic", @@ -173,7 +218,10 @@ void ImageDisplay::subscribe(){ (uint32_t)qos_profile.get_rmw_qos_profile().depth, // TODO try without cast &ImageDisplay::incomingMessage, this, - new image_transport::TransportHints(node.get(),getTransportStd(),"image_transport")); + new image_transport::TransportHints( + node.get(), + getTransportFromTopic(topic_property_->getStdString()), + "image_transport")); setStatus(rviz_common::properties::StatusProperty::Ok, "Topic", "OK"); } catch (rclcpp::exceptions::InvalidTopicNameError & e) { @@ -208,14 +256,6 @@ void ImageDisplay::updateNormalizeOptions() } } -bool ImageDisplay::setTransport(const QString & str){ - return image_transport_property_->setValue(str.toLower()); -} - -bool ImageDisplay::setTransportStd(const std::string & std_str){ - return image_transport_property_->setValue(QString::fromStdString(std_str).toLower()); -} - void ImageDisplay::clear() { texture_->clear(); @@ -258,14 +298,6 @@ void ImageDisplay::reset() clear(); } -QString ImageDisplay::getTransport(){ - return image_transport_property_->getString(); -} - -std::string ImageDisplay::getTransportStd(){ - return image_transport_property_->getStdString(); -} - /* This is called by incomingMessage(). */ void ImageDisplay::processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) { @@ -281,16 +313,6 @@ void ImageDisplay::processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) texture_->addMessage(msg); } -void ImageDisplay::updateTransport(){ - topic_property_->setMessageType( - transport_message_types_.at(image_transport_property_->getString())); - - // If topic does not match desired transport, clear it. - if (getTransportFromTopic(topic_property_->getStdString()) != - image_transport_property_->getStdString()) - topic_property_->setString(""); -} - void ImageDisplay::setupScreenRectangle() { static int count = 0; From f8bb97e255fbc119d8225b29f8749395869e80e0 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Fri, 11 Oct 2024 16:55:45 +0000 Subject: [PATCH 04/18] remove image transport plugins as dependency --- .devcontainer/Dockerfile | 1 + rviz_default_plugins/CMakeLists.txt | 3 --- rviz_default_plugins/package.xml | 1 - .../src/rviz_default_plugins/displays/image/image_display.cpp | 4 +++- 4 files changed, 4 insertions(+), 5 deletions(-) diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile index 70f2c8bb6..2542b5667 100644 --- a/.devcontainer/Dockerfile +++ b/.devcontainer/Dockerfile @@ -20,5 +20,6 @@ RUN apt update && apt install -y \ python3-pytest-timeout \ ros-dev-tools WORKDIR /ros2_rolling +ENV ROS_DISTRO="rolling" RUN mkdir src && vcs import --input https://raw.githubusercontent.com/ros2/ros2/rolling/ros2.repos src RUN apt upgrade -y && rosdep init && rosdep update && rosdep install --from-paths src --ignore-src -y --skip-keys "fastcdr rti-connext-dds-6.0.1 urdfdom_headers" \ No newline at end of file diff --git a/rviz_default_plugins/CMakeLists.txt b/rviz_default_plugins/CMakeLists.txt index 09f775a9a..1bdc96b17 100644 --- a/rviz_default_plugins/CMakeLists.txt +++ b/rviz_default_plugins/CMakeLists.txt @@ -65,7 +65,6 @@ find_package(gz_math_vendor REQUIRED) find_package(gz-math REQUIRED) find_package(image_transport REQUIRED) -find_package(image_transport_plugins REQUIRED) find_package(interactive_markers REQUIRED) find_package(laser_geometry REQUIRED) find_package(map_msgs REQUIRED) @@ -247,7 +246,6 @@ target_include_directories(rviz_default_plugins PUBLIC target_link_libraries(rviz_default_plugins PUBLIC ${geometry_msgs_TARGETS} image_transport::image_transport - ${image_transport_plugins_TARGETS} interactive_markers::interactive_markers laser_geometry::laser_geometry ${map_msgs_TARGETS} @@ -286,7 +284,6 @@ ament_export_targets(rviz_default_plugins HAS_LIBRARY_TARGET) ament_export_dependencies( geometry_msgs image_transport - image_transport_plugins interactive_markers laser_geometry map_msgs diff --git a/rviz_default_plugins/package.xml b/rviz_default_plugins/package.xml index 77d4047cd..f4fcf6444 100644 --- a/rviz_default_plugins/package.xml +++ b/rviz_default_plugins/package.xml @@ -40,7 +40,6 @@ geometry_msgs gz_math_vendor image_transport - image_transport_plugins interactive_markers laser_geometry nav_msgs diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 9b0352d76..1e97dd547 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -69,6 +69,9 @@ #include // TODO remove when done +// TODO This may have introduced a segfault upon closing the program, but it is infrequent. +// It's possible this existed before my changes. + namespace rviz_default_plugins { namespace displays @@ -198,7 +201,6 @@ void ImageDisplay::subscribe(){ // Update the message types to allow in the topic_property_ ((rviz_common::properties::RosTopicMultiProperty*)topic_property_)->setMessageTypes(message_types); - RVIZ_COMMON_LOG_INFO("subscribe"); if (topic_property_->isEmpty()) { setStatus( rviz_common::properties::StatusProperty::Error, "Topic", From 5928cd9a46f15f5c08ca046b97aac4fd6ac529ec Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Fri, 11 Oct 2024 16:59:57 +0000 Subject: [PATCH 05/18] segfault was not my fault --- .../rviz_default_plugins/displays/image/image_display.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 1e97dd547..f74e43da0 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -67,11 +67,6 @@ #include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" #include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp" -#include // TODO remove when done - -// TODO This may have introduced a segfault upon closing the program, but it is infrequent. -// It's possible this existed before my changes. - namespace rviz_default_plugins { namespace displays From fcdf0229499db130eadd1003a69f9983af26b730 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Tue, 15 Oct 2024 14:32:01 +0000 Subject: [PATCH 06/18] minor cleanup and comments --- .../properties/ros_topic_multi_property.hpp | 10 ++++++++-- .../properties/ros_topic_multi_property.cpp | 17 ----------------- .../displays/image/image_display.hpp | 4 ---- .../displays/image/image_display.cpp | 2 ++ 4 files changed, 10 insertions(+), 23 deletions(-) diff --git a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp index 55a042523..ae65879e3 100644 --- a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp +++ b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp @@ -42,6 +42,7 @@ namespace rviz_common namespace properties { +// Like RosTopicProperty but can accept multiple message types class RVIZ_COMMON_PUBLIC RosTopicMultiProperty : public RosTopicProperty { Q_OBJECT @@ -53,9 +54,14 @@ class RVIZ_COMMON_PUBLIC RosTopicMultiProperty : public RosTopicProperty const QString & description = QString(), Property * parent = nullptr, const char * changed_slot = nullptr, - QObject * receiver = nullptr); + QObject * receiver = nullptr): + RosTopicProperty(name, default_value, "", description, parent, changed_slot, receiver), + message_types_(message_types) + {} + + void setMessageTypes(const std::vector & message_types) + {message_types_ = message_types;} - void setMessageTypes(const std::vector & message_types); std::vector getMessageTypes() const {return message_types_;} diff --git a/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp b/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp index c439dce11..506eb3519 100644 --- a/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp +++ b/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp @@ -42,23 +42,6 @@ namespace rviz_common namespace properties { -RosTopicMultiProperty::RosTopicMultiProperty( - const QString & name, - const QString & default_value, - const std::vector & message_types, - const QString & description, - Property * parent, - const char * changed_slot, - QObject * receiver) -: RosTopicProperty(name, default_value, "", description, parent, changed_slot, receiver), - message_types_(message_types) -{} - -void RosTopicMultiProperty::setMessageTypes(const std::vector & message_types) -{ - message_types_ = message_types; -} - void RosTopicMultiProperty::fillTopicList() { QApplication::setOverrideCursor(QCursor(Qt::WaitCursor)); diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp index c460c53f8..c8e8ef63c 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp @@ -55,8 +55,6 @@ # include "rviz_default_plugins/displays/image/image_transport_display.hpp" # include -# include -//# include #endif @@ -89,12 +87,10 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay : public void update(float wall_dt, float ros_dt) override; void reset() override; - public Q_SLOTS: virtual void updateNormalizeOptions(); protected: - // overrides from Display void onEnable() override; void onDisable() override; void subscribe() override; diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index f74e43da0..4a0041159 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -78,6 +78,8 @@ ImageDisplay::ImageDisplay() ImageDisplay::ImageDisplay(std::unique_ptr texture) : texture_(std::move(texture)) { + // Remove the default single-type topic and replace with a multi-type topic property + // This allows us to display image and compressed image topics in the topic list delete this->topic_property_; this->topic_property_ = new rviz_common::properties::RosTopicMultiProperty( "Topic", From ef95ae803d9d1412b1e3028ea6adbc8ad8e22c09 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 24 Oct 2024 14:09:08 +0000 Subject: [PATCH 07/18] code style --- .../properties/ros_topic_multi_property.hpp | 29 ++-- .../properties/ros_topic_property.hpp | 35 ++--- .../properties/ros_topic_multi_property.cpp | 14 +- .../displays/image/image_display.hpp | 49 +++---- .../displays/image/image_display.cpp | 133 +++++++----------- 5 files changed, 107 insertions(+), 153 deletions(-) diff --git a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp index ae65879e3..4572dac4c 100644 --- a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp +++ b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp @@ -46,33 +46,32 @@ namespace properties class RVIZ_COMMON_PUBLIC RosTopicMultiProperty : public RosTopicProperty { Q_OBJECT + public: explicit RosTopicMultiProperty( - const QString & name = QString(), - const QString & default_value = QString(), + const QString & name = QString(), const QString & default_value = QString(), const std::vector & message_types = std::vector(), - const QString & description = QString(), - Property * parent = nullptr, - const char * changed_slot = nullptr, - QObject * receiver = nullptr): - RosTopicProperty(name, default_value, "", description, parent, changed_slot, receiver), - message_types_(message_types) - {} + const QString & description = QString(), Property * parent = nullptr, + const char * changed_slot = nullptr, QObject * receiver = nullptr) + : RosTopicProperty(name, default_value, "", description, parent, changed_slot, receiver), + message_types_(message_types) + { + } void setMessageTypes(const std::vector & message_types) - {message_types_ = message_types;} - + { + message_types_ = message_types; + } - std::vector getMessageTypes() const - {return message_types_;} + std::vector getMessageTypes() const {return message_types_;} protected Q_SLOTS: - virtual void fillTopicList() override; + void fillTopicList() override; private: // Hide the parent class methods which only take a single type - using RosTopicProperty::setMessageType; using RosTopicProperty::getMessageType; + using RosTopicProperty::setMessageType; // Instead of one message type, store a list of allowed types std::vector message_types_; diff --git a/rviz_common/include/rviz_common/properties/ros_topic_property.hpp b/rviz_common/include/rviz_common/properties/ros_topic_property.hpp index b52b2fbce..5308ad5d1 100644 --- a/rviz_common/include/rviz_common/properties/ros_topic_property.hpp +++ b/rviz_common/include/rviz_common/properties/ros_topic_property.hpp @@ -49,29 +49,21 @@ class RVIZ_COMMON_PUBLIC RosTopicProperty : public EditableEnumProperty public: explicit RosTopicProperty( - const QString & name = QString(), - const QString & default_value = QString(), - const QString & message_type = QString(), - const QString & description = QString(), - Property * parent = nullptr, - const char * changed_slot = nullptr, - QObject * receiver = nullptr); + const QString & name = QString(), const QString & default_value = QString(), + const QString & message_type = QString(), const QString & description = QString(), + Property * parent = nullptr, const char * changed_slot = nullptr, QObject * receiver = nullptr); void initialize(ros_integration::RosNodeAbstractionIface::WeakPtr rviz_ros_node); void setMessageType(const QString & message_type); - QString getMessageType() const - {return message_type_;} + QString getMessageType() const {return message_type_;} - QString getTopic() const - {return getValue().toString();} + QString getTopic() const {return getValue().toString();} - std::string getTopicStd() const - {return getValue().toString().toStdString();} + std::string getTopicStd() const {return getValue().toString().toStdString();} - bool isEmpty() const - {return getTopicStd().empty();} + bool isEmpty() const {return getTopicStd().empty();} protected Q_SLOTS: virtual void fillTopicList(); @@ -81,20 +73,15 @@ protected Q_SLOTS: QString message_type_; }; -class RVIZ_COMMON_PUBLIC RosFilteredTopicProperty - : public rviz_common::properties::RosTopicProperty +class RVIZ_COMMON_PUBLIC RosFilteredTopicProperty : public rviz_common::properties::RosTopicProperty { Q_OBJECT public: RosFilteredTopicProperty( - const QString & name = QString(), - const QString & default_value = QString(), - const QString & message_type = QString(), - const QString & description = QString(), - const QRegExp & filter = QRegExp(), - Property * parent = 0, - const char * changed_slot = 0, + const QString & name = QString(), const QString & default_value = QString(), + const QString & message_type = QString(), const QString & description = QString(), + const QRegExp & filter = QRegExp(), Property * parent = 0, const char * changed_slot = 0, QObject * receiver = 0); void enableFilter(bool enabled); diff --git a/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp b/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp index 506eb3519..3a722d963 100644 --- a/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp +++ b/rviz_common/src/rviz_common/properties/ros_topic_multi_property.cpp @@ -27,14 +27,13 @@ // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. +#include "rviz_common/properties/ros_topic_multi_property.hpp" +#include // NOLINT: cpplint can't handle Qt imports +#include #include #include -#include -#include // NOLINT: cpplint can't handle Qt imports - -#include "rviz_common/properties/ros_topic_multi_property.hpp" #include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp" namespace rviz_common @@ -53,9 +52,12 @@ void RosTopicMultiProperty::fillTopicList() for (const auto & topic : published_topics) { // Only add topics whose type matches. for (const auto & type : topic.second) { - if (std::find(message_types_.begin(), message_types_.end(), QString::fromStdString(type)) - != message_types_.end()) + if ( + std::find(message_types_.begin(), message_types_.end(), QString::fromStdString(type)) != + message_types_.end()) + { addOptionStd(topic.first); + } } } sortOptions(); diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp index c8e8ef63c..39e9b251f 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp @@ -29,40 +29,37 @@ // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. - #ifndef RVIZ_DEFAULT_PLUGINS__DISPLAYS__IMAGE__IMAGE_DISPLAY_HPP_ #define RVIZ_DEFAULT_PLUGINS__DISPLAYS__IMAGE__IMAGE_DISPLAY_HPP_ #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 -# include -# include - -# include // NOLINT cpplint cannot handle include order here - -# include -# include -# include - -# include "rviz_common/message_filter_display.hpp" -# include "rviz_common/render_panel.hpp" -# include "rviz_common/properties/bool_property.hpp" -# include "rviz_common/properties/float_property.hpp" -# include "rviz_common/properties/int_property.hpp" -# include "rviz_common/properties/enum_property.hpp" - -# include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" -# include "rviz_default_plugins/visibility_control.hpp" -# include "rviz_default_plugins/displays/image/image_transport_display.hpp" - -# include +#include +#include +#include + +#include // NOLINT cpplint cannot handle include order here + +#include +#include + +#include + +#include "rviz_common/message_filter_display.hpp" +#include "rviz_common/properties/bool_property.hpp" +#include "rviz_common/properties/enum_property.hpp" +#include "rviz_common/properties/float_property.hpp" +#include "rviz_common/properties/int_property.hpp" +#include "rviz_common/render_panel.hpp" +#include "rviz_default_plugins/displays/image/image_transport_display.hpp" +#include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" +#include "rviz_default_plugins/visibility_control.hpp" #endif - namespace Ogre { class SceneNode; class Rectangle2D; -} +} // namespace Ogre namespace rviz_default_plugins { @@ -73,8 +70,8 @@ namespace displays * \class ImageDisplay * */ -class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay : public - rviz_default_plugins::displays::ImageTransportDisplay +class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay + : public rviz_default_plugins::displays::ImageTransportDisplay { Q_OBJECT diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 4a0041159..786f10ca5 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -28,12 +28,7 @@ // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. - -#include -#include -#include -#include -#include +#include "rviz_default_plugins/displays/image/image_display.hpp" #include #include @@ -49,23 +44,26 @@ #include // NOLINT: cpplint is unable to handle the include order here -#include "sensor_msgs/image_encodings.hpp" +#include +#include +#include +#include +#include + #include "image_transport/image_transport.hpp" #include "image_transport/subscriber.hpp" - #include "rviz_common/display_context.hpp" #include "rviz_common/frame_manager_iface.hpp" +#include "rviz_common/properties/ros_topic_multi_property.hpp" #include "rviz_common/render_panel.hpp" -#include "rviz_common/validate_floats.hpp" #include "rviz_common/uniform_string_stream.hpp" -#include "rviz_common/properties/ros_topic_multi_property.hpp" -#include "rviz_rendering/material_manager.hpp" -#include "rviz_rendering/render_window.hpp" - +#include "rviz_common/validate_floats.hpp" +#include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp" #include "rviz_default_plugins/displays/image/ros_image_texture.hpp" -#include "rviz_default_plugins/displays/image/image_display.hpp" #include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" -#include "rviz_default_plugins/displays/image/get_transport_from_topic.hpp" +#include "rviz_rendering/material_manager.hpp" +#include "rviz_rendering/render_window.hpp" +#include "sensor_msgs/image_encodings.hpp" namespace rviz_default_plugins { @@ -82,42 +80,28 @@ ImageDisplay::ImageDisplay(std::unique_ptr texture) // This allows us to display image and compressed image topics in the topic list delete this->topic_property_; this->topic_property_ = new rviz_common::properties::RosTopicMultiProperty( - "Topic", - "", - std::vector(), - "Image transport topic to subscribe to.", - this, + "Topic", "", std::vector(), "Image transport topic to subscribe to.", this, SLOT(updateTopic())); delete this->qos_profile_property_; - this->qos_profile_property_ = new rviz_common::properties::QosProfileProperty(this->topic_property_, rclcpp::QoS(5)); + this->qos_profile_property_ = + new rviz_common::properties::QosProfileProperty(this->topic_property_, rclcpp::QoS(5)); normalize_property_ = new rviz_common::properties::BoolProperty( - "Normalize Range", - true, + "Normalize Range", true, "If set to true, will try to estimate the range of possible values from the received images.", - this, - SLOT(updateNormalizeOptions())); + this, SLOT(updateNormalizeOptions())); min_property_ = new rviz_common::properties::FloatProperty( - "Min Value", - 0.0, - "Value which will be displayed as black.", - this, + "Min Value", 0.0, "Value which will be displayed as black.", this, SLOT(updateNormalizeOptions())); max_property_ = new rviz_common::properties::FloatProperty( - "Max Value", - 1.0, - "Value which will be displayed as white.", - this, + "Max Value", 1.0, "Value which will be displayed as white.", this, SLOT(updateNormalizeOptions())); median_buffer_size_property_ = new rviz_common::properties::IntProperty( - "Median window", - 5, - "Window size for median filter used for computing min/max.", - this, + "Median window", 5, "Window size for median filter used for computing min/max.", this, SLOT(updateNormalizeOptions())); got_float_image_ = false; @@ -133,17 +117,12 @@ void ImageDisplay::onInitialize() setupRenderPanel(); render_panel_->getRenderWindow()->setupSceneAfterInit( - [this](Ogre::SceneNode * scene_node) { - scene_node->attachObject(screen_rect_.get()); - }); + [this](Ogre::SceneNode * scene_node) {scene_node->attachObject(screen_rect_.get());}); } ImageDisplay::~ImageDisplay() = default; -void ImageDisplay::onEnable() -{ - subscribe(); -} +void ImageDisplay::onEnable() {subscribe();} void ImageDisplay::onDisable() { @@ -152,51 +131,49 @@ void ImageDisplay::onDisable() } // Need a signature with pass by reference for image_transport_.subscribe -void ImageDisplay::incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg){ +void ImageDisplay::incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg) +{ ImageTransportDisplay::incomingMessage(img_msg); } -void ImageDisplay::subscribe(){ +void ImageDisplay::subscribe() +{ if (!isEnabled()) { return; } - // TODO this should really be in onInitialize but setStatus does not work there + // TODO(mjforan) this should really be in onInitialize but setStatus does not work there // Populate topic message types based on installed image_transport plugins image_transport::ImageTransport image_transport_(rviz_ros_node_.lock()->get_raw_node()); std::vector transports = image_transport_.getLoadableTransports(); std::vector message_types; // Map to message types - const std::unordered_map transport_message_types_ = - { - {"raw", "sensor_msgs/msg/Image"}, - {"compressed", "sensor_msgs/msg/CompressedImage"}, - {"compressedDepth", "sensor_msgs/msg/CompressedImage"}, - {"theora", "theora_image_transport/msg/Packet"}, - {"zstd", "sensor_msgs/msg/CompressedImage"}, + const std::unordered_map transport_message_types_ = { + {"raw", "sensor_msgs/msg/Image"}, + {"compressed", "sensor_msgs/msg/CompressedImage"}, + {"compressedDepth", "sensor_msgs/msg/CompressedImage"}, + {"theora", "theora_image_transport/msg/Packet"}, + {"zstd", "sensor_msgs/msg/CompressedImage"}, }; std::string transports_str = ""; rviz_common::properties::StatusProperty::Level transports_status_level = rviz_common::properties::StatusProperty::Ok; - for (std::string & transport : transports){ + for (std::string & transport : transports) { transport = transport.substr(transport.find_last_of('/') + 1); - try{ + try { message_types.push_back(QString::fromStdString(transport_message_types_.at(transport))); transports_str += transport + ", "; - } - catch (const std::out_of_range & e){ + } catch (const std::out_of_range & e) { transports_status_level = rviz_common::properties::StatusProperty::Warn; transports_str += "(unknown: " + transport + "), "; } } - setStatusStd( - transports_status_level, - "Image Transports", - transports_str); + setStatusStd(transports_status_level, "Image Transports", transports_str); // Remove duplicates - message_types.erase(std::unique(message_types.begin(), message_types.end() ), message_types.end()); + message_types.erase(std::unique(message_types.begin(), message_types.end()), message_types.end()); // Update the message types to allow in the topic_property_ - ((rviz_common::properties::RosTopicMultiProperty*)topic_property_)->setMessageTypes(message_types); + ((rviz_common::properties::RosTopicMultiProperty *)topic_property_) + ->setMessageTypes(message_types); if (topic_property_->isEmpty()) { setStatus( @@ -214,13 +191,10 @@ void ImageDisplay::subscribe(){ // are automatically converted. subscription_ = image_transport_.subscribe( rviz_default_plugins::displays::getBaseTopicFromTopic(topic_property_->getTopicStd()), - (uint32_t)qos_profile.get_rmw_qos_profile().depth, // TODO try without cast - &ImageDisplay::incomingMessage, - this, + (uint32_t)qos_profile.get_rmw_qos_profile().depth, // TODO(mjforan) try without cast + &ImageDisplay::incomingMessage, this, new image_transport::TransportHints( - node.get(), - getTransportFromTopic(topic_property_->getStdString()), - "image_transport")); + node.get(), getTransportFromTopic(topic_property_->getStdString()), "image_transport")); setStatus(rviz_common::properties::StatusProperty::Ok, "Topic", "OK"); } catch (rclcpp::exceptions::InvalidTopicNameError & e) { @@ -230,9 +204,7 @@ void ImageDisplay::subscribe(){ } } -void ImageDisplay::unsubscribe(){ - subscription_.shutdown(); -} +void ImageDisplay::unsubscribe() {subscription_.shutdown();} void ImageDisplay::updateNormalizeOptions() { @@ -255,15 +227,12 @@ void ImageDisplay::updateNormalizeOptions() } } -void ImageDisplay::clear() -{ - texture_->clear(); -} +void ImageDisplay::clear() {texture_->clear();} void ImageDisplay::update(float wall_dt, float ros_dt) { - (void) wall_dt; - (void) ros_dt; + (void)wall_dt; + (void)ros_dt; try { texture_->update(); @@ -300,7 +269,8 @@ void ImageDisplay::reset() /* This is called by incomingMessage(). */ void ImageDisplay::processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) { - bool got_float_image = msg->encoding == sensor_msgs::image_encodings::TYPE_32FC1 || + bool got_float_image = + msg->encoding == sensor_msgs::image_encodings::TYPE_32FC1 || msg->encoding == sensor_msgs::image_encodings::TYPE_16UC1 || msg->encoding == sensor_msgs::image_encodings::TYPE_16SC1 || msg->encoding == sensor_msgs::image_encodings::MONO16; @@ -328,8 +298,7 @@ void ImageDisplay::setupScreenRectangle() material_->setDepthWriteEnabled(false); material_->setDepthCheckEnabled(false); - Ogre::TextureUnitState * tu = - material_->getTechnique(0)->getPass(0)->createTextureUnitState(); + Ogre::TextureUnitState * tu = material_->getTechnique(0)->getPass(0)->createTextureUnitState(); tu->setTextureName(texture_->getName()); tu->setTextureFiltering(Ogre::TFO_NONE); tu->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP); From 0becd68ee895e008907531676afdac6f727d4e17 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 24 Oct 2024 15:02:04 +0000 Subject: [PATCH 08/18] add other image types --- rviz_default_plugins/plugins_description.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/rviz_default_plugins/plugins_description.xml b/rviz_default_plugins/plugins_description.xml index 0b5039577..d87244bb0 100644 --- a/rviz_default_plugins/plugins_description.xml +++ b/rviz_default_plugins/plugins_description.xml @@ -120,6 +120,8 @@ The Image display creates a new rendering window with an image. sensor_msgs/msg/Image + sensor_msgs/msg/CompressedImage + theora_image_transport/msg/Packet Date: Thu, 24 Oct 2024 11:04:43 -0400 Subject: [PATCH 09/18] remove docker stuff --- .devcontainer/Dockerfile | 25 ------------------------- .devcontainer/devcontainer.json | 32 -------------------------------- 2 files changed, 57 deletions(-) delete mode 100644 .devcontainer/Dockerfile delete mode 100644 .devcontainer/devcontainer.json diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile deleted file mode 100644 index 2542b5667..000000000 --- a/.devcontainer/Dockerfile +++ /dev/null @@ -1,25 +0,0 @@ -FROM ubuntu:noble -ENV DEBIAN_FRONTEND=noninteractive -RUN apt update && apt install -y locales && locale-gen en_US en_US.UTF-8 && update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 -ENV LANG=en_US.UTF-8 -RUN apt install -y software-properties-common && add-apt-repository universe -RUN apt update && apt install -y curl && 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/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" > /etc/apt/sources.list.d/ros2.list -RUN apt update && apt install -y \ - python3-flake8-blind-except \ - python3-flake8-class-newline \ - python3-flake8-deprecated \ - python3-mypy \ - python3-pip \ - python3-pytest \ - python3-pytest-cov \ - python3-pytest-mock \ - python3-pytest-repeat \ - python3-pytest-rerunfailures \ - python3-pytest-runner \ - python3-pytest-timeout \ - ros-dev-tools -WORKDIR /ros2_rolling -ENV ROS_DISTRO="rolling" -RUN mkdir src && vcs import --input https://raw.githubusercontent.com/ros2/ros2/rolling/ros2.repos src -RUN apt upgrade -y && rosdep init && rosdep update && rosdep install --from-paths src --ignore-src -y --skip-keys "fastcdr rti-connext-dds-6.0.1 urdfdom_headers" \ No newline at end of file diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json deleted file mode 100644 index a6e77dd6f..000000000 --- a/.devcontainer/devcontainer.json +++ /dev/null @@ -1,32 +0,0 @@ -// For format details, see https://aka.ms/devcontainer.json. For config options, see the -// README at: https://github.com/devcontainers/templates/tree/main/src/docker-existing-dockerfile -{ - "name": "rviz_rolling", - "build": { - // Sets the run context to one level up instead of the .devcontainer folder. - // Update the 'dockerFile' property if you aren't using the standard 'Dockerfile' filename. - "dockerfile": "Dockerfile" - }, - - // Features to add to the dev container. More info: https://containers.dev/features. - // "features": {}, - - // Use 'forwardPorts' to make a list of ports inside the container available locally. - // "forwardPorts": [], - - // Uncomment the next line to run commands after the container is created. - // "postCreateCommand": "cat /etc/os-release", - - // Configure tool-specific properties. - // "customizations": {} - - - // Uncomment to connect as an existing user other than the container default. More info: https://aka.ms/dev-containers-non-root. - // "remoteUser": "devcontainer" - "workspaceMount": "source=${localWorkspaceFolder},target=/ros2_rolling/src/ros2/rviz,type=bind", - "workspaceFolder": "/ros2_rolling/src/ros2/rviz", - //"overrideCommand": false - "runArgs": [ - "--network=host" - ] -} From b658026866e5d8355f5a6f0727fb31c9ab1abd04 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 24 Oct 2024 11:08:56 -0400 Subject: [PATCH 10/18] update README --- README.md | 58 +++++++++++++++++++++++++++---------------------------- 1 file changed, 29 insertions(+), 29 deletions(-) diff --git a/README.md b/README.md index 4367f51ed..63b2ff7d3 100644 --- a/README.md +++ b/README.md @@ -12,35 +12,35 @@ These features have already been ported from `ros-visualization/rviz` to `ros2/r The basic documentation can still be found on the RViz [wiki page](http://www.ros.org/wiki/rviz). For some displays, the [documentation is updated](docs/FEATURES.md). -| Displays | Tools | View Controller | Panels | -| --------------------- | ------------- | --------------------- | --------------- | -| Axes | Move Camera | Orbit | Displays | -| Camera | Focus Camera | XY Orbit | Help | -| DepthCloud | Measure | First Person | Selections | -| Effort | Select | Third Person Follower | Time | -| Fluid | 2D Nav Goal | Top Down Orthographic | Tool Properties | -| Grid | Publish Point | | Views | -| Grid Cells | Initial Pose | -| Illuminance | Interact | -| Image | -| Interactive Marker | -| Laser Scan | -| Map | -| Marker | -| Marker Array | -| Odometry | -| Point Cloud (1 and 2) | -| Point | -| Polygon | -| Pose | -| Pose Array | -| Pose With Covariance | -| Range | -| Relative Humidity | -| Robot Model | -| Temperature | -| TF | -| Wrench | +| Displays | Tools | View Controller | Panels | +| ----------------------------------- | ------------- | --------------------- | --------------- | +| Axes | Move Camera | Orbit | Displays | +| Camera | Focus Camera | XY Orbit | Help | +| DepthCloud | Measure | First Person | Selections | +| Effort | Select | Third Person Follower | Time | +| Fluid | 2D Nav Goal | Top Down Orthographic | Tool Properties | +| Grid | Publish Point | | Views | +| Grid Cells | Initial Pose | +| Illuminance | Interact | +| Image (and `image_transport` types) | +| Interactive Marker | +| Laser Scan | +| Map | +| Marker | +| Marker Array | +| Odometry | +| Point Cloud (1 and 2) | +| Point | +| Polygon | +| Pose | +| Pose Array | +| Pose With Covariance | +| Range | +| Relative Humidity | +| Robot Model | +| Temperature | +| TF | +| Wrench | ### Not yet ported From 5d7eebc7f5811a9e892e042f70d369f782499bf7 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 24 Oct 2024 11:17:09 -0400 Subject: [PATCH 11/18] remove unnecessary cast --- .../src/rviz_default_plugins/displays/image/image_display.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 786f10ca5..8f819e5a0 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -191,7 +191,7 @@ void ImageDisplay::subscribe() // are automatically converted. subscription_ = image_transport_.subscribe( rviz_default_plugins::displays::getBaseTopicFromTopic(topic_property_->getTopicStd()), - (uint32_t)qos_profile.get_rmw_qos_profile().depth, // TODO(mjforan) try without cast + qos_profile.get_rmw_qos_profile().depth, &ImageDisplay::incomingMessage, this, new image_transport::TransportHints( node.get(), getTransportFromTopic(topic_property_->getStdString()), "image_transport")); From 752fa4357e62084a73007b086c71e6783e9ae832 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 7 Nov 2024 15:56:06 +0000 Subject: [PATCH 12/18] property to override transport, make sure transport is installed before subscribing --- .../displays/image/image_display.hpp | 6 ++- .../displays/image/image_display.cpp | 46 ++++++++++++++++--- 2 files changed, 45 insertions(+), 7 deletions(-) diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp index 39e9b251f..3cc7d2ad0 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp @@ -87,10 +87,13 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay public Q_SLOTS: virtual void updateNormalizeOptions(); +protected Q_SLOTS: + void updateTopic() override; + void subscribe() override; + protected: void onEnable() override; void onDisable() override; - void subscribe() override; void unsubscribe() override; void incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg); @@ -113,6 +116,7 @@ public Q_SLOTS: std::unique_ptr render_panel_; + rviz_common::properties::EnumProperty * transport_override_property_; rviz_common::properties::BoolProperty * normalize_property_; rviz_common::properties::FloatProperty * min_property_; rviz_common::properties::FloatProperty * max_property_; diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 8f819e5a0..7849bc212 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -87,6 +87,12 @@ ImageDisplay::ImageDisplay(std::unique_ptr texture) this->qos_profile_property_ = new rviz_common::properties::QosProfileProperty(this->topic_property_, rclcpp::QoS(5)); + transport_override_property_ = new rviz_common::properties::EnumProperty( + "Transport Override", "", "By default this display uses the topic name to determine the" + + " image_transport type. If this is not possible, use this field to manually set the transport.", + this->topic_property_, SLOT(subscribe()), this + ); + normalize_property_ = new rviz_common::properties::BoolProperty( "Normalize Range", true, "If set to true, will try to estimate the range of possible values from the received images.", @@ -136,16 +142,16 @@ void ImageDisplay::incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr ImageTransportDisplay::incomingMessage(img_msg); } -void ImageDisplay::subscribe() +void ImageDisplay::updateTopic() { if (!isEnabled()) { return; } + transport_override_property_->setStdString(""); - // TODO(mjforan) this should really be in onInitialize but setStatus does not work there // Populate topic message types based on installed image_transport plugins image_transport::ImageTransport image_transport_(rviz_ros_node_.lock()->get_raw_node()); - std::vector transports = image_transport_.getLoadableTransports(); + std::vector loadable_transports = image_transport_.getLoadableTransports(); std::vector message_types; // Map to message types const std::unordered_map transport_message_types_ = { @@ -158,10 +164,13 @@ void ImageDisplay::subscribe() std::string transports_str = ""; rviz_common::properties::StatusProperty::Level transports_status_level = rviz_common::properties::StatusProperty::Ok; - for (std::string & transport : transports) { + // Populate topic message types and transport override options + transport_override_property_->addOptionStd(""); + for (std::string & transport : loadable_transports) { transport = transport.substr(transport.find_last_of('/') + 1); try { message_types.push_back(QString::fromStdString(transport_message_types_.at(transport))); + transport_override_property_->addOptionStd(transport); transports_str += transport + ", "; } catch (const std::out_of_range & e) { transports_status_level = rviz_common::properties::StatusProperty::Warn; @@ -175,13 +184,21 @@ void ImageDisplay::subscribe() ((rviz_common::properties::RosTopicMultiProperty *)topic_property_) ->setMessageTypes(message_types); + rviz_default_plugins::displays::ImageTransportDisplay::updateTopic(); +} + +void ImageDisplay::subscribe() +{ + if (!isEnabled()) { + return; + } + if (topic_property_->isEmpty()) { setStatus( rviz_common::properties::StatusProperty::Error, "Topic", QString("Error subscribing: Empty topic name")); return; } - try { rclcpp::Node::SharedPtr node = rviz_ros_node_.lock()->get_raw_node(); image_transport::ImageTransport image_transport_(node); @@ -189,12 +206,29 @@ void ImageDisplay::subscribe() // image_transport::SubscriberFilter, which requires a different callback for each transport // type. image_transport::Subscriber only requires one callback for "raw" and the other types // are automatically converted. + std::vector transports = image_transport_.getLoadableTransports(); + // Strip down to basic transport names + for (std::string & transport : transports) { + transport = transport.substr(transport.find_last_of('/') + 1); + } + // Use override property for transport hint if set, otherwise deduce from topic name + std::string transport_hint = transport_override_property_->getStdString(); + if (transport_hint.empty()) { + transport_hint = getTransportFromTopic(topic_property_->getStdString()); + } + // Check if the specified transport is in the list of loadable transports + if (std::find(transports.begin(), transports.end(), transport_hint) == transports.end()) { + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", + QString("Error subscribing: Specified image transport is not installed")); + return; + } subscription_ = image_transport_.subscribe( rviz_default_plugins::displays::getBaseTopicFromTopic(topic_property_->getTopicStd()), qos_profile.get_rmw_qos_profile().depth, &ImageDisplay::incomingMessage, this, new image_transport::TransportHints( - node.get(), getTransportFromTopic(topic_property_->getStdString()), "image_transport")); + node.get(), transport_hint, "image_transport")); setStatus(rviz_common::properties::StatusProperty::Ok, "Topic", "OK"); } catch (rclcpp::exceptions::InvalidTopicNameError & e) { From b1638dcc605fc6236990a3a025fa5f2f88156270 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Thu, 7 Nov 2024 18:12:59 +0000 Subject: [PATCH 13/18] fix build server compilation error --- .../rviz_default_plugins/displays/image/image_display.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 7849bc212..0c2931f76 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -88,8 +88,9 @@ ImageDisplay::ImageDisplay(std::unique_ptr texture) new rviz_common::properties::QosProfileProperty(this->topic_property_, rclcpp::QoS(5)); transport_override_property_ = new rviz_common::properties::EnumProperty( - "Transport Override", "", "By default this display uses the topic name to determine the" + - " image_transport type. If this is not possible, use this field to manually set the transport.", + "Transport Override", "", QString("By default this display uses the topic name to ") + + QString("determine the image_transport type. If this is not possible, use this ") + + QString("field to manually set the transport."), this->topic_property_, SLOT(subscribe()), this ); From 7063d9f81d444bade9bd4f191a70015d3999f65f Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Fri, 8 Nov 2024 14:36:06 +0000 Subject: [PATCH 14/18] fix duplicate transport override items --- .../properties/ros_topic_multi_property.hpp | 2 + .../displays/image/image_display.hpp | 1 - .../displays/image/image_display.cpp | 48 ++++++++----------- 3 files changed, 21 insertions(+), 30 deletions(-) diff --git a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp index 4572dac4c..df4f248a8 100644 --- a/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp +++ b/rviz_common/include/rviz_common/properties/ros_topic_multi_property.hpp @@ -30,6 +30,8 @@ #ifndef RVIZ_COMMON__PROPERTIES__ROS_TOPIC_MULTI_PROPERTY_HPP_ #define RVIZ_COMMON__PROPERTIES__ROS_TOPIC_MULTI_PROPERTY_HPP_ +#include + #include #include diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp index 3cc7d2ad0..f1deaf2d8 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp @@ -88,7 +88,6 @@ public Q_SLOTS: virtual void updateNormalizeOptions(); protected Q_SLOTS: - void updateTopic() override; void subscribe() override; protected: diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 0c2931f76..1976b641c 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -41,6 +41,7 @@ #include #include #include +#include #include // NOLINT: cpplint is unable to handle the include order here @@ -117,40 +118,14 @@ ImageDisplay::ImageDisplay(std::unique_ptr texture) void ImageDisplay::onInitialize() { ITDClass::onInitialize(); - updateNormalizeOptions(); setupScreenRectangle(); - setupRenderPanel(); render_panel_->getRenderWindow()->setupSceneAfterInit( [this](Ogre::SceneNode * scene_node) {scene_node->attachObject(screen_rect_.get());}); -} - -ImageDisplay::~ImageDisplay() = default; - -void ImageDisplay::onEnable() {subscribe();} - -void ImageDisplay::onDisable() -{ - unsubscribe(); - clear(); -} - -// Need a signature with pass by reference for image_transport_.subscribe -void ImageDisplay::incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg) -{ - ImageTransportDisplay::incomingMessage(img_msg); -} -void ImageDisplay::updateTopic() -{ - if (!isEnabled()) { - return; - } - transport_override_property_->setStdString(""); - - // Populate topic message types based on installed image_transport plugins + // Populate message types and transport overrides based on installed image_transport plugins image_transport::ImageTransport image_transport_(rviz_ros_node_.lock()->get_raw_node()); std::vector loadable_transports = image_transport_.getLoadableTransports(); std::vector message_types; @@ -165,7 +140,7 @@ void ImageDisplay::updateTopic() std::string transports_str = ""; rviz_common::properties::StatusProperty::Level transports_status_level = rviz_common::properties::StatusProperty::Ok; - // Populate topic message types and transport override options + transport_override_property_->clearOptions(); transport_override_property_->addOptionStd(""); for (std::string & transport : loadable_transports) { transport = transport.substr(transport.find_last_of('/') + 1); @@ -178,14 +153,29 @@ void ImageDisplay::updateTopic() transports_str += "(unknown: " + transport + "), "; } } + // TODO(mjforan) setStatus doesn't work in onInitialize or updateTopic setStatusStd(transports_status_level, "Image Transports", transports_str); // Remove duplicates message_types.erase(std::unique(message_types.begin(), message_types.end()), message_types.end()); // Update the message types to allow in the topic_property_ ((rviz_common::properties::RosTopicMultiProperty *)topic_property_) ->setMessageTypes(message_types); +} - rviz_default_plugins::displays::ImageTransportDisplay::updateTopic(); +ImageDisplay::~ImageDisplay() = default; + +void ImageDisplay::onEnable() {subscribe();} + +void ImageDisplay::onDisable() +{ + unsubscribe(); + clear(); +} + +// Need a signature with pass by reference for image_transport_.subscribe +void ImageDisplay::incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg) +{ + ImageTransportDisplay::incomingMessage(img_msg); } void ImageDisplay::subscribe() From 60a69d2a2834a2db84935cdda8dc8cc6ec6f5cd2 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Tue, 12 Nov 2024 16:10:19 +0000 Subject: [PATCH 15/18] use custom QoS --- .../src/rviz_default_plugins/displays/image/image_display.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index 1976b641c..dd291d166 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -216,7 +216,7 @@ void ImageDisplay::subscribe() } subscription_ = image_transport_.subscribe( rviz_default_plugins::displays::getBaseTopicFromTopic(topic_property_->getTopicStd()), - qos_profile.get_rmw_qos_profile().depth, + qos_profile.get_rmw_qos_profile(), &ImageDisplay::incomingMessage, this, new image_transport::TransportHints( node.get(), transport_hint, "image_transport")); From 0bc298d498ae2c34c33df5d704bebad2d2cbc190 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Wed, 20 Nov 2024 15:02:37 +0000 Subject: [PATCH 16/18] combine image_transport_display and image_display --- .../displays/camera/camera_display.hpp | 4 +- .../displays/image/image_display.hpp | 39 ++- .../image/image_transport_display.hpp | 227 ------------------ .../displays/camera/camera_display.cpp | 8 +- .../displays/image/image_display.cpp | 140 ++++++++--- 5 files changed, 139 insertions(+), 279 deletions(-) delete mode 100644 rviz_default_plugins/include/rviz_default_plugins/displays/image/image_transport_display.hpp diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/camera/camera_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/camera/camera_display.hpp index e23ddd3fe..2666c19b5 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/camera/camera_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/camera/camera_display.hpp @@ -53,7 +53,7 @@ # include "sensor_msgs/msg/camera_info.hpp" # include "tf2_ros/message_filter.h" -# include "rviz_default_plugins/displays/image/image_transport_display.hpp" +# include "rviz_default_plugins/displays/image/image_display.hpp" # include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" # include "rviz_default_plugins/visibility_control.hpp" # include "rviz_rendering/render_window.hpp" @@ -102,7 +102,7 @@ struct ImageDimensions * */ class RVIZ_DEFAULT_PLUGINS_PUBLIC CameraDisplay - : public rviz_default_plugins::displays::ImageTransportDisplay, + : public ImageDisplay, public Ogre::RenderTargetListener { Q_OBJECT diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp index f1deaf2d8..3f62ca1d6 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp @@ -38,9 +38,11 @@ #include #include // NOLINT cpplint cannot handle include order here +#include // NOLINT cpplint cannot handle include order here #include #include +#include #include @@ -50,9 +52,12 @@ #include "rviz_common/properties/float_property.hpp" #include "rviz_common/properties/int_property.hpp" #include "rviz_common/render_panel.hpp" -#include "rviz_default_plugins/displays/image/image_transport_display.hpp" #include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp" #include "rviz_default_plugins/visibility_control.hpp" +#include "get_transport_from_topic.hpp" +#include "image_transport/image_transport.hpp" +#include "image_transport/subscriber_filter.hpp" +#include "rviz_common/ros_topic_display.hpp" #endif namespace Ogre @@ -70,8 +75,7 @@ namespace displays * \class ImageDisplay * */ -class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay - : public rviz_default_plugins::displays::ImageTransportDisplay +class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay : public rviz_common::_RosTopicDisplay { Q_OBJECT @@ -81,26 +85,41 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay ~ImageDisplay() override; void onInitialize() override; - void update(float wall_dt, float ros_dt) override; + void update(float wall_dt, float ros_dt); void reset() override; public Q_SLOTS: virtual void updateNormalizeOptions(); protected Q_SLOTS: - void subscribe() override; + virtual void subscribe(); protected: void onEnable() override; void onDisable() override; - void unsubscribe() override; - + virtual void unsubscribe(); + void updateTopic() override; + void transformerChangedCallback() override; + void resetSubscription(); void incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg); + void setTopic(const QString & topic, const QString & datatype) override; /* This is called by incomingMessage(). */ - void processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) override; - - image_transport::Subscriber subscription_; + virtual void processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg); + + std::shared_ptr subscription_; + uint32_t messages_received_; + rclcpp::Time subscription_start_time_; + message_filters::Connection subscription_callback_; + const std::unordered_map transport_message_types_ = { + /* *INDENT-OFF* */ + {"raw", "sensor_msgs/msg/Image"}, + {"compressed", "sensor_msgs/msg/CompressedImage"}, + {"compressedDepth", "sensor_msgs/msg/CompressedImage"}, + {"theora", "theora_image_transport/msg/Packet"}, + {"zstd", "sensor_msgs/msg/CompressedImage"}, + /* *INDENT-ON* */ + }; private: void setupScreenRectangle(); diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_transport_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_transport_display.hpp deleted file mode 100644 index 7067291d8..000000000 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_transport_display.hpp +++ /dev/null @@ -1,227 +0,0 @@ -// Copyright (c) 2012, Willow Garage, Inc. -// Copyright (c) 2017, Bosch Software Innovations GmbH. -// Copyright (c) 2020, TNG Technology Consulting GmbH. -// 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__DISPLAYS__IMAGE__IMAGE_TRANSPORT_DISPLAY_HPP_ -#define RVIZ_DEFAULT_PLUGINS__DISPLAYS__IMAGE__IMAGE_TRANSPORT_DISPLAY_HPP_ - -#include -#include - -#include // NOLINT: cpplint is unable to handle the include order here - -#include "get_transport_from_topic.hpp" -#include "image_transport/image_transport.hpp" -#include "image_transport/subscriber_filter.hpp" -#include "rviz_common/ros_topic_display.hpp" - -namespace rviz_default_plugins -{ -namespace displays -{ - -template -class ImageTransportDisplay : public rviz_common::_RosTopicDisplay -{ -// No Q_OBJECT macro here, moc does not support Q_OBJECT in a templated class. - -public: -/// Convenience typedef so subclasses don't have to use -/// the long templated class name to refer to their super class. - typedef ImageTransportDisplay ITDClass; - - ImageTransportDisplay() - : messages_received_(0) - { - QString message_type = QString::fromStdString(rosidl_generator_traits::name()); - topic_property_->setMessageType(message_type); - topic_property_->setDescription(message_type + " topic to subscribe to."); - } - -/** -* When overriding this method, the onInitialize() method of this superclass has to be called. -* Otherwise, the ros node will not be initialized. -*/ - void onInitialize() override - { - _RosTopicDisplay::onInitialize(); - } - - ~ImageTransportDisplay() override - { - unsubscribe(); - } - - void reset() override - { - Display::reset(); - messages_received_ = 0; - } - - void setTopic(const QString & topic, const QString & datatype) override - { - (void) datatype; - topic_property_->setString(topic); - } - -protected: - void updateTopic() override - { - resetSubscription(); - } - - virtual void subscribe() - { - if (!isEnabled()) { - return; - } - - if (topic_property_->isEmpty()) { - setStatus( - rviz_common::properties::StatusProperty::Error, "Topic", - QString("Error subscribing: Empty topic name")); - return; - } - - try { - subscription_ = std::make_shared(); - rclcpp::Node::SharedPtr node = rviz_ros_node_.lock()->get_raw_node(); - subscription_->subscribe( - node.get(), - getBaseTopicFromTopic(topic_property_->getTopicStd()), - getTransportFromTopic(topic_property_->getTopicStd()), - qos_profile.get_rmw_qos_profile()); - subscription_start_time_ = node->now(); - subscription_callback_ = subscription_->registerCallback( - std::bind( - &ImageTransportDisplay::incomingMessage, this, std::placeholders::_1)); - setStatus(rviz_common::properties::StatusProperty::Ok, "Topic", "OK"); - } catch (rclcpp::exceptions::InvalidTopicNameError & e) { - setStatus( - rviz_common::properties::StatusProperty::Error, "Topic", - QString("Error subscribing: ") + e.what()); - } - } - - void transformerChangedCallback() override - { - resetSubscription(); - } - - void resetSubscription() - { - unsubscribe(); - reset(); - subscribe(); - context_->queueRender(); - } - - virtual void unsubscribe() - { - subscription_.reset(); - } - - void onEnable() override - { - subscribe(); - } - - void onDisable() override - { - unsubscribe(); - reset(); - } - -/// Incoming message callback. -/** -* Checks if the message pointer -* is valid, increments messages_received_, then calls -* processMessage(). -*/ - void incomingMessage(const typename MessageType::ConstSharedPtr msg) - { - if (!msg) { - return; - } - - ++messages_received_; - QString topic_str = QString::number(messages_received_) + " messages received"; - rviz_common::properties::StatusProperty::Level topic_status_level = - rviz_common::properties::StatusProperty::Ok; - // Append topic subscription frequency if we can lock rviz_ros_node_. - std::shared_ptr node_interface = - rviz_ros_node_.lock(); - if (node_interface != nullptr) { - try { - const double duration = - (node_interface->get_raw_node()->now() - subscription_start_time_).seconds(); - const double subscription_frequency = - static_cast(messages_received_) / duration; - topic_str += " at " + QString::number(subscription_frequency, 'f', 1) + " hz."; - } catch (const std::runtime_error & e) { - if (std::string(e.what()).find("can't subtract times with different time sources") != - std::string::npos) - { - topic_status_level = rviz_common::properties::StatusProperty::Warn; - topic_str += ". "; - topic_str += e.what(); - } else { - throw; - } - } - } - setStatus( - topic_status_level, - "Topic", - topic_str); - - processMessage(msg); - } - - -/// Implement this to process the contents of a message. -/** -* This is called by incomingMessage(). -*/ - virtual void processMessage(typename MessageType::ConstSharedPtr msg) = 0; - - uint32_t messages_received_; - - std::shared_ptr subscription_; - rclcpp::Time subscription_start_time_; - message_filters::Connection subscription_callback_; -}; - -} // end namespace displays -} // end namespace rviz_default_plugins - - -#endif // RVIZ_DEFAULT_PLUGINS__DISPLAYS__IMAGE__IMAGE_TRANSPORT_DISPLAY_HPP_ diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp index 053d03510..de31fe28f 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp @@ -167,7 +167,7 @@ CameraDisplay::~CameraDisplay() void CameraDisplay::onInitialize() { - ITDClass::onInitialize(); + ImageDisplay::onInitialize(); setupSceneNodes(); setupRenderPanel(); @@ -311,7 +311,7 @@ void CameraDisplay::fixedFrameChanged() void CameraDisplay::subscribe() { - ITDClass::subscribe(); + ImageDisplay::subscribe(); if (!subscription_) { return; @@ -380,7 +380,7 @@ void CameraDisplay::createCameraInfoSubscription() void CameraDisplay::unsubscribe() { - ITDClass::unsubscribe(); + ImageDisplay::unsubscribe(); caminfo_sub_.reset(); tf_filter_.reset(); } @@ -671,7 +671,7 @@ void CameraDisplay::processMessage(sensor_msgs::msg::Image::ConstSharedPtr msg) void CameraDisplay::reset() { - ITDClass::reset(); + ImageDisplay::reset(); clear(); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp index dd291d166..b08df6c61 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp @@ -48,6 +48,7 @@ #include #include #include +#include #include #include @@ -66,6 +67,7 @@ #include "rviz_rendering/render_window.hpp" #include "sensor_msgs/image_encodings.hpp" + namespace rviz_default_plugins { namespace displays @@ -75,7 +77,8 @@ ImageDisplay::ImageDisplay() : ImageDisplay(std::make_unique()) {} ImageDisplay::ImageDisplay(std::unique_ptr texture) -: texture_(std::move(texture)) +: messages_received_(0), + texture_(std::move(texture)) { // Remove the default single-type topic and replace with a multi-type topic property // This allows us to display image and compressed image topics in the topic list @@ -115,9 +118,17 @@ ImageDisplay::ImageDisplay(std::unique_ptr texture) got_float_image_ = false; } +// Need to override this method because of the new type RosTopicMultiProperty +void ImageDisplay::setTopic(const QString & topic, const QString & datatype) +{ + (void) datatype; + ((rviz_common::properties::RosTopicMultiProperty *)topic_property_) + ->setString(topic); +} + void ImageDisplay::onInitialize() { - ITDClass::onInitialize(); + _RosTopicDisplay::onInitialize(); updateNormalizeOptions(); setupScreenRectangle(); setupRenderPanel(); @@ -130,16 +141,6 @@ void ImageDisplay::onInitialize() std::vector loadable_transports = image_transport_.getLoadableTransports(); std::vector message_types; // Map to message types - const std::unordered_map transport_message_types_ = { - {"raw", "sensor_msgs/msg/Image"}, - {"compressed", "sensor_msgs/msg/CompressedImage"}, - {"compressedDepth", "sensor_msgs/msg/CompressedImage"}, - {"theora", "theora_image_transport/msg/Packet"}, - {"zstd", "sensor_msgs/msg/CompressedImage"}, - }; - std::string transports_str = ""; - rviz_common::properties::StatusProperty::Level transports_status_level = - rviz_common::properties::StatusProperty::Ok; transport_override_property_->clearOptions(); transport_override_property_->addOptionStd(""); for (std::string & transport : loadable_transports) { @@ -147,37 +148,78 @@ void ImageDisplay::onInitialize() try { message_types.push_back(QString::fromStdString(transport_message_types_.at(transport))); transport_override_property_->addOptionStd(transport); - transports_str += transport + ", "; } catch (const std::out_of_range & e) { - transports_status_level = rviz_common::properties::StatusProperty::Warn; - transports_str += "(unknown: " + transport + "), "; + // This case will be handled in subscribe } } - // TODO(mjforan) setStatus doesn't work in onInitialize or updateTopic - setStatusStd(transports_status_level, "Image Transports", transports_str); // Remove duplicates - message_types.erase(std::unique(message_types.begin(), message_types.end()), message_types.end()); + message_types.erase( + std::unique(message_types.begin(), message_types.end()), message_types.end()); // Update the message types to allow in the topic_property_ ((rviz_common::properties::RosTopicMultiProperty *)topic_property_) ->setMessageTypes(message_types); } -ImageDisplay::~ImageDisplay() = default; +ImageDisplay::~ImageDisplay() +{ + unsubscribe(); +} void ImageDisplay::onEnable() {subscribe();} void ImageDisplay::onDisable() { unsubscribe(); - clear(); + reset(); } -// Need a signature with pass by reference for image_transport_.subscribe +/// Incoming message callback. +/** +* Checks if the message pointer +* is valid, increments messages_received_, then calls +* processMessage(). +*/ void ImageDisplay::incomingMessage(const sensor_msgs::msg::Image::ConstSharedPtr & img_msg) { - ImageTransportDisplay::incomingMessage(img_msg); + if (!img_msg) { + return; + } + + ++messages_received_; + QString topic_str = QString::number(messages_received_) + " messages received"; + rviz_common::properties::StatusProperty::Level topic_status_level = + rviz_common::properties::StatusProperty::Ok; + // Append topic subscription frequency if we can lock rviz_ros_node_. + std::shared_ptr node_interface = + rviz_ros_node_.lock(); + if (node_interface != nullptr) { + try { + const double duration = + (node_interface->get_raw_node()->now() - subscription_start_time_).seconds(); + const double subscription_frequency = + static_cast(messages_received_) / duration; + topic_str += " at " + QString::number(subscription_frequency, 'f', 1) + " hz."; + } catch (const std::runtime_error & e) { + if (std::string(e.what()).find("can't subtract times with different time sources") != + std::string::npos) + { + topic_status_level = rviz_common::properties::StatusProperty::Warn; + topic_str += ". "; + topic_str += e.what(); + } else { + throw; + } + } + } + setStatus( + topic_status_level, + "Topic", + topic_str); + + processMessage(img_msg); } + void ImageDisplay::subscribe() { if (!isEnabled()) { @@ -193,15 +235,22 @@ void ImageDisplay::subscribe() try { rclcpp::Node::SharedPtr node = rviz_ros_node_.lock()->get_raw_node(); image_transport::ImageTransport image_transport_(node); - // This part differs from the parent class. ImageTransportDisplay uses an - // image_transport::SubscriberFilter, which requires a different callback for each transport - // type. image_transport::Subscriber only requires one callback for "raw" and the other types - // are automatically converted. + // Check which image_transport plugins are installed std::vector transports = image_transport_.getLoadableTransports(); - // Strip down to basic transport names + std::string transports_str = ""; + rviz_common::properties::StatusProperty::Level transports_status_level = + rviz_common::properties::StatusProperty::Ok; + // Strip down to basic transport names, construct string for status display for (std::string & transport : transports) { transport = transport.substr(transport.find_last_of('/') + 1); + if (transport_message_types_.find(transport) == transport_message_types_.end()) { + transports_status_level = rviz_common::properties::StatusProperty::Warn; + transports_str += "(unknown: " + transport + "), "; + } else { + transports_str += transport + ", "; + } } + setStatusStd(transports_status_level, "Image Transports Installed", transports_str); // Use override property for transport hint if set, otherwise deduce from topic name std::string transport_hint = transport_override_property_->getStdString(); if (transport_hint.empty()) { @@ -214,13 +263,19 @@ void ImageDisplay::subscribe() QString("Error subscribing: Specified image transport is not installed")); return; } - subscription_ = image_transport_.subscribe( - rviz_default_plugins::displays::getBaseTopicFromTopic(topic_property_->getTopicStd()), - qos_profile.get_rmw_qos_profile(), - &ImageDisplay::incomingMessage, this, - new image_transport::TransportHints( - node.get(), transport_hint, "image_transport")); - + // image_transport::Subscriber only requires one callback for "raw" and the other types are + // automatically converted. + subscription_ = std::make_shared(); + subscription_->subscribe( + node.get(), + getBaseTopicFromTopic(topic_property_->getTopicStd()), + transport_hint, + qos_profile.get_rmw_qos_profile()); + subscription_start_time_ = node->now(); + subscription_callback_ = subscription_->registerCallback( + std::bind( + &rviz_default_plugins::displays::ImageDisplay::incomingMessage, + this, std::placeholders::_1)); setStatus(rviz_common::properties::StatusProperty::Ok, "Topic", "OK"); } catch (rclcpp::exceptions::InvalidTopicNameError & e) { setStatus( @@ -229,7 +284,19 @@ void ImageDisplay::subscribe() } } -void ImageDisplay::unsubscribe() {subscription_.shutdown();} +void ImageDisplay::updateTopic() {resetSubscription();} + +void ImageDisplay::transformerChangedCallback() {resetSubscription();} + +void ImageDisplay::resetSubscription() +{ + unsubscribe(); + reset(); + subscribe(); + context_->queueRender(); +} + +void ImageDisplay::unsubscribe() {subscription_.reset();} void ImageDisplay::updateNormalizeOptions() { @@ -287,7 +354,8 @@ void ImageDisplay::update(float wall_dt, float ros_dt) void ImageDisplay::reset() { - ITDClass::reset(); + Display::reset(); + messages_received_ = 0; clear(); } From 40711b70e54ce955cfb84a9e95063682d0e5476a Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Wed, 20 Nov 2024 22:47:01 +0000 Subject: [PATCH 17/18] add test for compressed image display --- rviz_default_plugins/CMakeLists.txt | 4 + rviz_default_plugins/package.xml | 2 + .../image/image_display_visual_test.cpp | 19 ++++- .../publishers/compressed_image_publisher.hpp | 84 +++++++++++++++++++ 4 files changed, 108 insertions(+), 1 deletion(-) create mode 100644 rviz_default_plugins/test/rviz_default_plugins/publishers/compressed_image_publisher.hpp diff --git a/rviz_default_plugins/CMakeLists.txt b/rviz_default_plugins/CMakeLists.txt index 1bdc96b17..1e2d73f64 100644 --- a/rviz_default_plugins/CMakeLists.txt +++ b/rviz_default_plugins/CMakeLists.txt @@ -883,6 +883,9 @@ if(BUILD_TESTING) ${SKIP_VISUAL_TESTS} TIMEOUT 180) if(TARGET image_display_visual_test) + find_package(OpenCV REQUIRED) + find_package(image_transport_plugins REQUIRED) + include_directories(${OpenCV_INCLUDE_DIRS}) target_include_directories(image_display_visual_test PRIVATE test) target_link_libraries(image_display_visual_test Qt5::Test @@ -890,6 +893,7 @@ if(BUILD_TESTING) rclcpp::rclcpp ${sensor_msgs_TARGETS} ${std_msgs_TARGETS} + ${OpenCV_LIBRARIES} ) endif() diff --git a/rviz_default_plugins/package.xml b/rviz_default_plugins/package.xml index f4fcf6444..be676a9b2 100644 --- a/rviz_default_plugins/package.xml +++ b/rviz_default_plugins/package.xml @@ -64,6 +64,8 @@ ament_lint_auto rviz_rendering_tests rviz_visual_testing_framework + image_transport_plugins + vision_opencv ament_cmake diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_visual_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_visual_test.cpp index a2ef35fbb..e40e2a958 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_visual_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_visual_test.cpp @@ -36,9 +36,11 @@ #include "../../page_objects/image_display_page_object.hpp" #include "../../publishers/image_publisher.hpp" +#include "../../publishers/compressed_image_publisher.hpp" + TEST_F(VisualTestFixture, test_image_display_with_published_image) { - auto path_publisher = std::make_unique( + auto image_publisher = std::make_unique( std::make_shared(), "image_frame"); setCamPose(Ogre::Vector3(0, 0, 16)); @@ -51,3 +53,18 @@ TEST_F(VisualTestFixture, test_image_display_with_published_image) { assertScreenShotsIdentity(); } + +TEST_F(VisualTestFixture, test_compressed_image_display_with_published_image) { + auto compressed_image_publisher = std::make_unique( + std::make_shared(), "image_frame"); + + setCamPose(Ogre::Vector3(0, 0, 16)); + setCamLookAt(Ogre::Vector3(0, 0, 0)); + + auto image_display = addDisplay(); + image_display->setTopic("/image"); + + captureRenderWindow(image_display); + + assertScreenShotsIdentity(); +} diff --git a/rviz_default_plugins/test/rviz_default_plugins/publishers/compressed_image_publisher.hpp b/rviz_default_plugins/test/rviz_default_plugins/publishers/compressed_image_publisher.hpp new file mode 100644 index 000000000..858866f4f --- /dev/null +++ b/rviz_default_plugins/test/rviz_default_plugins/publishers/compressed_image_publisher.hpp @@ -0,0 +1,84 @@ +// Copyright (c) 2018, Bosch Software Innovations GmbH. +// 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__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_ +#define RVIZ_DEFAULT_PLUGINS__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_ + +#include +#include +#include +#include + +#include +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/clock.hpp" +#include "sensor_msgs/msg/compressed_image.hpp" +#include "std_msgs/msg/header.hpp" + +using namespace std::chrono_literals; // NOLINT + +namespace nodes +{ + +class CompressedImagePublisher : public rclcpp::Node +{ +public: + explicit CompressedImagePublisher(const std::string & topic_name = "image") + : Node("compressed_image_publisher") + { + publisher = this->create_publisher(topic_name, 10); + timer = this->create_wall_timer(100ms, + std::bind(&CompressedImagePublisher::timer_callback, this)); + } + +private: + void timer_callback() + { + auto message = sensor_msgs::msg::CompressedImage(); + message.header = std_msgs::msg::Header(); + message.header.frame_id = "image_frame"; + message.header.stamp = rclcpp::Clock().now(); + + cv::Mat image(200, 300, CV_8UC3, cv::Scalar(0, 255, 0)); + std::vector compressed_image; + cv::imencode(".jpg", image, compressed_image); + + message.data.assign(compressed_image.begin(), compressed_image.end()); + message.format = "jpeg"; + publisher->publish(message); + } + + rclcpp::TimerBase::SharedPtr timer; + rclcpp::Publisher::SharedPtr publisher; +}; + +} // namespace nodes + +#endif // RVIZ_DEFAULT_PLUGINS__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_ From 287e57a30ac92d36546cf8a69831f773881a2e82 Mon Sep 17 00:00:00 2001 From: Matthew Foran Date: Fri, 10 Jan 2025 17:45:47 +0000 Subject: [PATCH 18/18] remove duplicate image texture --- .../rviz_default_plugins/displays/camera/camera_display.hpp | 3 --- .../rviz_default_plugins/displays/image/image_display.hpp | 6 ++---- .../rviz_default_plugins/displays/camera/camera_display.cpp | 1 - 3 files changed, 2 insertions(+), 8 deletions(-) diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/camera/camera_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/camera/camera_display.hpp index 2666c19b5..479ef47f0 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/camera/camera_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/camera/camera_display.hpp @@ -192,9 +192,6 @@ private Q_SLOTS: std::shared_ptr> tf_filter_; - std::unique_ptr texture_; - std::unique_ptr render_panel_; - std::shared_ptr> cache_images_; rviz_common::properties::FloatProperty * alpha_property_; diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp index 3f62ca1d6..672f3c57e 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/image/image_display.hpp @@ -120,6 +120,8 @@ protected Q_SLOTS: {"zstd", "sensor_msgs/msg/CompressedImage"}, /* *INDENT-ON* */ }; + std::unique_ptr texture_; + std::unique_ptr render_panel_; private: void setupScreenRectangle(); @@ -130,10 +132,6 @@ protected Q_SLOTS: std::unique_ptr screen_rect_; Ogre::MaterialPtr material_; - std::unique_ptr texture_; - - std::unique_ptr render_panel_; - rviz_common::properties::EnumProperty * transport_override_property_; rviz_common::properties::BoolProperty * normalize_property_; rviz_common::properties::FloatProperty * min_property_; diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp index de31fe28f..72720bc9d 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp @@ -121,7 +121,6 @@ static Ogre::Vector4 calculateScreenCorners( CameraDisplay::CameraDisplay() : tf_filter_(nullptr), - texture_(std::make_unique()), new_caminfo_(false), caminfo_ok_(false), force_render_(false)