Skip to content

Commit f8bb97e

Browse files
committed
remove image transport plugins as dependency
1 parent 3f3296d commit f8bb97e

File tree

4 files changed

+4
-5
lines changed

4 files changed

+4
-5
lines changed

.devcontainer/Dockerfile

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,5 +20,6 @@ RUN apt update && apt install -y \
2020
python3-pytest-timeout \
2121
ros-dev-tools
2222
WORKDIR /ros2_rolling
23+
ENV ROS_DISTRO="rolling"
2324
RUN mkdir src && vcs import --input https://raw.githubusercontent.com/ros2/ros2/rolling/ros2.repos src
2425
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"

rviz_default_plugins/CMakeLists.txt

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,6 @@ find_package(gz_math_vendor REQUIRED)
6565
find_package(gz-math REQUIRED)
6666

6767
find_package(image_transport REQUIRED)
68-
find_package(image_transport_plugins REQUIRED)
6968
find_package(interactive_markers REQUIRED)
7069
find_package(laser_geometry REQUIRED)
7170
find_package(map_msgs REQUIRED)
@@ -247,7 +246,6 @@ target_include_directories(rviz_default_plugins PUBLIC
247246
target_link_libraries(rviz_default_plugins PUBLIC
248247
${geometry_msgs_TARGETS}
249248
image_transport::image_transport
250-
${image_transport_plugins_TARGETS}
251249
interactive_markers::interactive_markers
252250
laser_geometry::laser_geometry
253251
${map_msgs_TARGETS}
@@ -286,7 +284,6 @@ ament_export_targets(rviz_default_plugins HAS_LIBRARY_TARGET)
286284
ament_export_dependencies(
287285
geometry_msgs
288286
image_transport
289-
image_transport_plugins
290287
interactive_markers
291288
laser_geometry
292289
map_msgs

rviz_default_plugins/package.xml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,6 @@
4040
<depend>geometry_msgs</depend>
4141
<depend>gz_math_vendor</depend>
4242
<depend>image_transport</depend>
43-
<depend>image_transport_plugins</depend>
4443
<depend>interactive_markers</depend>
4544
<depend>laser_geometry</depend>
4645
<depend>nav_msgs</depend>

rviz_default_plugins/src/rviz_default_plugins/displays/image/image_display.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,9 @@
6969

7070
#include <rviz_common/logging.hpp> // TODO remove when done
7171

72+
// TODO This may have introduced a segfault upon closing the program, but it is infrequent.
73+
// It's possible this existed before my changes.
74+
7275
namespace rviz_default_plugins
7376
{
7477
namespace displays
@@ -198,7 +201,6 @@ void ImageDisplay::subscribe(){
198201
// Update the message types to allow in the topic_property_
199202
((rviz_common::properties::RosTopicMultiProperty*)topic_property_)->setMessageTypes(message_types);
200203

201-
RVIZ_COMMON_LOG_INFO("subscribe");
202204
if (topic_property_->isEmpty()) {
203205
setStatus(
204206
rviz_common::properties::StatusProperty::Error, "Topic",

0 commit comments

Comments
 (0)