diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CHANGELOG.rst b/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CHANGELOG.rst
deleted file mode 100644
index e7672ee001955..0000000000000
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CHANGELOG.rst
+++ /dev/null
@@ -1,24 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package rviz_2d_overlay_msgs
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-
-1.3.0 (2023-05-18)
-------------------
-* Removed old position message fields
-* Contributors: Dominik, Jonas Otto
-
-1.2.1 (2022-09-30)
-------------------
-
-1.2.0 (2022-09-27)
-------------------
-* Rename package from overlay_rviz_msgs to rviz_2d_overlay_msgs
-* Contributors: Jonas Otto
-
-1.1.0 (2022-09-11)
-------------------
-
-1.0.0 (2022-08-30)
-------------------
-* Create OverlayText message (currently same as jsk_rviz_plugins)
-* Contributors: Jonas Otto, Dominik Authaler
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CMakeLists.txt
deleted file mode 100644
index e23a4e755cbc4..0000000000000
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/CMakeLists.txt
+++ /dev/null
@@ -1,19 +0,0 @@
-cmake_minimum_required(VERSION 3.5)
-project(autoware_overlay_msgs)
-
-if (NOT CMAKE_CXX_STANDARD)
- set(CMAKE_CXX_STANDARD 17)
-endif ()
-
-
-# find dependencies
-find_package(ament_cmake REQUIRED)
-find_package(rosidl_default_generators REQUIRED)
-find_package(std_msgs REQUIRED)
-rosidl_generate_interfaces(${PROJECT_NAME}
- "msg/OverlayText.msg"
- DEPENDENCIES
- std_msgs
-)
-
-ament_package()
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/msg/OverlayText.msg b/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/msg/OverlayText.msg
deleted file mode 100644
index db3cf628b895b..0000000000000
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/msg/OverlayText.msg
+++ /dev/null
@@ -1,31 +0,0 @@
-uint8 ADD = 0
-uint8 DELETE = 1
-
-# constants for the horizontal and vertical alignment
-uint8 LEFT = 0
-uint8 RIGHT = 1
-uint8 CENTER = 2
-uint8 TOP = 3
-uint8 BOTTOM = 4
-
-uint8 action
-
-int32 width
-int32 height
-# Position: Positive values move the overlay towards the center of the window,
-# for center alignment positive values move the overlay towards the bottom right
-int32 horizontal_distance # Horizontal distance from left/right border or center, depending on alignment
-int32 vertical_distance # Vertical distance between from top/bottom border or center, depending on alignment
-
-# Alignment of the overlay withing RVIZ
-uint8 horizontal_alignment # one of LEFT, CENTER, RIGHT
-uint8 vertical_alignment # one of TOP, CENTER, BOTTOM
-
-std_msgs/ColorRGBA bg_color
-
-int32 line_width
-float32 text_size
-string font
-std_msgs/ColorRGBA fg_color
-
-string text
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/package.xml b/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/package.xml
deleted file mode 100644
index 4881b126ffffb..0000000000000
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_msgs/package.xml
+++ /dev/null
@@ -1,24 +0,0 @@
-
-
-
- autoware_overlay_msgs
- 1.3.0
- Messages describing 2D overlays for RVIZ, extracted/derived from the jsk_visualization package.
- Team Spatzenhirn
- BSD-3-Clause
-
- ament_cmake
- rosidl_default_generators
-
- autoware_auto_vehicle_msgs
- autoware_perception_msgs
- std_msgs
- unique_identifier_msgs
- rosidl_default_runtime
-
- rosidl_interface_packages
-
-
- ament_cmake
-
-
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt
index afb12bffeeaa7..aafc62fc90d25 100644
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt
+++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt
@@ -3,28 +3,13 @@ project(autoware_overlay_rviz_plugin)
# find dependencies
find_package(ament_cmake_auto REQUIRED)
-find_package(ament_cmake REQUIRED)
-find_package(autoware_auto_vehicle_msgs REQUIRED)
-find_package(tier4_planning_msgs REQUIRED)
-find_package(autoware_perception_msgs REQUIRED)
ament_auto_find_build_dependencies()
-find_package(autoware_overlay_msgs REQUIRED)
-
-find_package(rviz_common REQUIRED)
-find_package(rviz_rendering REQUIRED)
-find_package(rviz_ogre_vendor REQUIRED)
-find_package(std_msgs REQUIRED)
-
-set(
- headers_to_moc
- include/overlay_text_display.hpp
- include/signal_display.hpp
-
+set(headers_to_moc
+ include/signal_display.hpp
)
-set(
- headers_to_not_moc
+set(headers_to_not_moc
include/steering_wheel_display.hpp
include/gear_display.hpp
include/speed_display.hpp
@@ -34,47 +19,42 @@ set(
)
-
foreach(header "${headers_to_moc}")
- qt5_wrap_cpp(display_moc_files "${header}")
+ qt5_wrap_cpp(display_moc_files "${header}")
endforeach()
-set(
- display_source_files
- src/overlay_text_display.cpp
- src/overlay_utils.cpp
- src/signal_display.cpp
- src/steering_wheel_display.cpp
- src/gear_display.cpp
- src/speed_display.cpp
- src/turn_signals_display.cpp
- src/traffic_display.cpp
- src/speed_limit_display.cpp
-
+set(display_source_files
+ src/overlay_utils.cpp
+ src/signal_display.cpp
+ src/steering_wheel_display.cpp
+ src/gear_display.cpp
+ src/speed_display.cpp
+ src/turn_signals_display.cpp
+ src/traffic_display.cpp
+ src/speed_limit_display.cpp
)
-add_library(
- ${PROJECT_NAME} SHARED
- ${display_moc_files}
- ${headers_to_not_moc}
- ${display_source_files}
+add_library(${PROJECT_NAME} SHARED
+ ${display_moc_files}
+ ${headers_to_not_moc}
+ ${display_source_files}
)
set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 17)
target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic)
target_include_directories(
- ${PROJECT_NAME} PUBLIC
- $
- $
- ${Qt5Widgets_INCLUDE_DIRS}
- ${OpenCV_INCLUDE_DIRS}
+ ${PROJECT_NAME} PUBLIC
+ $
+ $
+ ${Qt5Widgets_INCLUDE_DIRS}
+ ${OpenCV_INCLUDE_DIRS}
)
target_link_libraries(
- ${PROJECT_NAME} PUBLIC
- rviz_ogre_vendor::OgreMain
- rviz_ogre_vendor::OgreOverlay
+ ${PROJECT_NAME} PUBLIC
+ rviz_ogre_vendor::OgreMain
+ rviz_ogre_vendor::OgreOverlay
)
@@ -85,22 +65,19 @@ target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNC
pluginlib_export_plugin_description_file(rviz_common plugins_description.xml)
-ament_target_dependencies(
- ${PROJECT_NAME}
- PUBLIC
- rviz_common
- rviz_rendering
- autoware_overlay_msgs
- autoware_auto_vehicle_msgs
- tier4_planning_msgs
- autoware_perception_msgs
+ament_target_dependencies(${PROJECT_NAME} PUBLIC
+ rviz_common
+ rviz_rendering
+ autoware_auto_vehicle_msgs
+ tier4_planning_msgs
+ autoware_perception_msgs
)
ament_export_include_directories(include)
ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET)
ament_export_dependencies(
- rviz_common
- rviz_ogre_vendor
+ rviz_common
+ rviz_ogre_vendor
)
if(BUILD_TESTING)
@@ -109,32 +86,32 @@ if(BUILD_TESTING)
endif()
install(
- TARGETS ${PROJECT_NAME}
- EXPORT ${PROJECT_NAME}
- ARCHIVE DESTINATION lib
- LIBRARY DESTINATION lib
- RUNTIME DESTINATION bin
- INCLUDES DESTINATION include
+ TARGETS ${PROJECT_NAME}
+ EXPORT ${PROJECT_NAME}
+ ARCHIVE DESTINATION lib
+ LIBRARY DESTINATION lib
+ RUNTIME DESTINATION bin
+ INCLUDES DESTINATION include
)
install(
- DIRECTORY include/
- DESTINATION include
+ DIRECTORY include/
+ DESTINATION include
)
install(
- TARGETS
- DESTINATION lib/${PROJECT_NAME}
+ TARGETS
+ DESTINATION lib/${PROJECT_NAME}
)
# Copy the assets directory to the installation directory
install(
- DIRECTORY assets/
- DESTINATION share/${PROJECT_NAME}/assets
+ DIRECTORY assets/
+ DESTINATION share/${PROJECT_NAME}/assets
)
add_definitions(-DQT_NO_KEYWORDS)
ament_package(
- CONFIG_EXTRAS "autoware_overlay_rviz_plugin-extras.cmake"
+ CONFIG_EXTRAS "autoware_overlay_rviz_plugin-extras.cmake"
)
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_text_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_text_display.hpp
deleted file mode 100644
index ccea51b9a5349..0000000000000
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_text_display.hpp
+++ /dev/null
@@ -1,157 +0,0 @@
-// Copyright 2024 The Autoware Contributors
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-// -*- mode: c++; -*-
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2022, Team Spatzenhirn
- * Copyright (c) 2014, JSK Lab
- * 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/o2r other materials provided
- * with the distribution.
- * * Neither the name of the JSK Lab nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-#ifndef OVERLAY_TEXT_DISPLAY_HPP_
-#define OVERLAY_TEXT_DISPLAY_HPP_
-
-#include "autoware_overlay_msgs/msg/overlay_text.hpp"
-#ifndef Q_MOC_RUN
-#include "overlay_utils.hpp"
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-#include
-
-#include
-#endif
-
-namespace autoware_overlay_rviz_plugin
-{
-class OverlayTextDisplay
-: public rviz_common::RosTopicDisplay
-{
- Q_OBJECT
-public:
- OverlayTextDisplay();
- virtual ~OverlayTextDisplay();
-
-protected:
- autoware_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_;
-
- int texture_width_;
- int texture_height_;
-
- bool overtake_fg_color_properties_;
- bool overtake_bg_color_properties_;
- bool overtake_position_properties_;
- bool align_bottom_;
- bool invert_shadow_;
- QColor bg_color_;
- QColor fg_color_;
- int text_size_;
- int line_width_;
- std::string text_;
- QStringList font_families_;
- std::string font_;
- int horizontal_dist_;
- int vertical_dist_;
- HorizontalAlignment horizontal_alignment_;
- VerticalAlignment vertical_alignment_;
-
- void onInitialize() override;
- void onEnable() override;
- void onDisable() override;
- void update(float wall_dt, float ros_dt) override;
- void reset() override;
-
- bool require_update_texture_;
- // properties are raw pointers since they are owned by Qt
- rviz_common::properties::BoolProperty * overtake_position_properties_property_;
- rviz_common::properties::BoolProperty * overtake_fg_color_properties_property_;
- rviz_common::properties::BoolProperty * overtake_bg_color_properties_property_;
- rviz_common::properties::BoolProperty * align_bottom_property_;
- rviz_common::properties::BoolProperty * invert_shadow_property_;
- rviz_common::properties::IntProperty * hor_dist_property_;
- rviz_common::properties::IntProperty * ver_dist_property_;
- rviz_common::properties::EnumProperty * hor_alignment_property_;
- rviz_common::properties::EnumProperty * ver_alignment_property_;
- rviz_common::properties::IntProperty * width_property_;
- rviz_common::properties::IntProperty * height_property_;
- rviz_common::properties::IntProperty * text_size_property_;
- rviz_common::properties::IntProperty * line_width_property_;
- rviz_common::properties::ColorProperty * bg_color_property_;
- rviz_common::properties::FloatProperty * bg_alpha_property_;
- rviz_common::properties::ColorProperty * fg_color_property_;
- rviz_common::properties::FloatProperty * fg_alpha_property_;
- rviz_common::properties::EnumProperty * font_property_;
-
-protected Q_SLOTS:
- void updateOvertakePositionProperties();
- void updateOvertakeFGColorProperties();
- void updateOvertakeBGColorProperties();
- void updateAlignBottom();
- void updateInvertShadow();
- void updateHorizontalDistance();
- void updateVerticalDistance();
- void updateHorizontalAlignment();
- void updateVerticalAlignment();
- void updateWidth();
- void updateHeight();
- void updateTextSize();
- void updateFGColor();
- void updateFGAlpha();
- void updateBGColor();
- void updateBGAlpha();
- void updateFont();
- void updateLineWidth();
-
-private:
- void processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg) override;
-};
-} // namespace autoware_overlay_rviz_plugin
-
-#endif // OVERLAY_TEXT_DISPLAY_HPP_
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp
index 8581628ef0bce..b9c060899bace 100644
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp
+++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp
@@ -54,8 +54,6 @@
#include
#include
-#include "autoware_overlay_msgs/msg/overlay_text.hpp"
-
#include
#include
#include
@@ -89,17 +87,9 @@ class ScopedPixelBuffer
Ogre::HardwarePixelBufferSharedPtr pixel_buffer_;
};
-enum class VerticalAlignment : uint8_t {
- CENTER = autoware_overlay_msgs::msg::OverlayText::CENTER,
- TOP = autoware_overlay_msgs::msg::OverlayText::TOP,
- BOTTOM = autoware_overlay_msgs::msg::OverlayText::BOTTOM,
-};
+enum class VerticalAlignment : uint8_t { CENTER, TOP, BOTTOM };
-enum class HorizontalAlignment : uint8_t {
- LEFT = autoware_overlay_msgs::msg::OverlayText::LEFT,
- RIGHT = autoware_overlay_msgs::msg::OverlayText::RIGHT,
- CENTER = autoware_overlay_msgs::msg::OverlayText::CENTER
-};
+enum class HorizontalAlignment : uint8_t { LEFT, RIGHT, CENTER };
/**
* Helper class for realizing an overlay object on top of the rviz 3D panel.
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml
index da075b2648937..4d2f53e1e27ed 100644
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml
+++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml
@@ -12,7 +12,6 @@
BSD-3-Clause
autoware_auto_vehicle_msgs
- autoware_overlay_msgs
autoware_perception_msgs
boost
rviz_common
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_text_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_text_display.cpp
deleted file mode 100644
index b853e14a5858d..0000000000000
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_text_display.cpp
+++ /dev/null
@@ -1,556 +0,0 @@
-// Copyright 2024 The Autoware Contributors
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-// -*- mode: c++; -*-
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2022, Team Spatzenhirn
- * Copyright (c) 2014, JSK Lab
- * 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/o2r other materials provided
- * with the distribution.
- * * Neither the name of the JSK Lab nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-
-#include "overlay_text_display.hpp"
-
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include
-#include
-
-#include
-#include
-#include
-
-#include
-#include
-
-namespace autoware_overlay_rviz_plugin
-{
-OverlayTextDisplay::OverlayTextDisplay()
-: texture_width_(0),
- texture_height_(0),
- bg_color_(0, 0, 0, 0),
- fg_color_(255, 255, 255, 255.0),
- text_size_(14),
- line_width_(2),
- text_(""),
- font_(""),
- require_update_texture_(false)
-{
- overtake_position_properties_property_ = new rviz_common::properties::BoolProperty(
- "Overtake Position Properties", false,
- "overtake position properties specified by message such as left, top and font", this,
- SLOT(updateOvertakePositionProperties()));
- overtake_fg_color_properties_property_ = new rviz_common::properties::BoolProperty(
- "Overtake FG Color Properties", false,
- "overtake color properties specified by message such as foreground color and alpha", this,
- SLOT(updateOvertakeFGColorProperties()));
- overtake_bg_color_properties_property_ = new rviz_common::properties::BoolProperty(
- "Overtake BG Color Properties", false,
- "overtake color properties specified by message such as background color and alpha", this,
- SLOT(updateOvertakeBGColorProperties()));
- align_bottom_property_ = new rviz_common::properties::BoolProperty(
- "Align Bottom", false, "align text with the bottom of the overlay region", this,
- SLOT(updateAlignBottom()));
- invert_shadow_property_ = new rviz_common::properties::BoolProperty(
- "Invert Shadow", false, "make shadow lighter than original text", this,
- SLOT(updateInvertShadow()));
- hor_dist_property_ = new rviz_common::properties::IntProperty(
- "hor_dist", 0, "horizontal distance to anchor", this, SLOT(updateHorizontalDistance()));
- ver_dist_property_ = new rviz_common::properties::IntProperty(
- "ver_dist", 0, "vertical distance to anchor", this, SLOT(updateVerticalDistance()));
- hor_alignment_property_ = new rviz_common::properties::EnumProperty(
- "hor_alignment", "left", "horizontal alignment of the overlay", this,
- SLOT(updateHorizontalAlignment()));
- hor_alignment_property_->addOption("left", autoware_overlay_msgs::msg::OverlayText::LEFT);
- hor_alignment_property_->addOption("center", autoware_overlay_msgs::msg::OverlayText::CENTER);
- hor_alignment_property_->addOption("right", autoware_overlay_msgs::msg::OverlayText::RIGHT);
- ver_alignment_property_ = new rviz_common::properties::EnumProperty(
- "ver_alignment", "top", "vertical alignment of the overlay", this,
- SLOT(updateVerticalAlignment()));
- ver_alignment_property_->addOption("top", autoware_overlay_msgs::msg::OverlayText::TOP);
- ver_alignment_property_->addOption("center", autoware_overlay_msgs::msg::OverlayText::CENTER);
- ver_alignment_property_->addOption("bottom", autoware_overlay_msgs::msg::OverlayText::BOTTOM);
- width_property_ = new rviz_common::properties::IntProperty(
- "width", 128, "width position", this, SLOT(updateWidth()));
- width_property_->setMin(0);
- height_property_ = new rviz_common::properties::IntProperty(
- "height", 128, "height position", this, SLOT(updateHeight()));
- height_property_->setMin(0);
- text_size_property_ = new rviz_common::properties::IntProperty(
- "text size", 12, "text size", this, SLOT(updateTextSize()));
- text_size_property_->setMin(0);
- line_width_property_ = new rviz_common::properties::IntProperty(
- "line width", 2, "line width", this, SLOT(updateLineWidth()));
- line_width_property_->setMin(0);
- fg_color_property_ = new rviz_common::properties::ColorProperty(
- "Foreground Color", QColor(25, 255, 240), "Foreground Color", this, SLOT(updateFGColor()));
- fg_alpha_property_ = new rviz_common::properties::FloatProperty(
- "Foreground Alpha", 0.8, "Foreground Alpha", this, SLOT(updateFGAlpha()));
- fg_alpha_property_->setMin(0.0);
- fg_alpha_property_->setMax(1.0);
- bg_color_property_ = new rviz_common::properties::ColorProperty(
- "Background Color", QColor(0, 0, 0), "Background Color", this, SLOT(updateBGColor()));
- bg_alpha_property_ = new rviz_common::properties::FloatProperty(
- "Background Alpha", 0.8, "Background Alpha", this, SLOT(updateBGAlpha()));
- bg_alpha_property_->setMin(0.0);
- bg_alpha_property_->setMax(1.0);
-
- QFontDatabase database;
- font_families_ = database.families();
- font_property_ = new rviz_common::properties::EnumProperty(
- "font", "DejaVu Sans Mono", "font", this, SLOT(updateFont()));
- for (ssize_t i = 0; i < font_families_.size(); i++) {
- font_property_->addOption(font_families_[i], static_cast(i));
- }
-}
-
-OverlayTextDisplay::~OverlayTextDisplay()
-{
- onDisable();
-}
-
-void OverlayTextDisplay::onEnable()
-{
- if (overlay_) {
- overlay_->show();
- }
- subscribe();
-}
-
-void OverlayTextDisplay::onDisable()
-{
- if (overlay_) {
- overlay_->hide();
- }
- unsubscribe();
-}
-
-// only the first time
-void OverlayTextDisplay::onInitialize()
-{
- RTDClass::onInitialize();
- rviz_rendering::RenderSystem::get()->prepareOverlays(scene_manager_);
-
- onEnable();
- updateTopic();
- updateOvertakePositionProperties();
- updateOvertakeFGColorProperties();
- updateOvertakeBGColorProperties();
- updateAlignBottom();
- updateInvertShadow();
- updateHorizontalDistance();
- updateVerticalDistance();
- updateHorizontalAlignment();
- updateVerticalAlignment();
- updateWidth();
- updateHeight();
- updateTextSize();
- updateFGColor();
- updateFGAlpha();
- updateBGColor();
- updateBGAlpha();
- updateFont();
- updateLineWidth();
- require_update_texture_ = true;
-}
-
-void OverlayTextDisplay::update(float /*wall_dt*/, float /*ros_dt*/)
-{
- if (!require_update_texture_) {
- return;
- }
- if (!isEnabled()) {
- return;
- }
- if (!overlay_) {
- return;
- }
-
- overlay_->updateTextureSize(texture_width_, texture_height_);
- {
- autoware_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer();
- QImage Hud = buffer.getQImage(*overlay_, bg_color_);
- QPainter painter(&Hud);
- painter.setRenderHint(QPainter::Antialiasing, true);
- painter.setPen(QPen(fg_color_, std::max(line_width_, 1), Qt::SolidLine));
- uint16_t w = overlay_->getTextureWidth();
- uint16_t h = overlay_->getTextureHeight();
-
- // font
- if (text_size_ != 0) {
- // QFont font = painter.font();
- QFont font(font_.length() > 0 ? font_.c_str() : "Liberation Sans");
- font.setPointSize(text_size_);
- font.setBold(true);
- painter.setFont(font);
- }
- if (text_.length() > 0) {
- QColor shadow_color;
- if (invert_shadow_)
- shadow_color = Qt::white; // fg_color_.lighter();
- else
- shadow_color = Qt::black; // fg_color_.darker();
- shadow_color.setAlpha(fg_color_.alpha());
-
- std::string color_wrapped_text =
- (boost::format("%1%") % text_ %
- fg_color_.red() % fg_color_.green() % fg_color_.blue() % fg_color_.alpha())
- .str();
-
- // find a remove "color: XXX;" regex match to generate a proper shadow
- std::regex color_tag_re("color:.+?;");
- std::string null_char("");
- std::string formatted_text_ = std::regex_replace(text_, color_tag_re, null_char);
- std::string color_wrapped_shadow =
- (boost::format("%1%") %
- formatted_text_ % shadow_color.red() % shadow_color.green() % shadow_color.blue() %
- shadow_color.alpha())
- .str();
-
- QStaticText static_text(
- boost::algorithm::replace_all_copy(color_wrapped_text, "\n", "
").c_str());
- static_text.setTextWidth(w);
-
- painter.setPen(QPen(shadow_color, std::max(line_width_, 1), Qt::SolidLine));
- QStaticText static_shadow(
- boost::algorithm::replace_all_copy(color_wrapped_shadow, "\n", "
").c_str());
- static_shadow.setTextWidth(w);
-
- if (!align_bottom_) {
- painter.drawStaticText(1, 1, static_shadow);
- painter.drawStaticText(0, 0, static_text);
- } else {
- QStaticText only_wrapped_text(color_wrapped_text.c_str());
- QFontMetrics fm(painter.fontMetrics());
- QRect text_rect = fm.boundingRect(
- 0, 0, w, h, Qt::TextWordWrap | Qt::AlignLeft | Qt::AlignTop,
- only_wrapped_text.text().remove(QRegExp("<[^>]*>")));
- painter.drawStaticText(1, h - text_rect.height() + 1, static_shadow);
- painter.drawStaticText(0, h - text_rect.height(), static_text);
- }
- }
- painter.end();
- }
- overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight());
- require_update_texture_ = false;
-}
-
-void OverlayTextDisplay::reset()
-{
- RTDClass::reset();
-
- if (overlay_) {
- overlay_->hide();
- }
-}
-
-void OverlayTextDisplay::processMessage(autoware_overlay_msgs::msg::OverlayText::ConstSharedPtr msg)
-{
- if (!isEnabled()) {
- return;
- }
- if (!overlay_) {
- static int count = 0;
- std::stringstream ss;
- ss << "OverlayTextDisplayObject" << count++;
- overlay_.reset(new autoware_overlay_rviz_plugin::OverlayObject(ss.str()));
- overlay_->show();
- }
- if (overlay_) {
- if (msg->action == autoware_overlay_msgs::msg::OverlayText::DELETE) {
- overlay_->hide();
- } else if (msg->action == autoware_overlay_msgs::msg::OverlayText::ADD) {
- overlay_->show();
- }
- }
-
- // store message for update method
- text_ = msg->text;
-
- if (!overtake_position_properties_) {
- texture_width_ = msg->width;
- texture_height_ = msg->height;
- text_size_ = msg->text_size;
- horizontal_dist_ = msg->horizontal_distance;
- vertical_dist_ = msg->vertical_distance;
-
- horizontal_alignment_ = HorizontalAlignment{msg->horizontal_alignment};
- vertical_alignment_ = VerticalAlignment{msg->vertical_alignment};
- }
- if (!overtake_bg_color_properties_)
- bg_color_ = QColor(
- msg->bg_color.r * 255.0, msg->bg_color.g * 255.0, msg->bg_color.b * 255.0,
- msg->bg_color.a * 255.0);
- if (!overtake_fg_color_properties_) {
- fg_color_ = QColor(
- msg->fg_color.r * 255.0, msg->fg_color.g * 255.0, msg->fg_color.b * 255.0,
- msg->fg_color.a * 255.0);
- font_ = msg->font;
- line_width_ = msg->line_width;
- }
- if (overlay_) {
- overlay_->setPosition(
- horizontal_dist_, vertical_dist_, horizontal_alignment_, vertical_alignment_);
- }
- require_update_texture_ = true;
-}
-
-void OverlayTextDisplay::updateOvertakePositionProperties()
-{
- if (!overtake_position_properties_ && overtake_position_properties_property_->getBool()) {
- updateVerticalDistance();
- updateHorizontalDistance();
- updateVerticalAlignment();
- updateHorizontalAlignment();
- updateWidth();
- updateHeight();
- updateTextSize();
- require_update_texture_ = true;
- }
-
- overtake_position_properties_ = overtake_position_properties_property_->getBool();
- if (overtake_position_properties_) {
- hor_dist_property_->show();
- ver_dist_property_->show();
- hor_alignment_property_->show();
- ver_alignment_property_->show();
- width_property_->show();
- height_property_->show();
- text_size_property_->show();
- } else {
- hor_dist_property_->hide();
- ver_dist_property_->hide();
- hor_alignment_property_->hide();
- ver_alignment_property_->hide();
- width_property_->hide();
- height_property_->hide();
- text_size_property_->hide();
- }
-}
-
-void OverlayTextDisplay::updateOvertakeFGColorProperties()
-{
- if (!overtake_fg_color_properties_ && overtake_fg_color_properties_property_->getBool()) {
- // read all the parameters from properties
- updateFGColor();
- updateFGAlpha();
- updateFont();
- updateLineWidth();
- require_update_texture_ = true;
- }
- overtake_fg_color_properties_ = overtake_fg_color_properties_property_->getBool();
- if (overtake_fg_color_properties_) {
- fg_color_property_->show();
- fg_alpha_property_->show();
- line_width_property_->show();
- font_property_->show();
- } else {
- fg_color_property_->hide();
- fg_alpha_property_->hide();
- line_width_property_->hide();
- font_property_->hide();
- }
-}
-
-void OverlayTextDisplay::updateOvertakeBGColorProperties()
-{
- if (!overtake_bg_color_properties_ && overtake_bg_color_properties_property_->getBool()) {
- // read all the parameters from properties
- updateBGColor();
- updateBGAlpha();
- require_update_texture_ = true;
- }
- overtake_bg_color_properties_ = overtake_bg_color_properties_property_->getBool();
- if (overtake_bg_color_properties_) {
- bg_color_property_->show();
- bg_alpha_property_->show();
- } else {
- bg_color_property_->hide();
- bg_alpha_property_->hide();
- }
-}
-
-void OverlayTextDisplay::updateAlignBottom()
-{
- if (align_bottom_ != align_bottom_property_->getBool()) {
- require_update_texture_ = true;
- }
- align_bottom_ = align_bottom_property_->getBool();
-}
-
-void OverlayTextDisplay::updateInvertShadow()
-{
- if (invert_shadow_ != invert_shadow_property_->getBool()) {
- require_update_texture_ = true;
- }
- invert_shadow_ = invert_shadow_property_->getBool();
-}
-
-void OverlayTextDisplay::updateVerticalDistance()
-{
- vertical_dist_ = ver_dist_property_->getInt();
- if (overtake_position_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateHorizontalDistance()
-{
- horizontal_dist_ = hor_dist_property_->getInt();
- if (overtake_position_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateVerticalAlignment()
-{
- vertical_alignment_ =
- VerticalAlignment{static_cast(ver_alignment_property_->getOptionInt())};
-
- if (overtake_position_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateHorizontalAlignment()
-{
- horizontal_alignment_ =
- HorizontalAlignment{static_cast(hor_alignment_property_->getOptionInt())};
-
- if (overtake_position_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateWidth()
-{
- texture_width_ = width_property_->getInt();
- if (overtake_position_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateHeight()
-{
- texture_height_ = height_property_->getInt();
- if (overtake_position_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateTextSize()
-{
- text_size_ = text_size_property_->getInt();
- if (overtake_position_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateBGColor()
-{
- QColor c = bg_color_property_->getColor();
- bg_color_.setRed(c.red());
- bg_color_.setGreen(c.green());
- bg_color_.setBlue(c.blue());
- if (overtake_bg_color_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateBGAlpha()
-{
- bg_color_.setAlpha(bg_alpha_property_->getFloat() * 255.0);
- if (overtake_bg_color_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateFGColor()
-{
- QColor c = fg_color_property_->getColor();
- fg_color_.setRed(c.red());
- fg_color_.setGreen(c.green());
- fg_color_.setBlue(c.blue());
- if (overtake_fg_color_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateFGAlpha()
-{
- fg_color_.setAlpha(fg_alpha_property_->getFloat() * 255.0);
- if (overtake_fg_color_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateFont()
-{
- int font_index = font_property_->getOptionInt();
- if (font_index < font_families_.size()) {
- font_ = font_families_[font_index].toStdString();
- } else {
- RVIZ_COMMON_LOG_ERROR_STREAM("Unexpected error at selecting font index " << font_index);
- return;
- }
- if (overtake_fg_color_properties_) {
- require_update_texture_ = true;
- }
-}
-
-void OverlayTextDisplay::updateLineWidth()
-{
- line_width_ = line_width_property_->getInt();
- if (overtake_fg_color_properties_) {
- require_update_texture_ = true;
- }
-}
-
-} // namespace autoware_overlay_rviz_plugin
-
-#include
-PLUGINLIB_EXPORT_CLASS(autoware_overlay_rviz_plugin::OverlayTextDisplay, rviz_common::Display)
diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp
index 841b33c29fbb0..9add6336ece46 100644
--- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp
+++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp
@@ -120,59 +120,13 @@ void SignalDisplay::onInitialize()
void SignalDisplay::setupRosSubscriptions()
{
- // Don't create a node, just use the one from the parent class
- auto rviz_node_ = context_->getRosNodeAbstraction().lock()->get_raw_node();
-
- gear_sub_ = rviz_node_->create_subscription(
- gear_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
- [this](const autoware_auto_vehicle_msgs::msg::GearReport::SharedPtr msg) {
- updateGearData(msg);
- });
-
- steering_sub_ = rviz_node_->create_subscription(
- steering_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
- [this](const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg) {
- updateSteeringData(msg);
- });
-
- speed_sub_ = rviz_node_->create_subscription(
- speed_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
- [this](const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg) {
- updateSpeedData(msg);
- });
-
- turn_signals_sub_ =
- rviz_node_->create_subscription(
- turn_signals_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
- [this](const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::SharedPtr msg) {
- updateTurnSignalsData(msg);
- });
-
- hazard_lights_sub_ =
- rviz_node_->create_subscription(
- hazard_lights_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
- [this](const autoware_auto_vehicle_msgs::msg::HazardLightsReport::SharedPtr msg) {
- updateHazardLightsData(msg);
- });
-
- traffic_sub_ = rviz_node_->create_subscription(
- traffic_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
- [this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) {
- updateTrafficLightData(msg);
- });
-
- speed_limit_sub_ = rviz_node_->create_subscription(
- speed_limit_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
- [this](const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) {
- updateSpeedLimitData(msg);
- });
+ topic_updated_gear();
+ topic_updated_steering();
+ topic_updated_speed();
+ topic_updated_speed_limit();
+ topic_updated_turn_signals();
+ topic_updated_hazard_lights();
+ topic_updated_traffic();
}
SignalDisplay::~SignalDisplay()
@@ -419,8 +373,7 @@ void SignalDisplay::topic_updated_gear()
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
gear_sub_ =
rviz_ros_node->get_raw_node()->create_subscription(
- gear_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
+ gear_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
[this](const autoware_auto_vehicle_msgs::msg::GearReport::SharedPtr msg) {
updateGearData(msg);
});
@@ -433,8 +386,7 @@ void SignalDisplay::topic_updated_steering()
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
steering_sub_ = rviz_ros_node->get_raw_node()
->create_subscription(
- steering_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
+ steering_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
[this](const autoware_auto_vehicle_msgs::msg::SteeringReport::SharedPtr msg) {
updateSteeringData(msg);
});
@@ -447,8 +399,7 @@ void SignalDisplay::topic_updated_speed()
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
speed_sub_ = rviz_ros_node->get_raw_node()
->create_subscription(
- speed_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
+ speed_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
[this](const autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr msg) {
updateSpeedData(msg);
});
@@ -462,7 +413,7 @@ void SignalDisplay::topic_updated_speed_limit()
speed_limit_sub_ =
rviz_ros_node->get_raw_node()->create_subscription(
speed_limit_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
+ rclcpp::QoS(rclcpp::KeepLast(10)).transient_local(),
[this](const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg) {
updateSpeedLimitData(msg);
});
@@ -477,8 +428,7 @@ void SignalDisplay::topic_updated_turn_signals()
turn_signals_sub_ =
rviz_ros_node->get_raw_node()
->create_subscription(
- turn_signals_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
+ turn_signals_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
[this](const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::SharedPtr msg) {
updateTurnSignalsData(msg);
});
@@ -493,8 +443,7 @@ void SignalDisplay::topic_updated_hazard_lights()
hazard_lights_sub_ =
rviz_ros_node->get_raw_node()
->create_subscription(
- hazard_lights_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
+ hazard_lights_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
[this](const autoware_auto_vehicle_msgs::msg::HazardLightsReport::SharedPtr msg) {
updateHazardLightsData(msg);
});
@@ -507,8 +456,7 @@ void SignalDisplay::topic_updated_traffic()
auto rviz_ros_node = context_->getRosNodeAbstraction().lock();
traffic_sub_ = rviz_ros_node->get_raw_node()
->create_subscription(
- traffic_topic_property_->getTopicStd(),
- rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(),
+ traffic_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)),
[this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) {
updateTrafficLightData(msg);
});