Skip to content
Open
Show file tree
Hide file tree
Changes from 23 commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
188eb92
first draft and devcontainer
mjforan Oct 10, 2024
d2e3289
devcontainer working, compressed image working
mjforan Oct 10, 2024
3f3296d
topic-multi property working (segfaults on close)
mjforan Oct 10, 2024
f8bb97e
remove image transport plugins as dependency
mjforan Oct 11, 2024
5928cd9
segfault was not my fault
mjforan Oct 11, 2024
fcdf022
minor cleanup and comments
mjforan Oct 15, 2024
ef95ae8
code style
mjforan Oct 24, 2024
0becd68
add other image types
mjforan Oct 24, 2024
64d0ef4
remove docker stuff
mjforan Oct 24, 2024
b658026
update README
mjforan Oct 24, 2024
5d7eebc
remove unnecessary cast
mjforan Oct 24, 2024
752fa43
property to override transport, make sure transport is installed bef…
mjforan Nov 7, 2024
b1638dc
fix build server compilation error
mjforan Nov 7, 2024
7063d9f
fix duplicate transport override items
mjforan Nov 8, 2024
60a69d2
use custom QoS
mjforan Nov 12, 2024
0bc298d
combine image_transport_display and image_display
mjforan Nov 20, 2024
40711b7
add test for compressed image display
mjforan Nov 20, 2024
287e57a
remove duplicate image texture
mjforan Jan 10, 2025
76559ad
address code review
mjforan Mar 25, 2025
35cb8de
revert header changes
mjforan Mar 27, 2025
6c70ede
remove extra dependency
mjforan Mar 28, 2025
dc6d160
Merge branch 'rolling' into compressed-image-display
mjforan May 15, 2025
c02e295
Merge remote-tracking branch 'origin/rolling' into compressed-image-d…
ahcorde May 19, 2025
3aa1332
Merge branch 'rolling' into compressed-image-display
mjforan Aug 22, 2025
a37c3c4
Update deprecated function calls
mjforan Aug 23, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,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
Expand Down Expand Up @@ -191,6 +192,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
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
// 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 <QString>

#include <string>
#include <vector>

#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
{

// Like RosTopicProperty but can accept multiple message types
class RVIZ_COMMON_PUBLIC RosTopicMultiProperty : public RosTopicProperty
{
Q_OBJECT

public:
explicit RosTopicMultiProperty(
const QString & name = QString(), const QString & default_value = QString(),
const std::vector<QString> & message_types = std::vector<QString>(),
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<QString> & message_types)
{
message_types_ = message_types;
}

std::vector<QString> getMessageTypes() const {return message_types_;}

protected Q_SLOTS:
void fillTopicList() override;

private:
// Hide the parent class methods which only take a single type
using RosTopicProperty::getMessageType;
using RosTopicProperty::setMessageType;

// Instead of one message type, store a list of allowed types
std::vector<QString> message_types_;
};

} // end namespace properties
} // end namespace rviz_common

#endif // RVIZ_COMMON__PROPERTIES__ROS_TOPIC_MULTI_PROPERTY_HPP_
27 changes: 9 additions & 18 deletions rviz_common/include/rviz_common/properties/ros_topic_property.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,40 +50,31 @@ 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();

private:
protected:
ros_integration::RosNodeAbstractionIface::WeakPtr rviz_ros_node_;
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

Expand Down
Original file line number Diff line number Diff line change
@@ -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.

#include "rviz_common/properties/ros_topic_multi_property.hpp"

#include <QApplication> // NOLINT: cpplint can't handle Qt imports
#include <algorithm>
#include <map>
#include <string>
#include <vector>

#include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp"

namespace rviz_common
{
namespace properties
{

void RosTopicMultiProperty::fillTopicList()
{
QApplication::setOverrideCursor(QCursor(Qt::WaitCursor));
clearOptions();

std::map<std::string, std::vector<std::string>> 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 (
std::find(message_types_.begin(), message_types_.end(), QString::fromStdString(type)) !=
message_types_.end())
{
addOptionStd(topic.first);
}
}
}
sortOptions();
QApplication::restoreOverrideCursor();
}

} // end namespace properties
} // end namespace rviz_common
3 changes: 3 additions & 0 deletions rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -922,13 +922,16 @@ if(BUILD_TESTING)
${SKIP_VISUAL_TESTS}
TIMEOUT 180)
if(TARGET image_display_visual_test)
find_package(OpenCV REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})
target_include_directories(image_display_visual_test PRIVATE test)
target_link_libraries(image_display_visual_test
Qt${QT_VERSION_MAJOR}::Test
rviz_visual_testing_framework::rviz_visual_testing_framework
rclcpp::rclcpp
${sensor_msgs_TARGETS}
${std_msgs_TARGETS}
${OpenCV_LIBRARIES}
)
endif()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -102,7 +102,7 @@ struct ImageDimensions
*
*/
class RVIZ_DEFAULT_PLUGINS_PUBLIC CameraDisplay
: public rviz_default_plugins::displays::ImageTransportDisplay<sensor_msgs::msg::Image>,
: public ImageDisplay,
public Ogre::RenderTargetListener
{
Q_OBJECT
Expand Down Expand Up @@ -192,9 +192,6 @@ private Q_SLOTS:
std::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::Image,
rviz_common::transformation::FrameTransformer>> tf_filter_;

std::unique_ptr<ROSImageTextureIface> texture_;
std::unique_ptr<rviz_common::RenderPanel> render_panel_;

std::shared_ptr<message_filters::Cache<sensor_msgs::msg::Image>> cache_images_;

rviz_common::properties::FloatProperty * alpha_property_;
Expand Down
Loading