diff -pruN 1.14.14+dfsg-2/CHANGELOG.rst 1.14.15+dfsg-3/CHANGELOG.rst
--- 1.14.14+dfsg-2/CHANGELOG.rst	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/CHANGELOG.rst	2022-08-01 08:39:42.000000000 +0000
@@ -2,6 +2,38 @@
 Changelog for package rviz
 ^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.14.15 (2022-08-01)
+--------------------
+* Improve SplitterHandle of PropertyTreeWidgets (`#1760 <https://github.com/ros-visualization/rviz/issues/1760>`_)
+
+  * Suppress horizontal scrolling and auto-resizing of columns
+  * Double click auto-adjusts to content
+* Fix segfault occuring for direct dock panel deletion (`#1759 <https://github.com/ros-visualization/rviz/issues/1759>`_)
+* Fix race conditions in PointCloud displays (`#1754 <https://github.com/ros-visualization/rviz/issues/1754>`_)
+* Acquire mutexes before destroying PointCloudCommon
+* PointCloud displays: unsubscribe before destroying PointCloudCommon
+* Fix segfault in ``TimePanel::onTimeSignal()`` (`#1753 <https://github.com/ros-visualization/rviz/issues/1753>`_): Drop source Display* argument, which is a dangling pointer if the Display was deleted meanwhile
+* OGRE compatibility layer: more precise version info
+* Use more verbose material names for robot links (robot link material -> robot link <link name>:<material name>)
+* Fix transparency of RobotLinks with multiple visuals and different alpha values (`#1751 <https://github.com/ros-visualization/rviz/issues/1751>`_)
+* Maintain original (mesh) materials for RobotLinks (`#1704 <https://github.com/ros-visualization/rviz/issues/1704>`_, `#1732 <https://github.com/ros-visualization/rviz/issues/1732>`_)
+* Improve TF time syncing (`#1698 <https://github.com/ros-visualization/rviz/issues/1698>`_)
+
+  - TimePanel: Integrate experimental view
+  - New mode SyncFrame, syncing TF lookups within a visualization frame
+* Conditionally include OgreVector3.h vs. OgreVector.h for OGRE 1.9 vs. 1.12 (`#1741 <https://github.com/ros-visualization/rviz/issues/1741>`_)
+* Don't disable display if associated widget tab changes (`#1739 <https://github.com/ros-visualization/rviz/issues/1739>`_)
+* Drop OGRE/ from #include directives (`#1730 <https://github.com/ros-visualization/rviz/issues/1730>`_)
+* Fix segfault when no tools are available (`#1729 <https://github.com/ros-visualization/rviz/issues/1729>`_)
+* GridCells: implement setTopic() (`#1722 <https://github.com/ros-visualization/rviz/issues/1722>`_)
+* Adaptions for Ubuntu 22 (`#1717 <https://github.com/ros-visualization/rviz/issues/1717>`_)
+
+  * Switch to new boost/bind/bind.hpp
+  * Drop C++11 COMPILE_FLAGS
+  * Do not force obsolete CXX14
+  * Support python_qt_bindings with sip5
+* Contributors: AndreasR30, Brosong, Jochen Sprickerhof, Lucas Walter, Matthijs van der Burgh, Robert Haschke
+
 1.14.14 (2022-02-12)
 --------------------
 * Fixup `#1497 <https://github.com/ros-visualization/rviz/issues/1497>`_: Initialize ``fixed_frame_id``
diff -pruN 1.14.14+dfsg-2/CMakeLists.txt 1.14.15+dfsg-3/CMakeLists.txt
--- 1.14.14+dfsg-2/CMakeLists.txt	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/CMakeLists.txt	2022-08-01 08:39:42.000000000 +0000
@@ -8,10 +8,6 @@ if (POLICY CMP0054)
   cmake_policy(SET CMP0054 NEW)
 endif()
 
-set(CMAKE_CXX_STANDARD 14)
-set(CMAKE_CXX_STANDARD_REQUIRED ON)
-set(CMAKE_CXX_EXTENSIONS OFF)
-
 # Define global caktin_lint suppressions
 #catkin_lint: ignore uninstalled_script missing_install_target
 
@@ -86,9 +82,9 @@ else()
 endif()
 
 # TODO: adapt version after upgrade to newer OGRE release
-# Disable deprecation warnings for OGRE >= 1.10
+# Consider deprecation issues as warnings, not as errors for OGRE >= 1.10
 if(NOT OGRE_VERSION VERSION_LESS "1.10.0" AND NOT MSVC)
-  add_compile_options(-Wno-deprecated-declarations)
+  add_compile_options(-Wno-error=deprecated-declarations)
 endif()
 
 if(APPLE)
diff -pruN 1.14.14+dfsg-2/debian/changelog 1.14.15+dfsg-3/debian/changelog
--- 1.14.14+dfsg-2/debian/changelog	2022-06-13 17:45:12.000000000 +0000
+++ 1.14.15+dfsg-3/debian/changelog	2022-08-04 21:37:13.000000000 +0000
@@ -1,3 +1,23 @@
+ros-rviz (1.14.15+dfsg-3) unstable; urgency=medium
+
+  * really upload to unstable
+
+ -- Jochen Sprickerhof <jspricke@debian.org>  Thu, 04 Aug 2022 23:37:13 +0200
+
+ros-rviz (1.14.15+dfsg-2) experimental; urgency=medium
+
+  * upload to unstable
+
+ -- Jochen Sprickerhof <jspricke@debian.org>  Thu, 04 Aug 2022 23:29:33 +0200
+
+ros-rviz (1.14.15+dfsg-1) experimental; urgency=medium
+
+  * New upstream version 1.14.15+dfsg
+  * Drop upstreamed patches, define RVIZ_SOVERSION
+  * Bump SoName due to ABI change
+
+ -- Jochen Sprickerhof <jspricke@debian.org>  Thu, 04 Aug 2022 09:40:28 +0200
+
 ros-rviz (1.14.14+dfsg-2) unstable; urgency=medium
 
   * Fix missing include
diff -pruN 1.14.14+dfsg-2/debian/control 1.14.15+dfsg-3/debian/control
--- 1.14.14+dfsg-2/debian/control	2022-06-13 17:45:07.000000000 +0000
+++ 1.14.15+dfsg-3/debian/control	2022-08-04 07:34:10.000000000 +0000
@@ -16,14 +16,14 @@ Package: librviz-dev
 Section: libdevel
 Architecture: any
 Multi-Arch: same
-Depends: librviz6d (= ${binary:Version}), ${misc:Depends}, libimage-transport-dev, libinteractive-markers-dev, liblaser-geometry-dev, libmap-msgs-dev, libmessage-filters-dev, libnav-msgs-dev, pluginlib-dev, python3-python-qt-binding, libresource-retriever-dev, librosbag-dev, librosconsole-dev, libroscpp-dev, libroslib-dev, python3-rospy, libsensor-msgs-dev, libstd-msgs-dev, libstd-srvs-dev, libtf-dev, liburdf-dev, libvisualization-msgs-dev, libogre-1.12-dev
+Depends: librviz7d (= ${binary:Version}), ${misc:Depends}, libimage-transport-dev, libinteractive-markers-dev, liblaser-geometry-dev, libmap-msgs-dev, libmessage-filters-dev, libnav-msgs-dev, pluginlib-dev, python3-python-qt-binding, libresource-retriever-dev, librosbag-dev, librosconsole-dev, libroscpp-dev, libroslib-dev, python3-rospy, libsensor-msgs-dev, libstd-msgs-dev, libstd-srvs-dev, libtf-dev, liburdf-dev, libvisualization-msgs-dev, libogre-1.12-dev
 Description: Development files for the Robot OS 3D visualization tool
  This package is part of Robot OS (ROS) RViz package. RViz is a tool to
  visualize ROS messages and the state of the robot.
  .
  This package contains the development files for the rviz library.
 
-Package: librviz6d
+Package: librviz7d
 Architecture: any
 Depends: ${shlibs:Depends}, ${misc:Depends}
 Multi-Arch: same
diff -pruN 1.14.14+dfsg-2/debian/librviz6d.install 1.14.15+dfsg-3/debian/librviz6d.install
--- 1.14.14+dfsg-2/debian/librviz6d.install	2021-11-10 20:41:34.000000000 +0000
+++ 1.14.15+dfsg-3/debian/librviz6d.install	1970-01-01 00:00:00.000000000 +0000
@@ -1 +0,0 @@
-usr/lib/*/librviz.so.*
diff -pruN 1.14.14+dfsg-2/debian/librviz7d.install 1.14.15+dfsg-3/debian/librviz7d.install
--- 1.14.14+dfsg-2/debian/librviz7d.install	1970-01-01 00:00:00.000000000 +0000
+++ 1.14.15+dfsg-3/debian/librviz7d.install	2021-11-10 20:41:34.000000000 +0000
@@ -0,0 +1 @@
+usr/lib/*/librviz.so.*
diff -pruN 1.14.14+dfsg-2/debian/patches/0001-Add-Debian-specific-SOVERSION.patch 1.14.15+dfsg-3/debian/patches/0001-Add-Debian-specific-SOVERSION.patch
--- 1.14.14+dfsg-2/debian/patches/0001-Add-Debian-specific-SOVERSION.patch	2022-06-02 16:53:49.000000000 +0000
+++ 1.14.15+dfsg-3/debian/patches/0001-Add-Debian-specific-SOVERSION.patch	2022-08-04 07:30:51.000000000 +0000
@@ -3,18 +3,20 @@ Date: Wed, 5 Aug 2015 14:05:24 +0200
 Subject: Add Debian specific SOVERSION
 
 ---
- src/rviz/CMakeLists.txt | 1 +
- 1 file changed, 1 insertion(+)
+ src/rviz/CMakeLists.txt | 3 +++
+ 1 file changed, 3 insertions(+)
 
 diff --git a/src/rviz/CMakeLists.txt b/src/rviz/CMakeLists.txt
-index d594109..31282f8 100644
+index e131dd5..46256b3 100644
 --- a/src/rviz/CMakeLists.txt
 +++ b/src/rviz/CMakeLists.txt
-@@ -146,6 +146,7 @@ target_link_libraries(${PROJECT_NAME}
+@@ -143,6 +143,9 @@ target_link_libraries(${PROJECT_NAME}
  )
  
  add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
-+set_target_properties(${PROJECT_NAME} PROPERTIES VERSION ${rviz_VERSION} SOVERSION "6d")
++if(RVIZ_SOVERSION)
++  set_target_properties(${PROJECT_NAME} PROPERTIES SOVERSION ${RVIZ_SOVERSION})
++endif()
  
  
  if(APPLE)
diff -pruN 1.14.14+dfsg-2/debian/patches/0003-Make-Python-version-variable-for-pybuild.patch 1.14.15+dfsg-3/debian/patches/0003-Make-Python-version-variable-for-pybuild.patch
--- 1.14.14+dfsg-2/debian/patches/0003-Make-Python-version-variable-for-pybuild.patch	2022-06-02 16:53:49.000000000 +0000
+++ 1.14.15+dfsg-3/debian/patches/0003-Make-Python-version-variable-for-pybuild.patch	2022-08-04 07:30:51.000000000 +0000
@@ -7,10 +7,10 @@ Subject: Make Python version variable fo
  1 file changed, 1 insertion(+), 1 deletion(-)
 
 diff --git a/src/python_bindings/sip/CMakeLists.txt b/src/python_bindings/sip/CMakeLists.txt
-index f9124db..bd66776 100644
+index 81daa94..bca06d2 100644
 --- a/src/python_bindings/sip/CMakeLists.txt
 +++ b/src/python_bindings/sip/CMakeLists.txt
-@@ -73,5 +73,5 @@ if(sip_helper_FOUND)
+@@ -75,5 +75,5 @@ if(sip_helper_FOUND)
    endif()
    #catkin_lint: ignore_once external_file
    install(FILES ${CATKIN_DEVEL_PREFIX}/${PYTHON_INSTALL_DIR}/rviz/${rviz_sip_LIBRARY_FILE}
diff -pruN 1.14.14+dfsg-2/debian/patches/0003-Remove-rpath.patch 1.14.15+dfsg-3/debian/patches/0003-Remove-rpath.patch
--- 1.14.14+dfsg-2/debian/patches/0003-Remove-rpath.patch	2022-06-02 16:53:49.000000000 +0000
+++ 1.14.15+dfsg-3/debian/patches/0003-Remove-rpath.patch	2022-08-04 07:30:51.000000000 +0000
@@ -7,7 +7,7 @@ Subject: Remove rpath
  1 file changed, 2 deletions(-)
 
 diff --git a/src/python_bindings/sip/CMakeLists.txt b/src/python_bindings/sip/CMakeLists.txt
-index 847f75b..f9124db 100644
+index efbb497..81daa94 100644
 --- a/src/python_bindings/sip/CMakeLists.txt
 +++ b/src/python_bindings/sip/CMakeLists.txt
 @@ -52,8 +52,6 @@ set(rviz_sip_LIBRARIES ${rviz_LIBRARIES} ${PROJECT_NAME})
diff -pruN 1.14.14+dfsg-2/debian/patches/0004-Switch-to-new-boost-bind-bind.hpp.patch 1.14.15+dfsg-3/debian/patches/0004-Switch-to-new-boost-bind-bind.hpp.patch
--- 1.14.14+dfsg-2/debian/patches/0004-Switch-to-new-boost-bind-bind.hpp.patch	2022-06-02 16:53:53.000000000 +0000
+++ 1.14.15+dfsg-3/debian/patches/0004-Switch-to-new-boost-bind-bind.hpp.patch	1970-01-01 00:00:00.000000000 +0000
@@ -1,356 +0,0 @@
-From: Jochen Sprickerhof <jspricke@debian.org>
-Date: Tue, 15 Dec 2020 13:59:09 +0100
-Subject: Switch to new boost/bind/bind.hpp
-
----
- src/image_view/image_view.cpp                          | 2 +-
- src/rviz/default_plugin/axes_display.cpp               | 2 +-
- src/rviz/default_plugin/camera_display.cpp             | 2 +-
- src/rviz/default_plugin/depth_cloud_display.cpp        | 8 ++++----
- src/rviz/default_plugin/effort_display.cpp             | 2 +-
- src/rviz/default_plugin/grid_cells_display.cpp         | 2 +-
- src/rviz/default_plugin/grid_display.cpp               | 2 +-
- src/rviz/default_plugin/image_display.cpp              | 2 +-
- src/rviz/default_plugin/interactive_marker_display.cpp | 8 ++++----
- src/rviz/default_plugin/map_display.cpp                | 2 +-
- src/rviz/default_plugin/marker_display.cpp             | 4 ++--
- src/rviz/default_plugin/path_display.cpp               | 2 +-
- src/rviz/default_plugin/robot_model_display.cpp        | 4 ++--
- src/rviz/default_plugin/tf_display.cpp                 | 2 +-
- src/rviz/displays_panel.cpp                            | 2 +-
- src/rviz/frame_manager.h                               | 4 ++--
- src/rviz/image/image_display_base.cpp                  | 6 +++---
- src/rviz/message_filter_display.h                      | 2 +-
- src/rviz/visualization_frame.cpp                       | 2 +-
- src/rviz/visualization_manager.cpp                     | 2 +-
- src/test/rviz_logo_marker.cpp                          | 2 +-
- 21 files changed, 32 insertions(+), 32 deletions(-)
-
-diff --git a/src/image_view/image_view.cpp b/src/image_view/image_view.cpp
-index d331555..924ea5e 100644
---- a/src/image_view/image_view.cpp
-+++ b/src/image_view/image_view.cpp
-@@ -94,7 +94,7 @@ void ImageView::showEvent(QShowEvent* event)
- 
-     texture_sub_.reset(new image_transport::SubscriberFilter());
-     texture_sub_->subscribe(texture_it_, "image", 1, image_transport::TransportHints("raw"));
--    texture_sub_->registerCallback(boost::bind(&ImageView::textureCallback, this, _1));
-+    texture_sub_->registerCallback(boost::bind(&ImageView::textureCallback, this, boost::placeholders::_1));
-   }
-   catch (ros::Exception& e)
-   {
-diff --git a/src/rviz/default_plugin/axes_display.cpp b/src/rviz/default_plugin/axes_display.cpp
-index 3c32155..5fe1a9c 100644
---- a/src/rviz/default_plugin/axes_display.cpp
-+++ b/src/rviz/default_plugin/axes_display.cpp
-@@ -27,7 +27,7 @@
-  * POSSIBILITY OF SUCH DAMAGE.
-  */
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <OGRE/OgreSceneNode.h>
- #include <OGRE/OgreSceneManager.h>
-diff --git a/src/rviz/default_plugin/camera_display.cpp b/src/rviz/default_plugin/camera_display.cpp
-index 668f706..003f78e 100644
---- a/src/rviz/default_plugin/camera_display.cpp
-+++ b/src/rviz/default_plugin/camera_display.cpp
-@@ -27,7 +27,7 @@
-  * POSSIBILITY OF SUCH DAMAGE.
-  */
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <OGRE/OgreManualObject.h>
- #include <OGRE/OgreMaterialManager.h>
-diff --git a/src/rviz/default_plugin/depth_cloud_display.cpp b/src/rviz/default_plugin/depth_cloud_display.cpp
-index 777c587..9cce8e0 100644
---- a/src/rviz/default_plugin/depth_cloud_display.cpp
-+++ b/src/rviz/default_plugin/depth_cloud_display.cpp
-@@ -41,7 +41,7 @@
- 
- #include <tf2_ros/buffer.h>
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- #include <boost/algorithm/string/erase.hpp>
- #include <boost/foreach.hpp>
- #include <boost/shared_ptr.hpp>
-@@ -302,7 +302,7 @@ void DepthCloudDisplay::subscribe()
-       // subscribe to CameraInfo  topic
-       std::string info_topic = image_transport::getCameraInfoTopic(depthmap_topic);
-       cam_info_sub_->subscribe(threaded_nh_, info_topic, queue_size_);
--      cam_info_sub_->registerCallback(boost::bind(&DepthCloudDisplay::caminfoCallback, this, _1));
-+      cam_info_sub_->registerCallback(boost::bind(&DepthCloudDisplay::caminfoCallback, this, boost::placeholders::_1));
- 
-       if (!color_topic.empty() && !color_transport.empty())
-       {
-@@ -315,13 +315,13 @@ void DepthCloudDisplay::subscribe()
-         sync_depth_color_->setInterMessageLowerBound(0, ros::Duration(0.5));
-         sync_depth_color_->setInterMessageLowerBound(1, ros::Duration(0.5));
-         sync_depth_color_->registerCallback(
--            boost::bind(&DepthCloudDisplay::processMessage, this, _1, _2));
-+            boost::bind(&DepthCloudDisplay::processMessage, this, boost::placeholders::_1, boost::placeholders::_2));
- 
-         pointcloud_common_->color_transformer_property_->setValue("RGB8");
-       }
-       else
-       {
--        depthmap_tf_filter_->registerCallback(boost::bind(&DepthCloudDisplay::processMessage, this, _1));
-+        depthmap_tf_filter_->registerCallback(boost::bind(&DepthCloudDisplay::processMessage, this, boost::placeholders::_1));
-       }
-     }
-   }
-diff --git a/src/rviz/default_plugin/effort_display.cpp b/src/rviz/default_plugin/effort_display.cpp
-index c3e6e09..6378f2e 100644
---- a/src/rviz/default_plugin/effort_display.cpp
-+++ b/src/rviz/default_plugin/effort_display.cpp
-@@ -119,7 +119,7 @@ void EffortDisplay::onInitialize()
-                                                                    std::string(), 1, update_nh_);
- 
-   // but directly process messages
--  sub_.registerCallback(boost::bind(&EffortDisplay::incomingMessage, this, _1));
-+  sub_.registerCallback(boost::bind(&EffortDisplay::incomingMessage, this, boost::placeholders::_1));
-   updateHistoryLength();
- }
- 
-diff --git a/src/rviz/default_plugin/grid_cells_display.cpp b/src/rviz/default_plugin/grid_cells_display.cpp
-index 86a20a5..82ef4ed 100644
---- a/src/rviz/default_plugin/grid_cells_display.cpp
-+++ b/src/rviz/default_plugin/grid_cells_display.cpp
-@@ -27,7 +27,7 @@
-  * POSSIBILITY OF SUCH DAMAGE.
-  */
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- #include <OGRE/OgreSceneNode.h>
- #include <OGRE/OgreSceneManager.h>
- #include <OGRE/OgreManualObject.h>
-diff --git a/src/rviz/default_plugin/grid_display.cpp b/src/rviz/default_plugin/grid_display.cpp
-index 9da0532..c288935 100644
---- a/src/rviz/default_plugin/grid_display.cpp
-+++ b/src/rviz/default_plugin/grid_display.cpp
-@@ -29,7 +29,7 @@
- 
- #include <stdint.h>
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <OGRE/OgreSceneNode.h>
- #include <OGRE/OgreSceneManager.h>
-diff --git a/src/rviz/default_plugin/image_display.cpp b/src/rviz/default_plugin/image_display.cpp
-index eff2ebf..346d918 100644
---- a/src/rviz/default_plugin/image_display.cpp
-+++ b/src/rviz/default_plugin/image_display.cpp
-@@ -27,7 +27,7 @@
-  * POSSIBILITY OF SUCH DAMAGE.
-  */
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <OGRE/OgreManualObject.h>
- #include <OGRE/OgreMaterialManager.h>
-diff --git a/src/rviz/default_plugin/interactive_marker_display.cpp b/src/rviz/default_plugin/interactive_marker_display.cpp
-index f3c559d..ec27776 100644
---- a/src/rviz/default_plugin/interactive_marker_display.cpp
-+++ b/src/rviz/default_plugin/interactive_marker_display.cpp
-@@ -109,10 +109,10 @@ void InteractiveMarkerDisplay::onInitialize()
-   auto tf = context_->getFrameManager()->getTF2BufferPtr();
-   im_client_.reset(new interactive_markers::InteractiveMarkerClient(*tf, fixed_frame_.toStdString()));
- 
--  im_client_->setInitCb(boost::bind(&InteractiveMarkerDisplay::initCb, this, _1));
--  im_client_->setUpdateCb(boost::bind(&InteractiveMarkerDisplay::updateCb, this, _1));
--  im_client_->setResetCb(boost::bind(&InteractiveMarkerDisplay::resetCb, this, _1));
--  im_client_->setStatusCb(boost::bind(&InteractiveMarkerDisplay::statusCb, this, _1, _2, _3));
-+  im_client_->setInitCb(boost::bind(&InteractiveMarkerDisplay::initCb, this, boost::placeholders::_1));
-+  im_client_->setUpdateCb(boost::bind(&InteractiveMarkerDisplay::updateCb, this, boost::placeholders::_1));
-+  im_client_->setResetCb(boost::bind(&InteractiveMarkerDisplay::resetCb, this, boost::placeholders::_1));
-+  im_client_->setStatusCb(boost::bind(&InteractiveMarkerDisplay::statusCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
- 
-   client_id_ = ros::this_node::getName() + "/" + getNameStd();
- 
-diff --git a/src/rviz/default_plugin/map_display.cpp b/src/rviz/default_plugin/map_display.cpp
-index 41ebb78..9e14618 100644
---- a/src/rviz/default_plugin/map_display.cpp
-+++ b/src/rviz/default_plugin/map_display.cpp
-@@ -27,7 +27,7 @@
-  * POSSIBILITY OF SUCH DAMAGE.
-  */
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <OGRE/OgreManualObject.h>
- #include <OGRE/OgreMaterialManager.h>
-diff --git a/src/rviz/default_plugin/marker_display.cpp b/src/rviz/default_plugin/marker_display.cpp
-index 4802d24..348fff7 100644
---- a/src/rviz/default_plugin/marker_display.cpp
-+++ b/src/rviz/default_plugin/marker_display.cpp
-@@ -77,8 +77,8 @@ void MarkerDisplay::onInitialize()
-                                                              queue_size_property_->getInt(), update_nh_);
- 
-   tf_filter_->connectInput(sub_);
--  tf_filter_->registerCallback(boost::bind(&MarkerDisplay::incomingMarker, this, _1));
--  tf_filter_->registerFailureCallback(boost::bind(&MarkerDisplay::failedMarker, this, _1, _2));
-+  tf_filter_->registerCallback(boost::bind(&MarkerDisplay::incomingMarker, this, boost::placeholders::_1));
-+  tf_filter_->registerFailureCallback(boost::bind(&MarkerDisplay::failedMarker, this, boost::placeholders::_1, boost::placeholders::_2));
- 
-   namespace_config_enabled_state_.clear();
- }
-diff --git a/src/rviz/default_plugin/path_display.cpp b/src/rviz/default_plugin/path_display.cpp
-index 6d06c30..1c342e4 100644
---- a/src/rviz/default_plugin/path_display.cpp
-+++ b/src/rviz/default_plugin/path_display.cpp
-@@ -27,7 +27,7 @@
-  * POSSIBILITY OF SUCH DAMAGE.
-  */
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <OGRE/OgreSceneNode.h>
- #include <OGRE/OgreSceneManager.h>
-diff --git a/src/rviz/default_plugin/robot_model_display.cpp b/src/rviz/default_plugin/robot_model_display.cpp
-index 2670436..952456c 100644
---- a/src/rviz/default_plugin/robot_model_display.cpp
-+++ b/src/rviz/default_plugin/robot_model_display.cpp
-@@ -205,7 +205,7 @@ void RobotModelDisplay::load()
-               QString("Errors loading geometries:").append(ss.str().c_str()));
- 
-   robot_->update(TFLinkUpdater(context_->getFrameManager(),
--                               boost::bind(linkUpdaterStatusFunction, _1, _2, _3, this),
-+                               boost::bind(linkUpdaterStatusFunction, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, this),
-                                tf_prefix_property_->getStdString()));
- }
- 
-@@ -230,7 +230,7 @@ void RobotModelDisplay::update(float wall_dt, float /*ros_dt*/)
-   if (has_new_transforms_ || update)
-   {
-     robot_->update(TFLinkUpdater(context_->getFrameManager(),
--                                 boost::bind(linkUpdaterStatusFunction, _1, _2, _3, this),
-+                                 boost::bind(linkUpdaterStatusFunction, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, this),
-                                  tf_prefix_property_->getStdString()));
-     context_->queueRender();
- 
-diff --git a/src/rviz/default_plugin/tf_display.cpp b/src/rviz/default_plugin/tf_display.cpp
-index bf7e9ce..e91cdc9 100644
---- a/src/rviz/default_plugin/tf_display.cpp
-+++ b/src/rviz/default_plugin/tf_display.cpp
-@@ -27,7 +27,7 @@
-  * POSSIBILITY OF SUCH DAMAGE.
-  */
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <OGRE/OgreSceneNode.h>
- #include <OGRE/OgreSceneManager.h>
-diff --git a/src/rviz/displays_panel.cpp b/src/rviz/displays_panel.cpp
-index 5a4f3f8..2ca9fdd 100644
---- a/src/rviz/displays_panel.cpp
-+++ b/src/rviz/displays_panel.cpp
-@@ -36,7 +36,7 @@
- #include <QApplication>
- #include <QProgressDialog>
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <rviz/display_factory.h>
- #include <rviz/display.h>
-diff --git a/src/rviz/frame_manager.h b/src/rviz/frame_manager.h
-index 2ce359f..52b3ac0 100644
---- a/src/rviz/frame_manager.h
-+++ b/src/rviz/frame_manager.h
-@@ -192,9 +192,9 @@ public:
-   template <class M>
-   void registerFilterForTransformStatusCheck(tf2_ros::MessageFilter<M>* filter, Display* display)
-   {
--    filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
-+    filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, boost::placeholders::_1, display));
-     filter->registerFailureCallback(boost::bind(
--        &FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, this, _1, _2, display));
-+        &FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, this, boost::placeholders::_1, boost::placeholders::_2, display));
-   }
- 
-   /** @brief Return the current fixed frame name. */
-diff --git a/src/rviz/image/image_display_base.cpp b/src/rviz/image/image_display_base.cpp
-index c03fbb6..94fd7d5 100644
---- a/src/rviz/image/image_display_base.cpp
-+++ b/src/rviz/image/image_display_base.cpp
-@@ -181,15 +181,15 @@ void ImageDisplayBase::subscribe()
- 
-       if (targetFrame_.empty())
-       {
--        sub_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
-+        sub_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, boost::placeholders::_1));
-       }
-       else
-       {
-         tf_filter_.reset(new tf2_ros::MessageFilter<sensor_msgs::Image>(
-             *sub_, *context_->getTF2BufferPtr(), targetFrame_, queue_size_property_->getInt(),
-             update_nh_));
--        tf_filter_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
--        tf_filter_->registerFailureCallback(boost::bind(&ImageDisplayBase::failedMessage, this, _1, _2));
-+        tf_filter_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, boost::placeholders::_1));
-+        tf_filter_->registerFailureCallback(boost::bind(&ImageDisplayBase::failedMessage, this, boost::placeholders::_1, boost::placeholders::_2));
-       }
-     }
-     setStatus(StatusProperty::Ok, "Topic", "OK");
-diff --git a/src/rviz/message_filter_display.h b/src/rviz/message_filter_display.h
-index 224f403..2016d05 100644
---- a/src/rviz/message_filter_display.h
-+++ b/src/rviz/message_filter_display.h
-@@ -111,7 +111,7 @@ public:
- 
-     tf_filter_->connectInput(sub_);
-     tf_filter_->registerCallback(
--        boost::bind(&MessageFilterDisplay<MessageType>::incomingMessage, this, _1));
-+        boost::bind(&MessageFilterDisplay<MessageType>::incomingMessage, this, boost::placeholders::_1));
-     context_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
-   }
- 
-diff --git a/src/rviz/visualization_frame.cpp b/src/rviz/visualization_frame.cpp
-index 54cfad6..2cbbba5 100644
---- a/src/rviz/visualization_frame.cpp
-+++ b/src/rviz/visualization_frame.cpp
-@@ -53,7 +53,7 @@
- 
- #include <boost/algorithm/string/split.hpp>
- #include <boost/algorithm/string/trim.hpp>
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- #include <boost/filesystem.hpp>
- 
- #include <ros/console.h>
-diff --git a/src/rviz/visualization_manager.cpp b/src/rviz/visualization_manager.cpp
-index dcb5aab..1816236 100644
---- a/src/rviz/visualization_manager.cpp
-+++ b/src/rviz/visualization_manager.cpp
-@@ -35,7 +35,7 @@
- #include <QTimer>
- #include <QWindow>
- 
--#include <boost/bind.hpp>
-+#include <boost/bind/bind.hpp>
- 
- #include <OGRE/OgreRoot.h>
- #include <OGRE/OgreSceneManager.h>
-diff --git a/src/test/rviz_logo_marker.cpp b/src/test/rviz_logo_marker.cpp
-index 6ff8746..d66686d 100644
---- a/src/test/rviz_logo_marker.cpp
-+++ b/src/test/rviz_logo_marker.cpp
-@@ -99,7 +99,7 @@ int main(int argc, char** argv)
-   ros::init(argc, argv, "rviz_logo_marker");
-   ros::NodeHandle n;
- 
--  ros::Timer publish_timer = n.createTimer(ros::Duration(0.1), boost::bind(&publishCallback, _1));
-+  ros::Timer publish_timer = n.createTimer(ros::Duration(0.1), boost::bind(&publishCallback, boost::placeholders::_1));
- 
-   server = new interactive_markers::InteractiveMarkerServer("rviz_logo");
-   makeMarker();
diff -pruN 1.14.14+dfsg-2/debian/patches/0005-Drop-c-11-COMPILE_FLAGS.patch 1.14.15+dfsg-3/debian/patches/0005-Drop-c-11-COMPILE_FLAGS.patch
--- 1.14.14+dfsg-2/debian/patches/0005-Drop-c-11-COMPILE_FLAGS.patch	2022-06-02 16:53:49.000000000 +0000
+++ 1.14.15+dfsg-3/debian/patches/0005-Drop-c-11-COMPILE_FLAGS.patch	1970-01-01 00:00:00.000000000 +0000
@@ -1,228 +0,0 @@
-From: Jochen Sprickerhof <jspricke@debian.org>
-Date: Fri, 14 Jan 2022 21:30:36 +0100
-Subject: Drop c++11 COMPILE_FLAGS
-
----
- src/image_view/CMakeLists.txt               |  3 --
- src/python_bindings/shiboken/CMakeLists.txt |  3 --
- src/rviz/CMakeLists.txt                     |  7 ----
- src/rviz/default_plugin/CMakeLists.txt      |  4 ---
- src/test/CMakeLists.txt                     | 51 -----------------------------
- 5 files changed, 68 deletions(-)
-
-diff --git a/src/image_view/CMakeLists.txt b/src/image_view/CMakeLists.txt
-index 1c86461..b2bd513 100644
---- a/src/image_view/CMakeLists.txt
-+++ b/src/image_view/CMakeLists.txt
-@@ -2,9 +2,6 @@ add_executable(rviz_image_view
-   image_view.cpp
-   main.cpp
- )
--if(NOT WIN32)
--  set_target_properties(rviz_image_view PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- 
- target_link_libraries(rviz_image_view
-   ${OGRE_LIBRARIES}
-diff --git a/src/python_bindings/shiboken/CMakeLists.txt b/src/python_bindings/shiboken/CMakeLists.txt
-index 24ea096..7bf671c 100644
---- a/src/python_bindings/shiboken/CMakeLists.txt
-+++ b/src/python_bindings/shiboken/CMakeLists.txt
-@@ -90,9 +90,6 @@ if(shiboken_helper_FOUND)
-     )
-     shiboken_include_directories(rviz_shiboken "${rviz_shiboken_QT_COMPONENTS}")
-     add_library(rviz_shiboken ${rviz_shiboken_SRCS})
--    if(NOT WIN32)
--      set_target_properties(rviz_shiboken PROPERTIES COMPILE_FLAGS "-std=c++11")
--    endif()
-     set_target_properties(rviz_shiboken PROPERTIES
-       LIBRARY_OUTPUT_DIRECTORY ${CATKIN_DEVEL_PREFIX}/${PYTHON_INSTALL_DIR}/rviz)
-     target_link_libraries(rviz_shiboken ${PROJECT_NAME})
-diff --git a/src/rviz/CMakeLists.txt b/src/rviz/CMakeLists.txt
-index 31282f8..af98735 100644
---- a/src/rviz/CMakeLists.txt
-+++ b/src/rviz/CMakeLists.txt
-@@ -128,9 +128,6 @@ add_library(${PROJECT_NAME}
- include(GenerateExportHeader)
- set(EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/rviz/${PROJECT_NAME}_export.h)
- generate_export_header(${PROJECT_NAME} EXPORT_FILE_NAME ${EXPORT_FILE_NAME})
--if(NOT WIN32)
--  set_target_properties(${PROJECT_NAME} PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- 
- target_link_libraries(${PROJECT_NAME}
-   ${Boost_LIBRARIES}
-@@ -156,10 +153,6 @@ endif(APPLE)
- ########### The rviz executable ###########
- add_executable(executable main.cpp)
- 
--if(NOT WIN32)
--  set_target_properties(executable PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
--
- target_link_libraries(executable ${PROJECT_NAME} ${QT_LIBRARIES} ${OGRE_LIBRARIES})
- 
- set_target_properties(executable
-diff --git a/src/rviz/default_plugin/CMakeLists.txt b/src/rviz/default_plugin/CMakeLists.txt
-index 196c252..c6ebc40 100644
---- a/src/rviz/default_plugin/CMakeLists.txt
-+++ b/src/rviz/default_plugin/CMakeLists.txt
-@@ -72,10 +72,6 @@ add_library(${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME} ${SOURCE_FILES})
- include(GenerateExportHeader)
- set(EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/rviz/default_plugin/${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME}_export.h)
- generate_export_header(${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME} EXPORT_FILE_NAME ${EXPORT_FILE_NAME})
--if(NOT WIN32)
--  set_target_properties(${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME}
--    PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME}
-   ${PROJECT_NAME}
-   ${Boost_LIBRARIES}
-diff --git a/src/test/CMakeLists.txt b/src/test/CMakeLists.txt
-index 5ec9067..ceeb70d 100644
---- a/src/test/CMakeLists.txt
-+++ b/src/test/CMakeLists.txt
-@@ -3,25 +3,16 @@ find_package(rostest REQUIRED)
- 
- # This is a test utility which publishes images of different types.
- add_executable(send_images EXCLUDE_FROM_ALL send_images.cpp)
--if(NOT WIN32)
--  set_target_properties(send_images PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(send_images ${catkin_LIBRARIES})
- add_dependencies(tests send_images)
- 
- # This is a test utility which can publish different kinds of markers.
- add_executable(marker_test EXCLUDE_FROM_ALL marker_test.cpp)
--if(NOT WIN32)
--  set_target_properties(marker_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(marker_test ${catkin_LIBRARIES})
- add_dependencies(tests marker_test)
- 
- # This is a test utility which can publish different kinds of mesh markers.
- add_executable(mesh_marker_test EXCLUDE_FROM_ALL mesh_marker_test.cpp)
--if(NOT WIN32)
--  set_target_properties(mesh_marker_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(mesh_marker_test ${catkin_LIBRARIES})
- add_dependencies(tests mesh_marker_test)
- 
-@@ -53,81 +44,51 @@ catkin_add_gtest(uniform_string_stream_test
- 
- # This is an example node which serves an rviz logo as an interactive marker.
- add_executable(rviz_logo_marker EXCLUDE_FROM_ALL rviz_logo_marker.cpp)
--if(NOT WIN32)
--  set_target_properties(rviz_logo_marker PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(rviz_logo_marker ${catkin_LIBRARIES})
- add_dependencies(tests rviz_logo_marker)
- 
- # This is an example node which publishes different kinds of point clouds.
- add_executable(cloud_test EXCLUDE_FROM_ALL cloud_test.cpp)
--if(NOT WIN32)
--  set_target_properties(cloud_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(cloud_test ${catkin_LIBRARIES})
- add_dependencies(tests cloud_test)
- 
- # This is an example node which serves an interactive marker.
- add_executable(interactive_marker_test interactive_marker_test.cpp)
--if(NOT WIN32)
--  set_target_properties(interactive_marker_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(interactive_marker_test ${catkin_LIBRARIES})
- add_dependencies(tests interactive_marker_test)
- 
- # This is another example node that publishes images.
- add_executable(image_test EXCLUDE_FROM_ALL image_test.cpp)
--if(NOT WIN32)
--  set_target_properties(image_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(image_test ${catkin_LIBRARIES})
- add_dependencies(tests image_test)
- 
- # This is a node that sends lots of point clouds.
- add_executable(send_lots_of_points EXCLUDE_FROM_ALL send_lots_of_points_node.cpp)
--if(NOT WIN32)
--  set_target_properties(send_lots_of_points PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(send_lots_of_points ${catkin_LIBRARIES})
- add_dependencies(tests send_lots_of_points)
- 
- # Yet another example which sends point clouds.
- add_executable(send_point_cloud_2 EXCLUDE_FROM_ALL send_point_cloud_2.cpp)
--if(NOT WIN32)
--  set_target_properties(send_point_cloud_2 PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(send_point_cloud_2 ${catkin_LIBRARIES})
- add_dependencies(tests send_point_cloud_2)
- 
- # This is a node which sends grid cells.
- add_executable(send_grid_cells EXCLUDE_FROM_ALL send_grid_cells_node.cpp)
--if(NOT WIN32)
--  set_target_properties(send_grid_cells PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(send_grid_cells ${catkin_LIBRARIES})
- add_dependencies(tests send_grid_cells)
- 
- # This is a test program that uses the rviz panel interface.
- add_executable(render_panel_test render_panel_test.cpp)
--if(NOT WIN32)
--  set_target_properties(render_panel_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(render_panel_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
- add_dependencies(tests render_panel_test)
- 
- # This is an executable which uses the rviz new display diaglog interface.
- add_executable(new_display_dialog_test new_display_dialog_test.cpp)
--if(NOT WIN32)
--  set_target_properties(new_display_dialog_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(new_display_dialog_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
- add_dependencies(tests new_display_dialog_test)
- 
- # This is an executable which uses the rviz color editor test.
- add_executable(color_editor_test color_editor_test.cpp)
--if(NOT WIN32)
--  set_target_properties(color_editor_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(color_editor_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
- add_dependencies(tests color_editor_test)
- 
-@@ -143,17 +104,11 @@ add_dependencies(tests property_with_ros_spinner_test)
- 
- # This is an executable that uses the line_edit_with_button property interface.
- add_executable(line_edit_with_button_test line_edit_with_button_test.cpp)
--if(NOT WIN32)
--  set_target_properties(line_edit_with_button_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(line_edit_with_button_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
- add_dependencies(tests line_edit_with_button_test)
- 
- # This is an executable which tests the connect/disconnect behavior of signals and slots in Qt.
- add_executable(connect_test connect_test.cpp)
--if(NOT WIN32)
--  set_target_properties(connect_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(connect_test ${QT_LIBRARIES})
- add_dependencies(tests connect_test)
- 
-@@ -166,17 +121,11 @@ add_executable(render_points_test
-   render_points_test.cpp
-   ../rviz/ogre_helpers/orbit_camera.cpp
- )
--if(NOT WIN32)
--  set_target_properties(render_points_test PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(render_points_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
- add_dependencies(tests render_points_test)
- 
- # This is an example application which creates two ogre render windows.
- add_executable(two_render_widgets two_render_widgets.cpp)
--if(NOT WIN32)
--  set_target_properties(two_render_widgets PROPERTIES COMPILE_FLAGS "-std=c++11")
--endif()
- target_link_libraries(two_render_widgets rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
- add_dependencies(tests two_render_widgets)
- 
diff -pruN 1.14.14+dfsg-2/debian/patches/0006-Do-not-force-obsolete-CXX-14.patch 1.14.15+dfsg-3/debian/patches/0006-Do-not-force-obsolete-CXX-14.patch
--- 1.14.14+dfsg-2/debian/patches/0006-Do-not-force-obsolete-CXX-14.patch	2022-06-02 16:53:49.000000000 +0000
+++ 1.14.15+dfsg-3/debian/patches/0006-Do-not-force-obsolete-CXX-14.patch	1970-01-01 00:00:00.000000000 +0000
@@ -1,23 +0,0 @@
-From: =?utf-8?q?Timo_R=C3=B6hling?= <roehling@debian.org>
-Date: Sat, 15 Jan 2022 16:04:00 +0100
-Subject: Do not force obsolete CXX 14
-
----
- CMakeLists.txt | 4 ----
- 1 file changed, 4 deletions(-)
-
-diff --git a/CMakeLists.txt b/CMakeLists.txt
-index 038a431..13d86f6 100644
---- a/CMakeLists.txt
-+++ b/CMakeLists.txt
-@@ -8,10 +8,6 @@ if (POLICY CMP0054)
-   cmake_policy(SET CMP0054 NEW)
- endif()
- 
--set(CMAKE_CXX_STANDARD 14)
--set(CMAKE_CXX_STANDARD_REQUIRED ON)
--set(CMAKE_CXX_EXTENSIONS OFF)
--
- # Define global caktin_lint suppressions
- #catkin_lint: ignore uninstalled_script missing_install_target
- 
diff -pruN 1.14.14+dfsg-2/debian/patches/0008-Add-missing-include.patch 1.14.15+dfsg-3/debian/patches/0008-Add-missing-include.patch
--- 1.14.14+dfsg-2/debian/patches/0008-Add-missing-include.patch	2022-06-02 16:53:49.000000000 +0000
+++ 1.14.15+dfsg-3/debian/patches/0008-Add-missing-include.patch	1970-01-01 00:00:00.000000000 +0000
@@ -1,21 +0,0 @@
-From: Jochen Sprickerhof <jspricke@debian.org>
-Date: Thu, 26 May 2022 21:29:40 +0200
-Subject: Add missing include
-
----
- src/rviz/pluginlib_factory.h | 2 ++
- 1 file changed, 2 insertions(+)
-
-diff --git a/src/rviz/pluginlib_factory.h b/src/rviz/pluginlib_factory.h
-index 6b0059c..b493437 100644
---- a/src/rviz/pluginlib_factory.h
-+++ b/src/rviz/pluginlib_factory.h
-@@ -36,6 +36,8 @@
- #include <string>
- #include <vector>
- 
-+#include <ros/console.h>
-+
- #ifndef Q_MOC_RUN
- #include <pluginlib/class_loader.hpp>
- #endif
diff -pruN 1.14.14+dfsg-2/debian/patches/series 1.14.15+dfsg-3/debian/patches/series
--- 1.14.14+dfsg-2/debian/patches/series	2022-06-02 16:53:49.000000000 +0000
+++ 1.14.15+dfsg-3/debian/patches/series	2022-08-04 07:30:51.000000000 +0000
@@ -1,8 +1,4 @@
 0001-Add-Debian-specific-SOVERSION.patch
 0003-Remove-rpath.patch
 0003-Make-Python-version-variable-for-pybuild.patch
-0004-Switch-to-new-boost-bind-bind.hpp.patch
-0005-Drop-c-11-COMPILE_FLAGS.patch
-0006-Do-not-force-obsolete-CXX-14.patch
 0007-Fix-default-plugin-location.patch
-0008-Add-missing-include.patch
diff -pruN 1.14.14+dfsg-2/debian/rules 1.14.15+dfsg-3/debian/rules
--- 1.14.14+dfsg-2/debian/rules	2022-01-16 09:06:49.000000000 +0000
+++ 1.14.15+dfsg-3/debian/rules	2022-08-04 07:34:10.000000000 +0000
@@ -1,6 +1,6 @@
 #!/usr/bin/make -f
 
-export PYBUILD_CONFIGURE_ARGS=-DPYBUILD_PYTHON_VERSION={version}
+export PYBUILD_CONFIGURE_ARGS=-DPYBUILD_PYTHON_VERSION={version} -DRVIZ_SOVERSION=7d
 export PYBUILD_SYSTEM=cmake
 
 include /usr/share/dpkg/architecture.mk
diff -pruN 1.14.14+dfsg-2/doc/conf.py 1.14.15+dfsg-3/doc/conf.py
--- 1.14.14+dfsg-2/doc/conf.py	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/doc/conf.py	2022-08-01 08:39:42.000000000 +0000
@@ -41,8 +41,8 @@ source_suffix = ".rst"
 master_doc = "index"
 
 # General information about the project.
-project = u"RViz"
-copyright = u"2012, Willow Garage, Inc"
+project = "RViz"
+copyright = "2012, Willow Garage, Inc"
 
 # The version info for the project you're documenting, acts as replacement for
 # |version| and |release|, also used in various other places throughout the
@@ -186,8 +186,8 @@ latex_documents = [
     (
         "index",
         "RViz.tex",
-        u"RViz Documentation",
-        u"Josh Faust, Dave Hershberger, David Gossow, and others",
+        "RViz Documentation",
+        "Josh Faust, Dave Hershberger, David Gossow, and others",
         "manual",
     ),
 ]
@@ -221,8 +221,8 @@ man_pages = [
     (
         "index",
         "rviz",
-        u"RViz Documentation",
-        [u"Josh Faust, Dave Hershberger, David Gossow, and others"],
+        "RViz Documentation",
+        ["Josh Faust, Dave Hershberger, David Gossow, and others"],
         1,
     )
 ]
@@ -240,8 +240,8 @@ texinfo_documents = [
     (
         "index",
         "RViz",
-        u"RViz Documentation",
-        u"Josh Faust, Dave Hershberger, David Gossow, and others",
+        "RViz Documentation",
+        "Josh Faust, Dave Hershberger, David Gossow, and others",
         "RViz",
         "One line description of project.",
         "Miscellaneous",
diff -pruN 1.14.14+dfsg-2/doc/youtube.py 1.14.15+dfsg-3/doc/youtube.py
--- 1.14.14+dfsg-2/doc/youtube.py	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/doc/youtube.py	2022-08-01 08:39:42.000000000 +0000
@@ -49,7 +49,7 @@ PARAM = """\n    <param name="%s" value=
 def youtube(
     name, args, options, content, lineno, contentOffset, blockText, state, stateMachine
 ):
-    """ Restructured text extension for inserting youtube embedded videos """
+    """Restructured text extension for inserting youtube embedded videos"""
     if len(content) == 0:
         return
     string_vars = {"yid": content[0], "width": 425, "height": 344, "extra": ""}
diff -pruN 1.14.14+dfsg-2/.github/workflows/abi.yaml 1.14.15+dfsg-3/.github/workflows/abi.yaml
--- 1.14.14+dfsg-2/.github/workflows/abi.yaml	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/.github/workflows/abi.yaml	2022-08-01 08:39:42.000000000 +0000
@@ -20,7 +20,7 @@ jobs:
       BASEDIR: /home/runner/work
       DOCKER_IMAGE: rhaschke/ici:rviz-${{ matrix.distro }}-${{ matrix.repo || 'ros' }}
       CACHE_PREFIX: ${{ matrix.distro }}
-      ABICHECK_URL: github:ros-visualization/rviz#1.14.10
+      ABICHECK_URL: github:ros-visualization/rviz#1.14.15
 
     name: "check"
     runs-on: ubuntu-latest
diff -pruN 1.14.14+dfsg-2/.github/workflows/ci.yaml 1.14.15+dfsg-3/.github/workflows/ci.yaml
--- 1.14.14+dfsg-2/.github/workflows/ci.yaml	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/.github/workflows/ci.yaml	2022-08-01 08:39:42.000000000 +0000
@@ -11,16 +11,20 @@ on:
 jobs:
   default:
     strategy:
+      fail-fast: false
       matrix:
         distro: [noetic]
+        ogre: ["1.9", "1.12"]
         include:
           - distro: noetic
+            ogre: 1.9
             env:
               CLANG_TIDY: true
 
     env:
       CXXFLAGS: "-Werror -Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-strict-aliasing -Wno-sign-compare"
       UPSTREAM_WORKSPACE: github:rhaschke/python_qt_binding#silent-external-warnings
+      AFTER_INSTALL_TARGET_DEPENDENCIES: apt install -qq -y libogre-${{ matrix.ogre }}-dev
       CATKIN_LINT: true
       CCACHE_DIR: ${{ github.workspace }}/.ccache
       BASEDIR: /home/runner/work
@@ -29,7 +33,7 @@ jobs:
       # perform full clang-tidy check only on manual trigger (workflow_dispatch), PRs do check changed files, otherwise nothing
       CLANG_TIDY_BASE_REF: ${{ github.event_name != 'workflow_dispatch' && (github.base_ref || github.ref) || '' }}
 
-    name: "${{ matrix.distro }}${{ matrix.repo && format(' • {0}', matrix.repo) || '' }}${{ matrix.env.CLANG_TIDY && (github.event_name != 'workflow_dispatch' && ' • clang-tidy (delta)' || ' • clang-tidy (all)') || '' }}"
+    name: "${{ matrix.distro }} • ogre ${{ matrix.ogre }}${{ matrix.env.CLANG_TIDY && (github.event_name != 'workflow_dispatch' && ' • clang-tidy (delta)' || ' • clang-tidy (all)') || '' }}"
     runs-on: ubuntu-latest
     steps:
       - uses: actions/checkout@v2
diff -pruN 1.14.14+dfsg-2/package.xml 1.14.15+dfsg-3/package.xml
--- 1.14.14+dfsg-2/package.xml	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/package.xml	2022-08-01 08:39:42.000000000 +0000
@@ -1,6 +1,6 @@
 <package format="2">
   <name>rviz</name>
-  <version>1.14.14</version>
+  <version>1.14.15</version>
   <description>
      3D visualization tool for ROS.
   </description>
diff -pruN 1.14.14+dfsg-2/.pre-commit-config.yaml 1.14.15+dfsg-3/.pre-commit-config.yaml
--- 1.14.14+dfsg-2/.pre-commit-config.yaml	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/.pre-commit-config.yaml	2022-08-01 08:39:42.000000000 +0000
@@ -28,7 +28,7 @@ repos:
       - id: trailing-whitespace
 
   - repo: https://github.com/psf/black
-    rev: 20.8b1
+    rev: 22.3.0
     hooks:
       - id: black
 
diff -pruN 1.14.14+dfsg-2/README.md 1.14.15+dfsg-3/README.md
--- 1.14.14+dfsg-2/README.md	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/README.md	2022-08-01 08:39:42.000000000 +0000
@@ -1,6 +1,8 @@
-![rviz logo](https://raw.githubusercontent.com/ros-visualization/rviz/melodic-devel/images/splash.png)
+![rviz logo](https://raw.githubusercontent.com/ros-visualization/rviz/noetic-devel/images/splash.png)
 
-[![Build Status](http://build.ros.org/buildStatus/icon?job=Mdev__rviz__ubuntu_bionic_amd64)](http://build.ros.org/view/Mdev/job/Mdev__rviz__ubuntu_bionic_amd64/)
+[![Format](https://github.com/ros-visualization/rviz/actions/workflows/format.yaml/badge.svg?branch=noetic-devel)](https://github.com/ros-visualization/rviz/actions/workflows/format.yaml?query=branch%3Anoetic-devel)
+[![CI](https://github.com/ros-visualization/rviz/actions/workflows/ci.yaml/badge.svg?branch=noetic-devel)](https://github.com/ros-visualization/rviz/actions/workflows/ci.yaml?query=branch%3Anoetic-devel)
+[![ROS CI](https://build.ros.org/buildStatus/icon?job=Ndev__rviz__ubuntu_focal_amd64)](https://build.ros.org/view/Ndev/job/Ndev__rviz__ubuntu_focal_amd64/)
 
 rviz is a 3D visualizer for the Robot Operating System (ROS) framework.
 
diff -pruN 1.14.14+dfsg-2/src/image_view/CMakeLists.txt 1.14.15+dfsg-3/src/image_view/CMakeLists.txt
--- 1.14.14+dfsg-2/src/image_view/CMakeLists.txt	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/image_view/CMakeLists.txt	2022-08-01 08:39:42.000000000 +0000
@@ -2,9 +2,6 @@ add_executable(rviz_image_view
   image_view.cpp
   main.cpp
 )
-if(NOT WIN32)
-  set_target_properties(rviz_image_view PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 
 target_link_libraries(rviz_image_view
   ${OGRE_LIBRARIES}
diff -pruN 1.14.14+dfsg-2/src/image_view/image_view.cpp 1.14.15+dfsg-3/src/image_view/image_view.cpp
--- 1.14.14+dfsg-2/src/image_view/image_view.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/image_view/image_view.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -39,17 +39,17 @@
 #include "ros/ros.h"
 #include <ros/package.h>
 
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreRenderWindow.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreRectangle2D.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTextureUnitState.h>
-#include <OGRE/OgreSharedPtr.h>
-#include <OGRE/OgreTechnique.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreRoot.h>
+#include <OgreRenderWindow.h>
+#include <OgreSceneManager.h>
+#include <OgreViewport.h>
+#include <OgreRectangle2D.h>
+#include <OgreMaterial.h>
+#include <OgreMaterialManager.h>
+#include <OgreTextureUnitState.h>
+#include <OgreSharedPtr.h>
+#include <OgreTechnique.h>
+#include <OgreSceneNode.h>
 
 #include "image_view.h"
 
@@ -94,7 +94,8 @@ void ImageView::showEvent(QShowEvent* ev
 
     texture_sub_.reset(new image_transport::SubscriberFilter());
     texture_sub_->subscribe(texture_it_, "image", 1, image_transport::TransportHints("raw"));
-    texture_sub_->registerCallback(boost::bind(&ImageView::textureCallback, this, _1));
+    texture_sub_->registerCallback(
+        boost::bind(&ImageView::textureCallback, this, boost::placeholders::_1));
   }
   catch (ros::Exception& e)
   {
diff -pruN 1.14.14+dfsg-2/src/image_view/image_view.h 1.14.15+dfsg-3/src/image_view/image_view.h
--- 1.14.14+dfsg-2/src/image_view/image_view.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/image_view/image_view.h	2022-08-01 08:39:42.000000000 +0000
@@ -35,13 +35,13 @@
 #include "ros/ros.h"
 #include <ros/package.h>
 
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreRectangle2D.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTextureUnitState.h>
+#include <OgreRoot.h>
+#include <OgreSceneManager.h>
+#include <OgreViewport.h>
+#include <OgreRectangle2D.h>
+#include <OgreMaterial.h>
+#include <OgreMaterialManager.h>
+#include <OgreTextureUnitState.h>
 
 #include <image_transport/image_transport.h>
 #include <image_transport/subscriber_filter.h>
diff -pruN 1.14.14+dfsg-2/src/python_bindings/shiboken/CMakeLists.txt 1.14.15+dfsg-3/src/python_bindings/shiboken/CMakeLists.txt
--- 1.14.14+dfsg-2/src/python_bindings/shiboken/CMakeLists.txt	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/python_bindings/shiboken/CMakeLists.txt	2022-08-01 08:39:42.000000000 +0000
@@ -90,9 +90,6 @@ if(shiboken_helper_FOUND)
     )
     shiboken_include_directories(rviz_shiboken "${rviz_shiboken_QT_COMPONENTS}")
     add_library(rviz_shiboken ${rviz_shiboken_SRCS})
-    if(NOT WIN32)
-      set_target_properties(rviz_shiboken PROPERTIES COMPILE_FLAGS "-std=c++11")
-    endif()
     set_target_properties(rviz_shiboken PROPERTIES
       LIBRARY_OUTPUT_DIRECTORY ${CATKIN_DEVEL_PREFIX}/${PYTHON_INSTALL_DIR}/rviz)
     target_link_libraries(rviz_shiboken ${PROJECT_NAME})
diff -pruN 1.14.14+dfsg-2/src/python_bindings/sip/CMakeLists.txt 1.14.15+dfsg-3/src/python_bindings/sip/CMakeLists.txt
--- 1.14.14+dfsg-2/src/python_bindings/sip/CMakeLists.txt	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/python_bindings/sip/CMakeLists.txt	2022-08-01 08:39:42.000000000 +0000
@@ -66,7 +66,9 @@ if(sip_helper_FOUND)
     DEPENDS ${rviz_sip_DEPENDENT_FILES}
     DEPENDENCIES rviz
   )
-  if(APPLE)
+  if(DEFINED PYTHON_EXTENSION_MODULE_SUFFIX)
+    set(rviz_sip_LIBRARY_FILE librviz_sip${PYTHON_EXTENSION_MODULE_SUFFIX})
+  elseif(APPLE)
     set(rviz_sip_LIBRARY_FILE librviz_sip.so)
   elseif(WIN32)
     set(rviz_sip_LIBRARY_FILE librviz_sip.pyd)
diff -pruN 1.14.14+dfsg-2/src/rviz/CMakeLists.txt 1.14.15+dfsg-3/src/rviz/CMakeLists.txt
--- 1.14.14+dfsg-2/src/rviz/CMakeLists.txt	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/CMakeLists.txt	2022-08-01 08:39:42.000000000 +0000
@@ -128,9 +128,6 @@ add_library(${PROJECT_NAME}
 include(GenerateExportHeader)
 set(EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/rviz/${PROJECT_NAME}_export.h)
 generate_export_header(${PROJECT_NAME} EXPORT_FILE_NAME ${EXPORT_FILE_NAME})
-if(NOT WIN32)
-  set_target_properties(${PROJECT_NAME} PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 
 target_link_libraries(${PROJECT_NAME}
   ${Boost_LIBRARIES}
@@ -155,10 +152,6 @@ endif(APPLE)
 ########### The rviz executable ###########
 add_executable(executable main.cpp)
 
-if(NOT WIN32)
-  set_target_properties(executable PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
-
 target_link_libraries(executable ${PROJECT_NAME} ${QT_LIBRARIES} ${OGRE_LIBRARIES})
 
 set_target_properties(executable
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/axes_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/axes_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/axes_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/axes_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,11 +27,11 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreRibbonTrail.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreRibbonTrail.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/camera_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/camera_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/camera_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/camera_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,19 +27,19 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreRectangle2D.h>
-#include <OGRE/OgreRenderSystem.h>
-#include <OGRE/OgreRenderWindow.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreTechnique.h>
-#include <OGRE/OgreCamera.h>
+#include <OgreManualObject.h>
+#include <OgreMaterialManager.h>
+#include <OgreRectangle2D.h>
+#include <OgreRenderSystem.h>
+#include <OgreRenderWindow.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreTextureManager.h>
+#include <OgreViewport.h>
+#include <OgreTechnique.h>
+#include <OgreCamera.h>
 
 #include <tf2_ros/message_filter.h>
 
@@ -110,7 +110,7 @@ CameraDisplay::~CameraDisplay()
   {
     render_panel_->getRenderWindow()->removeListener(this);
 
-    unsubscribe();
+    CameraDisplay::unsubscribe();
 
     delete render_panel_;
     delete bg_screen_rect_;
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/camera_display.h 1.14.15+dfsg-3/src/rviz/default_plugin/camera_display.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/camera_display.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/camera_display.h	2022-08-01 08:39:42.000000000 +0000
@@ -35,9 +35,9 @@
 #include <QObject>
 
 #ifndef Q_MOC_RUN
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreRenderTargetListener.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreMaterial.h>
+#include <OgreRenderTargetListener.h>
+#include <OgreSharedPtr.h>
 
 #include <sensor_msgs/CameraInfo.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/CMakeLists.txt 1.14.15+dfsg-3/src/rviz/default_plugin/CMakeLists.txt
--- 1.14.14+dfsg-2/src/rviz/default_plugin/CMakeLists.txt	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/CMakeLists.txt	2022-08-01 08:39:42.000000000 +0000
@@ -72,10 +72,6 @@ add_library(${rviz_DEFAULT_PLUGIN_LIBRAR
 include(GenerateExportHeader)
 set(EXPORT_FILE_NAME ${EXPORT_HEADER_DIR}/rviz/default_plugin/${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME}_export.h)
 generate_export_header(${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME} EXPORT_FILE_NAME ${EXPORT_FILE_NAME})
-if(NOT WIN32)
-  set_target_properties(${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME}
-    PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(${rviz_DEFAULT_PLUGIN_LIBRARY_TARGET_NAME}
   ${PROJECT_NAME}
   ${Boost_LIBRARIES}
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/covariance_property.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/covariance_property.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/covariance_property.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/covariance_property.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -36,8 +36,8 @@
 
 #include <QColor>
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/covariance_property.h 1.14.15+dfsg-3/src/rviz/default_plugin/covariance_property.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/covariance_property.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/covariance_property.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,7 +32,7 @@
 
 #include <QColor>
 
-#include <OGRE/OgreColourValue.h>
+#include <OgreColourValue.h>
 
 #include <rviz/properties/bool_property.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/covariance_visual.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/covariance_visual.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/covariance_visual.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/covariance_visual.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -32,9 +32,9 @@
 #include <rviz/ogre_helpers/shape.h>
 #include <rviz/validate_quaternions.h>
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreQuaternion.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreQuaternion.h>
 
 #include <ros/console.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/covariance_visual.h 1.14.15+dfsg-3/src/rviz/default_plugin/covariance_visual.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/covariance_visual.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/covariance_visual.h	2022-08-01 08:39:42.000000000 +0000
@@ -40,8 +40,8 @@
 
 #include <Eigen/Dense>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreColourValue.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreColourValue.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/depth_cloud_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/depth_cloud_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/depth_cloud_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/depth_cloud_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -41,13 +41,13 @@
 
 #include <tf2_ros/buffer.h>
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 #include <boost/algorithm/string/erase.hpp>
 #include <boost/foreach.hpp>
 #include <boost/shared_ptr.hpp>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <image_transport/camera_common.h>
 #include <image_transport/subscriber_plugin.h>
@@ -302,7 +302,8 @@ void DepthCloudDisplay::subscribe()
       // subscribe to CameraInfo  topic
       std::string info_topic = image_transport::getCameraInfoTopic(depthmap_topic);
       cam_info_sub_->subscribe(threaded_nh_, info_topic, queue_size_);
-      cam_info_sub_->registerCallback(boost::bind(&DepthCloudDisplay::caminfoCallback, this, _1));
+      cam_info_sub_->registerCallback(
+          boost::bind(&DepthCloudDisplay::caminfoCallback, this, boost::placeholders::_1));
 
       if (!color_topic.empty() && !color_transport.empty())
       {
@@ -314,14 +315,15 @@ void DepthCloudDisplay::subscribe()
         sync_depth_color_->connectInput(*depthmap_tf_filter_, *rgb_sub_);
         sync_depth_color_->setInterMessageLowerBound(0, ros::Duration(0.5));
         sync_depth_color_->setInterMessageLowerBound(1, ros::Duration(0.5));
-        sync_depth_color_->registerCallback(
-            boost::bind(&DepthCloudDisplay::processMessage, this, _1, _2));
+        sync_depth_color_->registerCallback(boost::bind(
+            &DepthCloudDisplay::processMessage, this, boost::placeholders::_1, boost::placeholders::_2));
 
         pointcloud_common_->color_transformer_property_->setValue("RGB8");
       }
       else
       {
-        depthmap_tf_filter_->registerCallback(boost::bind(&DepthCloudDisplay::processMessage, this, _1));
+        depthmap_tf_filter_->registerCallback(
+            boost::bind(&DepthCloudDisplay::processMessage, this, boost::placeholders::_1));
       }
     }
   }
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/effort_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/effort_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/effort_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/effort_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -1,5 +1,5 @@
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 #include <QTimer>
 
 #include <rviz/visualization_manager.h>
@@ -119,7 +119,7 @@ void EffortDisplay::onInitialize()
                                                                    std::string(), 1, update_nh_);
 
   // but directly process messages
-  sub_.registerCallback(boost::bind(&EffortDisplay::incomingMessage, this, _1));
+  sub_.registerCallback(boost::bind(&EffortDisplay::incomingMessage, this, boost::placeholders::_1));
   updateHistoryLength();
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/effort_visual.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/effort_visual.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/effort_visual.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/effort_visual.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -1,6 +1,6 @@
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <rviz/ogre_helpers/arrow.h>
 #include <rviz/ogre_helpers/billboard_line.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/effort_visual.h 1.14.15+dfsg-3/src/rviz/default_plugin/effort_visual.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/effort_visual.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/effort_visual.h	2022-08-01 08:39:42.000000000 +0000
@@ -1,7 +1,7 @@
 #ifndef EFFORT_VISUAL_H
 #define EFFORT_VISUAL_H
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/fluid_pressure_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/fluid_pressure_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/fluid_pressure_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/fluid_pressure_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <ros/time.h>
 
@@ -50,6 +50,7 @@ FluidPressureDisplay::FluidPressureDispl
 
 FluidPressureDisplay::~FluidPressureDisplay()
 {
+  FluidPressureDisplay::unsubscribe();
   delete point_cloud_common_;
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/grid_cells_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/grid_cells_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/grid_cells_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/grid_cells_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,11 +27,10 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreBillboardSet.h>
+#include <boost/bind/bind.hpp>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreManualObject.h>
 
 #include <rviz/frame_manager.h>
 #include <rviz/ogre_helpers/arrow.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/grid_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/grid_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/grid_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/grid_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,10 +29,10 @@
 
 #include <stdint.h>
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/illuminance_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/illuminance_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/illuminance_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/illuminance_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <ros/time.h>
 
@@ -50,6 +50,7 @@ IlluminanceDisplay::IlluminanceDisplay()
 
 IlluminanceDisplay::~IlluminanceDisplay()
 {
+  IlluminanceDisplay::unsubscribe();
   delete point_cloud_common_;
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/image_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/image_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/image_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/image_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,20 +27,20 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreRectangle2D.h>
-#include <OGRE/OgreRenderSystem.h>
-#include <OGRE/OgreRenderWindow.h>
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreTechnique.h>
-#include <OGRE/OgreCamera.h>
+#include <OgreManualObject.h>
+#include <OgreMaterialManager.h>
+#include <OgreRectangle2D.h>
+#include <OgreRenderSystem.h>
+#include <OgreRenderWindow.h>
+#include <OgreRoot.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreTextureManager.h>
+#include <OgreViewport.h>
+#include <OgreTechnique.h>
+#include <OgreCamera.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/image_display.h 1.14.15+dfsg-3/src/rviz/default_plugin/image_display.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/image_display.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/image_display.h	2022-08-01 08:39:42.000000000 +0000
@@ -33,9 +33,9 @@
 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
 #include <QObject>
 
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreRenderTargetListener.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreMaterial.h>
+#include <OgreRenderTargetListener.h>
+#include <OgreSharedPtr.h>
 
 #include "rviz/image/image_display_base.h"
 #include "rviz/image/ros_image_texture.h"
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_marker_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_marker_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_marker_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_marker_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -109,10 +109,12 @@ void InteractiveMarkerDisplay::onInitial
   auto tf = context_->getFrameManager()->getTF2BufferPtr();
   im_client_.reset(new interactive_markers::InteractiveMarkerClient(*tf, fixed_frame_.toStdString()));
 
-  im_client_->setInitCb(boost::bind(&InteractiveMarkerDisplay::initCb, this, _1));
-  im_client_->setUpdateCb(boost::bind(&InteractiveMarkerDisplay::updateCb, this, _1));
-  im_client_->setResetCb(boost::bind(&InteractiveMarkerDisplay::resetCb, this, _1));
-  im_client_->setStatusCb(boost::bind(&InteractiveMarkerDisplay::statusCb, this, _1, _2, _3));
+  im_client_->setInitCb(boost::bind(&InteractiveMarkerDisplay::initCb, this, boost::placeholders::_1));
+  im_client_->setUpdateCb(
+      boost::bind(&InteractiveMarkerDisplay::updateCb, this, boost::placeholders::_1));
+  im_client_->setResetCb(boost::bind(&InteractiveMarkerDisplay::resetCb, this, boost::placeholders::_1));
+  im_client_->setStatusCb(boost::bind(&InteractiveMarkerDisplay::statusCb, this, boost::placeholders::_1,
+                                      boost::placeholders::_2, boost::placeholders::_3));
 
   client_id_ = ros::this_node::getName() + "/" + getNameStd();
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_markers/interactive_marker_control.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_markers/interactive_marker_control.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_markers/interactive_marker_control.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_markers/interactive_marker_control.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,16 +27,16 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgrePass.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreSubEntity.h>
-#include <OGRE/OgreSharedPtr.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgrePass.h>
+#include <OgreMaterial.h>
+#include <OgreEntity.h>
+#include <OgreSubEntity.h>
+#include <OgreSharedPtr.h>
+#include <OgreTechnique.h>
 
 #include <rviz/display_context.h>
 #include <rviz/selection/selection_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_markers/interactive_marker_control.h 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_markers/interactive_marker_control.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_markers/interactive_marker_control.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_markers/interactive_marker_control.h	2022-08-01 08:39:42.000000000 +0000
@@ -34,10 +34,10 @@
 #include <boost/shared_ptr.hpp>
 #include <boost/enable_shared_from_this.hpp>
 
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreRay.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreSceneManager.h>
 #endif
 
 #include <QCursor>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,13 +31,13 @@
 
 #include <QMenu>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreResourceGroupManager.h>
-#include <OGRE/OgreSubEntity.h>
-#include <OGRE/OgreMath.h>
-#include <OGRE/OgreRenderWindow.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreMaterialManager.h>
+#include <OgreResourceGroupManager.h>
+#include <OgreSubEntity.h>
+#include <OgreMath.h>
+#include <OgreRenderWindow.h>
 
 #include <ros/ros.h>
 #include <interactive_markers/tools.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_markers/interactive_marker.h 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_markers/interactive_marker.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/interactive_markers/interactive_marker.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/interactive_markers/interactive_marker.h	2022-08-01 08:39:42.000000000 +0000
@@ -36,8 +36,8 @@
 #include <boost/thread/recursive_mutex.hpp>
 #include <boost/thread/thread.hpp>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 #endif
 
 #include <visualization_msgs/InteractiveMarker.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/laser_scan_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/laser_scan_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/laser_scan_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/laser_scan_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <ros/time.h>
 
@@ -52,6 +52,7 @@ LaserScanDisplay::LaserScanDisplay()
 
 LaserScanDisplay::~LaserScanDisplay()
 {
+  LaserScanDisplay::unsubscribe();
   delete point_cloud_common_;
   delete projector_;
 }
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/map_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/map_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/map_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/map_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,15 +27,15 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreTechnique.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreManualObject.h>
+#include <OgreMaterialManager.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreTextureManager.h>
+#include <OgreTechnique.h>
+#include <OgreSharedPtr.h>
 
 #include <ros/ros.h>
 
@@ -272,7 +272,7 @@ MapDisplay::MapDisplay() : Display(), lo
 
 MapDisplay::~MapDisplay()
 {
-  unsubscribe();
+  MapDisplay::unsubscribe();
   clear();
   for (unsigned i = 0; i < swatches.size(); i++)
   {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/map_display.h 1.14.15+dfsg-3/src/rviz/default_plugin/map_display.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/map_display.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/map_display.h	2022-08-01 08:39:42.000000000 +0000
@@ -33,10 +33,10 @@
 #ifndef Q_MOC_RUN
 #include <boost/thread/thread.hpp>
 
-#include <OGRE/OgreTexture.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreTexture.h>
+#include <OgreMaterial.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreSharedPtr.h>
 #endif
 
 #include <nav_msgs/MapMetaData.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/marker_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/marker_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/marker_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/marker_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -77,8 +77,10 @@ void MarkerDisplay::onInitialize()
                                                              queue_size_property_->getInt(), update_nh_);
 
   tf_filter_->connectInput(sub_);
-  tf_filter_->registerCallback(boost::bind(&MarkerDisplay::incomingMarker, this, _1));
-  tf_filter_->registerFailureCallback(boost::bind(&MarkerDisplay::failedMarker, this, _1, _2));
+  tf_filter_->registerCallback(
+      boost::bind(&MarkerDisplay::incomingMarker, this, boost::placeholders::_1));
+  tf_filter_->registerFailureCallback(
+      boost::bind(&MarkerDisplay::failedMarker, this, boost::placeholders::_1, boost::placeholders::_2));
 
   namespace_config_enabled_state_.clear();
 }
@@ -87,7 +89,7 @@ MarkerDisplay::~MarkerDisplay()
 {
   if (initialized())
   {
-    unsubscribe();
+    MarkerDisplay::unsubscribe();
 
     clearMarkers();
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/arrow_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/arrow_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/arrow_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/arrow_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,11 +27,11 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreEntity.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreEntity.h>
 
 #include <rviz/default_plugin/marker_display.h>
 #include <rviz/default_plugin/markers/marker_selection_handler.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/line_list_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/line_list_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/line_list_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/line_list_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -34,9 +34,9 @@
 
 #include <rviz/ogre_helpers/billboard_line.h>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreSceneNode.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/line_strip_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/line_strip_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/line_strip_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/line_strip_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -36,9 +36,9 @@
 
 #include <rviz/ogre_helpers/billboard_line.h>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreSceneNode.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/marker_base.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/marker_base.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/marker_base.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/marker_base.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -34,11 +34,11 @@
 #include "marker_selection_handler.h"
 #include <rviz/frame_manager.h>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreSubEntity.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreEntity.h>
+#include <OgreSubEntity.h>
+#include <OgreSharedPtr.h>
 
 
 #include <utility>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/marker_base.h 1.14.15+dfsg-3/src/rviz/default_plugin/markers/marker_base.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/marker_base.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/marker_base.h	2022-08-01 08:39:42.000000000 +0000
@@ -39,7 +39,7 @@
 
 #include <boost/shared_ptr.hpp>
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/marker_selection_handler.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/marker_selection_handler.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/marker_selection_handler.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/marker_selection_handler.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreVector3.h>
+#include <OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <rviz/default_plugin/interactive_markers/interactive_marker_control.h>
 #include <rviz/default_plugin/marker_display.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/mesh_resource_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/mesh_resource_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/mesh_resource_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/mesh_resource_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -36,14 +36,14 @@
 #include <rviz/display_context.h>
 #include <rviz/mesh_loader.h>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreSubEntity.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreSharedPtr.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreEntity.h>
+#include <OgreSubEntity.h>
+#include <OgreMaterialManager.h>
+#include <OgreTextureManager.h>
+#include <OgreSharedPtr.h>
+#include <OgreTechnique.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/mesh_resource_marker.h 1.14.15+dfsg-3/src/rviz/default_plugin/markers/mesh_resource_marker.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/mesh_resource_marker.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/mesh_resource_marker.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,7 +32,7 @@
 
 #include "marker_base.h"
 
-#include <OGRE/OgreMaterial.h>
+#include <OgreMaterial.h>
 
 #include <vector>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/points_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/points_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/points_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/points_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -35,10 +35,10 @@
 
 #include <rviz/ogre_helpers/point_cloud.h>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/shape_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/shape_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/shape_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/shape_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -36,8 +36,8 @@
 
 #include <rviz/ogre_helpers/shape.h>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreMatrix3.h>
+#include <OgreSceneNode.h>
+#include <OgreMatrix3.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/text_view_facing_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/text_view_facing_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/text_view_facing_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/text_view_facing_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <ros/assert.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/triangle_list_marker.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/markers/triangle_list_marker.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/triangle_list_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/triangle_list_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -37,12 +37,12 @@
 #include <rviz/display_context.h>
 #include <rviz/mesh_loader.h>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreManualObject.h>
+#include <OgreMaterialManager.h>
+#include <OgreTextureManager.h>
+#include <OgreTechnique.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/markers/triangle_list_marker.h 1.14.15+dfsg-3/src/rviz/default_plugin/markers/triangle_list_marker.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/markers/triangle_list_marker.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/markers/triangle_list_marker.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,8 +30,8 @@
 #ifndef RVIZ_TRIANGLE_LIST_MARKER_H
 #define RVIZ_TRIANGLE_LIST_MARKER_H
 
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreMaterial.h>
+#include <OgreSharedPtr.h>
 
 #include <rviz/default_plugin/markers/marker_base.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/odometry_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/odometry_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/odometry_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/odometry_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -36,8 +36,8 @@
 #include <rviz/validate_floats.h>
 #include <rviz/validate_quaternions.h>
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
 
 #include "odometry_display.h"
 #include "covariance_property.h"
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/path_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/path_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/path_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/path_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,13 +27,12 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreBillboardSet.h>
-#include <OGRE/OgreMatrix4.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreManualObject.h>
+#include <OgreMatrix4.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud2_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud2_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud2_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud2_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <ros/time.h>
 
@@ -50,6 +50,7 @@ PointCloud2Display::PointCloud2Display()
 
 PointCloud2Display::~PointCloud2Display()
 {
+  PointCloud2Display::unsubscribe();
   delete point_cloud_common_;
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud_common.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud_common.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud_common.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud_common.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,9 +29,9 @@
 
 #include <QColor>
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreWireBoundingBox.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreWireBoundingBox.h>
 
 #include <ros/time.h>
 
@@ -380,6 +380,9 @@ void PointCloudCommon::initialize(Displa
 
 PointCloudCommon::~PointCloudCommon()
 {
+  // Ensure any threads holding the mutexes have finished
+  boost::recursive_mutex::scoped_lock lock1(transformers_mutex_);
+  boost::mutex::scoped_lock lock2(new_clouds_mutex_);
   delete transformer_class_loader_;
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <ros/time.h>
 
@@ -48,6 +48,7 @@ PointCloudDisplay::PointCloudDisplay() :
 
 PointCloudDisplay::~PointCloudDisplay()
 {
+  PointCloudDisplay::unsubscribe();
   delete point_cloud_common_;
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud_transformer.h 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud_transformer.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud_transformer.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud_transformer.h	2022-08-01 08:39:42.000000000 +0000
@@ -35,8 +35,8 @@
 #include <ros/message_forward.h>
 
 #ifndef Q_MOC_RUN
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreColourValue.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreColourValue.h>
 
 #include <rviz/ogre_helpers/point_cloud.h>
 #endif
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud_transformers.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud_transformers.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/point_cloud_transformers.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/point_cloud_transformers.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,9 +27,9 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreColourValue.h>
-#include <OGRE/OgreMatrix4.h>
-#include <OGRE/OgreVector3.h>
+#include <OgreColourValue.h>
+#include <OgreMatrix4.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <rviz/properties/bool_property.h>
 #include <rviz/properties/color_property.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/point_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/point_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/point_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/point_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -1,5 +1,5 @@
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <rviz/visualization_manager.h>
 #include <rviz/properties/color_property.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/point_visual.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/point_visual.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/point_visual.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/point_visual.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -1,6 +1,6 @@
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <rviz/ogre_helpers/shape.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/point_visual.h 1.14.15+dfsg-3/src/rviz/default_plugin/point_visual.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/point_visual.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/point_visual.h	2022-08-01 08:39:42.000000000 +0000
@@ -3,7 +3,7 @@
 
 #include <geometry_msgs/PointStamped.h>
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/polygon_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/polygon_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/polygon_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/polygon_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,10 +27,9 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreBillboardSet.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreManualObject.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/pose_array_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/pose_array_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/pose_array_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/pose_array_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,9 +27,9 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreManualObject.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/pose_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/pose_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/pose_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/pose_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreEntity.h>
+#include <OgreSceneNode.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/pose_with_covariance_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/pose_with_covariance_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/pose_with_covariance_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/pose_with_covariance_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreEntity.h>
+#include <OgreSceneNode.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/range_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/range_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/range_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/range_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/relative_humidity_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/relative_humidity_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/relative_humidity_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/relative_humidity_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <ros/time.h>
 
@@ -50,6 +50,7 @@ RelativeHumidityDisplay::RelativeHumidit
 
 RelativeHumidityDisplay::~RelativeHumidityDisplay()
 {
+  RelativeHumidityDisplay::unsubscribe();
   delete point_cloud_common_;
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/robot_model_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/robot_model_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/robot_model_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/robot_model_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 #include <QTimer>
 
 #include <urdf/model.h>
@@ -205,7 +205,8 @@ void RobotModelDisplay::load()
               QString("Errors loading geometries:").append(ss.str().c_str()));
 
   robot_->update(TFLinkUpdater(context_->getFrameManager(),
-                               boost::bind(linkUpdaterStatusFunction, _1, _2, _3, this),
+                               boost::bind(linkUpdaterStatusFunction, boost::placeholders::_1,
+                                           boost::placeholders::_2, boost::placeholders::_3, this),
                                tf_prefix_property_->getStdString()));
 }
 
@@ -230,7 +231,8 @@ void RobotModelDisplay::update(float wal
   if (has_new_transforms_ || update)
   {
     robot_->update(TFLinkUpdater(context_->getFrameManager(),
-                                 boost::bind(linkUpdaterStatusFunction, _1, _2, _3, this),
+                                 boost::bind(linkUpdaterStatusFunction, boost::placeholders::_1,
+                                             boost::placeholders::_2, boost::placeholders::_3, this),
                                  tf_prefix_property_->getStdString()));
     context_->queueRender();
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/robot_model_display.h 1.14.15+dfsg-3/src/rviz/default_plugin/robot_model_display.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/robot_model_display.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/robot_model_display.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,7 +32,7 @@
 
 #include <rviz/display.h>
 
-#include <OGRE/OgreVector3.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <map>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/screw_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/screw_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/screw_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/screw_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -1,5 +1,5 @@
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <rviz/visualization_manager.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/screw_visual.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/screw_visual.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/screw_visual.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/screw_visual.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -1,6 +1,6 @@
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <rviz/ogre_helpers/arrow.h>
 #include <rviz/ogre_helpers/billboard_line.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/screw_visual.h 1.14.15+dfsg-3/src/rviz/default_plugin/screw_visual.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/screw_visual.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/screw_visual.h	2022-08-01 08:39:42.000000000 +0000
@@ -2,7 +2,7 @@
 #define SCREW_VISUAL_H
 
 #include <geometry_msgs/Vector3.h>
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/temperature_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/temperature_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/temperature_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/temperature_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <ros/time.h>
 
@@ -50,6 +50,7 @@ TemperatureDisplay::TemperatureDisplay()
 
 TemperatureDisplay::~TemperatureDisplay()
 {
+  TemperatureDisplay::unsubscribe();
   delete point_cloud_common_;
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tf_display.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/tf_display.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tf_display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tf_display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,10 +27,10 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tf_display.h 1.14.15+dfsg-3/src/rviz/default_plugin/tf_display.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tf_display.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tf_display.h	2022-08-01 08:39:42.000000000 +0000
@@ -33,8 +33,8 @@
 #include <map>
 #include <set>
 
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreVector3.h>
+#include <OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <rviz/selection/forwards.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tools/focus_tool.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/tools/focus_tool.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tools/focus_tool.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tools/focus_tool.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,10 +27,10 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreCamera.h>
+#include <OgreRay.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreViewport.h>
+#include <OgreCamera.h>
 
 #include <rviz/viewport_mouse_event.h>
 #include <rviz/load_resource.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tools/interaction_tool.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/tools/interaction_tool.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tools/interaction_tool.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tools/interaction_tool.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,11 +27,11 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgrePlane.h>
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgrePlane.h>
+#include <OgreRay.h>
+#include <OgreSceneNode.h>
+#include <OgreViewport.h>
 
 #include <rviz/render_panel.h>
 #include <rviz/selection/selection_handler.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tools/measure_tool.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/tools/measure_tool.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tools/measure_tool.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tools/measure_tool.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -41,7 +41,7 @@
 #include <rviz/selection/selection_manager.h>
 #include <rviz/load_resource.h>
 
-#include <OGRE/OgreSceneNode.h>
+#include <OgreSceneNode.h>
 
 #include <sstream>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tools/measure_tool.h 1.14.15+dfsg-3/src/rviz/default_plugin/tools/measure_tool.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tools/measure_tool.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tools/measure_tool.h	2022-08-01 08:39:42.000000000 +0000
@@ -38,7 +38,7 @@
 
 #include <rviz/tool.h>
 
-#include <OGRE/OgreVector3.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tools/point_tool.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/tools/point_tool.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tools/point_tool.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tools/point_tool.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgreVector3.h>
+#include <OgreRay.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <rviz/viewport_mouse_event.h>
 #include <rviz/load_resource.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tools/pose_tool.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/tools/pose_tool.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tools/pose_tool.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tools/pose_tool.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,10 +27,10 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgrePlane.h>
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreViewport.h>
+#include <OgrePlane.h>
+#include <OgreRay.h>
+#include <OgreSceneNode.h>
+#include <OgreViewport.h>
 
 #include <rviz/geometry.h>
 #include <rviz/ogre_helpers/arrow.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tools/pose_tool.h 1.14.15+dfsg-3/src/rviz/default_plugin/tools/pose_tool.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tools/pose_tool.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tools/pose_tool.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,7 +30,7 @@
 #ifndef RVIZ_POSE_TOOL_H
 #define RVIZ_POSE_TOOL_H
 
-#include <OGRE/OgreVector3.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <QCursor>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/tools/selection_tool.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/tools/selection_tool.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/tools/selection_tool.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/tools/selection_tool.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,16 +29,16 @@
 
 #include <QKeyEvent>
 
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreMovableObject.h>
-#include <OGRE/OgreRectangle2D.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTexture.h>
-#include <OGRE/OgreTextureManager.h>
+#include <OgreRay.h>
+#include <OgreSceneManager.h>
+#include <OgreCamera.h>
+#include <OgreMovableObject.h>
+#include <OgreRectangle2D.h>
+#include <OgreSceneNode.h>
+#include <OgreViewport.h>
+#include <OgreMaterialManager.h>
+#include <OgreTexture.h>
+#include <OgreTextureManager.h>
 
 #include <ros/time.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/fixed_orientation_ortho_view_controller.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/fixed_orientation_ortho_view_controller.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/fixed_orientation_ortho_view_controller.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/fixed_orientation_ortho_view_controller.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,12 +27,12 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgreQuaternion.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreViewport.h>
 
 #include <rviz/display_context.h>
 #include <rviz/ogre_helpers/orthographic.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/fixed_orientation_ortho_view_controller.h 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/fixed_orientation_ortho_view_controller.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/fixed_orientation_ortho_view_controller.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/fixed_orientation_ortho_view_controller.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,7 +32,7 @@
 
 #include <rviz/frame_position_tracking_view_controller.h>
 
-#include <OGRE/OgreQuaternion.h>
+#include <OgreQuaternion.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/fps_view_controller.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/fps_view_controller.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/fps_view_controller.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/fps_view_controller.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -35,9 +35,9 @@
 #include <rviz/properties/bool_property.h>
 #include <rviz/properties/vector_property.h>
 
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgreSceneNode.h>
 #include <Eigen/Geometry>
 #include <QSignalBlocker>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/frame_view_controller.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/frame_view_controller.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/frame_view_controller.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/frame_view_controller.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -35,9 +35,9 @@
 #include <rviz/properties/bool_property.h>
 #include <rviz/properties/vector_property.h>
 
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgreSceneNode.h>
 #include <Eigen/Geometry>
 #include <QSignalBlocker>
 
@@ -48,7 +48,7 @@ static const QString ANY_AXIS("arbitrary
 // helper function to create axis strings from option ID
 inline QString fmtAxis(int i)
 {
-  return QStringLiteral("%1%2 axis").arg(QChar(i % 2 ? '+' : '-')).arg(QChar('x' + (i - 1) / 2));
+  return QString("%1%2 axis").arg(QChar(i % 2 ? '+' : '-')).arg(QChar('x' + (i - 1) / 2));
 }
 
 FrameViewController::FrameViewController()
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/orbit_view_controller.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/orbit_view_controller.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/orbit_view_controller.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/orbit_view_controller.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,12 +29,12 @@
 
 #include <stdint.h>
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgreQuaternion.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreViewport.h>
 
 #include <rviz/display_context.h>
 #include <rviz/geometry.h>
@@ -137,25 +137,20 @@ void OrbitViewController::handleMouseEve
   int32_t diff_x = 0;
   int32_t diff_y = 0;
 
-  bool moved = false;
-
   if (event.type == QEvent::MouseButtonPress)
   {
     focal_shape_->getRootNode()->setVisible(true);
-    moved = true;
     dragging_ = true;
   }
   else if (event.type == QEvent::MouseButtonRelease)
   {
     focal_shape_->getRootNode()->setVisible(false);
-    moved = true;
     dragging_ = false;
   }
   else if (dragging_ && event.type == QEvent::MouseMove)
   {
     diff_x = event.x - event.last_x;
     diff_y = event.y - event.last_y;
-    moved = true;
   }
 
   // regular left-button drag
@@ -198,8 +193,6 @@ void OrbitViewController::handleMouseEve
     setCursor(event.shift() ? MoveXY : Rotate3D);
   }
 
-  moved = true;
-
   if (event.wheel_delta != 0)
   {
     int diff = event.wheel_delta;
@@ -211,14 +204,9 @@ void OrbitViewController::handleMouseEve
     {
       zoom(diff * 0.001 * distance);
     }
-
-    moved = true;
   }
 
-  if (moved)
-  {
-    context_->queueRender();
-  }
+  context_->queueRender();
 }
 
 void OrbitViewController::mimic(ViewController* source_view)
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/orbit_view_controller.h 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/orbit_view_controller.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/orbit_view_controller.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/orbit_view_controller.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,7 +30,7 @@
 #ifndef RVIZ_ORBIT_VIEW_CONTROLLER_H
 #define RVIZ_ORBIT_VIEW_CONTROLLER_H
 
-#include <OGRE/OgreVector3.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <QCursor>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,14 +31,14 @@
 
 #include <ros/ros.h>
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgrePlane.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreMath.h>
+#include <OgreCamera.h>
+#include <OgrePlane.h>
+#include <OgreQuaternion.h>
+#include <OgreRay.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreViewport.h>
+#include <OgreMath.h>
 
 #include <rviz/display_context.h>
 #include <rviz/ogre_helpers/shape.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.h 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,7 +32,7 @@
 
 #include <rviz/default_plugin/view_controllers/orbit_view_controller.h>
 
-#include <OGRE/OgreVector3.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/xy_orbit_view_controller.cpp 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/xy_orbit_view_controller.cpp
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/xy_orbit_view_controller.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/xy_orbit_view_controller.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,13 +31,13 @@
 
 #include <ros/ros.h>
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgrePlane.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgrePlane.h>
+#include <OgreQuaternion.h>
+#include <OgreRay.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreViewport.h>
 
 #include <rviz/display_context.h>
 #include <rviz/ogre_helpers/shape.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/xy_orbit_view_controller.h 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/xy_orbit_view_controller.h
--- 1.14.14+dfsg-2/src/rviz/default_plugin/view_controllers/xy_orbit_view_controller.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/default_plugin/view_controllers/xy_orbit_view_controller.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,7 +32,7 @@
 
 #include <rviz/default_plugin/view_controllers/orbit_view_controller.h>
 
-#include <OGRE/OgreVector3.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/display.cpp 1.14.15+dfsg-3/src/rviz/display.cpp
--- 1.14.14+dfsg-2/src/rviz/display.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/display.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -36,8 +36,8 @@
 #include <QMetaObject>
 #include <QWidget>
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
 
 #include <rviz/display_context.h>
 #include <rviz/ogre_helpers/apply_visibility_bits.h>
@@ -60,7 +60,7 @@ Display::Display()
   , visibility_bits_(0xFFFFFFFF)
   , associated_widget_(nullptr)
   , associated_widget_panel_(nullptr)
-  , associated_widget_visible_(false)
+  , suppress_hiding_associated_widget_panel_(false)
 {
   // Needed for timeSignal (see header) to work across threads
   qRegisterMetaType<ros::Time>();
@@ -284,7 +284,7 @@ void Display::setFixedFrame(const QStrin
 
 void Display::emitTimeSignal(ros::Time time)
 {
-  Q_EMIT(timeSignal(this, time));
+  Q_EMIT(timeSignal(time, QPrivateSignal()));
 }
 
 void Display::reset()
@@ -311,10 +311,7 @@ void Display::onEnableChanged()
     scene_node_->setVisible(true);
 
     if (associated_widget_panel_)
-    {
-      if (!associated_widget_visible_)
-        associated_widget_panel_->show();
-    }
+      associated_widget_panel_->show();
     else if (associated_widget_)
       associated_widget_->show();
 
@@ -327,7 +324,7 @@ void Display::onEnableChanged()
 
     if (associated_widget_panel_)
     {
-      if (associated_widget_visible_)
+      if (!suppress_hiding_associated_widget_panel_)
         associated_widget_panel_->hide();
     }
     else if (associated_widget_)
@@ -366,7 +363,6 @@ void Display::setAssociatedWidget(QWidge
     if (wm)
     {
       associated_widget_panel_ = wm->addPane(getName(), associated_widget_);
-      associated_widget_visible_ = true;
       connect(associated_widget_panel_, SIGNAL(visibilityChanged(bool)), this,
               SLOT(associatedPanelVisibilityChange(bool)));
       connect(associated_widget_panel_, SIGNAL(closed()), this, SLOT(disable()));
@@ -386,9 +382,10 @@ void Display::setAssociatedWidget(QWidge
 
 void Display::associatedPanelVisibilityChange(bool visible)
 {
-  associated_widget_visible_ = visible;
   // If something external makes the panel visible/invisible, make sure to enable/disable the display
+  suppress_hiding_associated_widget_panel_ = true;
   setEnabled(visible);
+  suppress_hiding_associated_widget_panel_ = false;
   // Remark: vice versa, in Display::onEnableChanged(),
   //         the panel is made visible/invisible when the display is enabled/disabled
 }
diff -pruN 1.14.14+dfsg-2/src/rviz/display_group.cpp 1.14.15+dfsg-3/src/rviz/display_group.cpp
--- 1.14.14+dfsg-2/src/rviz/display_group.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/display_group.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -46,7 +46,7 @@ DisplayGroup::DisplayGroup()
 
 DisplayGroup::~DisplayGroup()
 {
-  removeAllDisplays();
+  DisplayGroup::removeAllDisplays();
 }
 
 Qt::ItemFlags DisplayGroup::getViewFlags(int column) const
diff -pruN 1.14.14+dfsg-2/src/rviz/display.h 1.14.15+dfsg-3/src/rviz/display.h
--- 1.14.14+dfsg-2/src/rviz/display.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/display.h	2022-08-01 08:39:42.000000000 +0000
@@ -225,7 +225,7 @@ public:
 
 Q_SIGNALS:
 
-  void timeSignal(rviz::Display* display, ros::Time time);
+  void timeSignal(ros::Time time, QPrivateSignal);
 
 public Q_SLOTS:
   /** @brief Enable or disable this Display.
@@ -328,7 +328,7 @@ private:
   uint32_t visibility_bits_;
   QWidget* associated_widget_;
   PanelDockWidget* associated_widget_panel_;
-  bool associated_widget_visible_;
+  bool suppress_hiding_associated_widget_panel_;
 };
 
 } // end namespace rviz
diff -pruN 1.14.14+dfsg-2/src/rviz/displays_panel.cpp 1.14.15+dfsg-3/src/rviz/displays_panel.cpp
--- 1.14.14+dfsg-2/src/rviz/displays_panel.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/displays_panel.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -36,7 +36,7 @@
 #include <QApplication>
 #include <QProgressDialog>
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <rviz/display_factory.h>
 #include <rviz/display.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/frame_manager.cpp 1.14.15+dfsg-3/src/rviz/frame_manager.cpp
--- 1.14.14+dfsg-2/src/rviz/frame_manager.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/frame_manager.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -59,32 +59,30 @@ FrameManager::~FrameManager()
 
 void FrameManager::update()
 {
-  boost::mutex::scoped_lock lock(cache_mutex_);
-  if (!pause_)
+  if (pause_)
+    return;
+  else
   {
+    boost::mutex::scoped_lock lock(cache_mutex_);
     cache_.clear();
-  }
-
-  if (!pause_)
-  {
     switch (sync_mode_)
     {
-    case SyncOff:
+    case SyncOff: // always use latest time
       sync_time_ = ros::Time::now();
       break;
-    case SyncExact:
+    case SyncExact: // sync to external source
+      // sync_time_ set via syncTime()
       break;
     case SyncApprox:
-      // adjust current time offset to sync source
-      current_delta_ = 0.7 * current_delta_ + 0.3 * sync_delta_;
-      try
-      {
-        sync_time_ = ros::Time::now() - ros::Duration(current_delta_);
-      }
-      catch (...)
-      {
-        sync_time_ = ros::Time::now();
-      }
+      // sync_delta is a sliding average of current_delta_, i.e.
+      // approximating the average delay of incoming sync messages w.r.t. current time
+      sync_delta_ = 0.7 * sync_delta_ + 0.3 * current_delta_;
+      // date back sync_time_ to ensure finding TFs that are as old as now() - sync_delta_
+      sync_time_ = ros::Time::now() - ros::Duration(sync_delta_);
+      break;
+    case SyncFrame: // sync to current time
+      // date back sync_time_ to ensure finding TFs that are as old as now() - sync_delta_
+      sync_time_ = ros::Time::now() - ros::Duration(sync_delta_);
       break;
     }
   }
@@ -98,7 +96,6 @@ void FrameManager::setFixedFrame(const s
     if (fixed_frame_ != frame)
     {
       fixed_frame_ = frame;
-      fixed_frame_id_ = tf_buffer_->_lookupFrameNumber(fixed_frame_);
       cache_.clear();
       should_emit = true;
     }
@@ -119,8 +116,8 @@ void FrameManager::setSyncMode(SyncMode
 {
   sync_mode_ = mode;
   sync_time_ = ros::Time(0);
-  current_delta_ = 0;
   sync_delta_ = 0;
+  current_delta_ = 0;
 }
 
 void FrameManager::syncTime(ros::Time time)
@@ -128,6 +125,7 @@ void FrameManager::syncTime(ros::Time ti
   switch (sync_mode_)
   {
   case SyncOff:
+  case SyncFrame:
     break;
   case SyncExact:
     sync_time_ = time;
@@ -135,13 +133,13 @@ void FrameManager::syncTime(ros::Time ti
   case SyncApprox:
     if (time == ros::Time(0))
     {
-      sync_delta_ = 0;
+      current_delta_ = 0;
       return;
     }
-    // avoid exception due to negative time
-    if (ros::Time::now() >= time)
+    if (ros::Time::now() >= time) // avoid exception due to negative time
     {
-      sync_delta_ = (ros::Time::now() - time).toSec();
+      // estimate delay of sync message w.r.t. current time
+      current_delta_ = (ros::Time::now() - time).toSec();
     }
     else
     {
@@ -151,48 +149,22 @@ void FrameManager::syncTime(ros::Time ti
   }
 }
 
-bool FrameManager::adjustTime(const std::string& frame, ros::Time& time)
+void FrameManager::adjustTime(ros::Time& time)
 {
   // we only need to act if we get a zero timestamp, which means "latest"
   if (time != ros::Time())
-  {
-    return true;
-  }
+    return;
 
   switch (sync_mode_)
   {
   case SyncOff:
     break;
+  case SyncFrame:
   case SyncExact:
+  case SyncApprox:
     time = sync_time_;
     break;
-  case SyncApprox:
-  {
-    // if we don't have tf info for the given timestamp, use the latest available
-    ros::Time latest_time;
-    std::string error_string;
-    int error_code;
-    if (fixed_frame_id_ == 0) // we couldn't resolve the fixed_frame_id yet
-      fixed_frame_id_ = tf_buffer_->_lookupFrameNumber(fixed_frame_);
-
-    error_code = tf_buffer_->_getLatestCommonTime(fixed_frame_id_, tf_buffer_->_lookupFrameNumber(frame),
-                                                  latest_time, &error_string);
-
-    if (error_code != 0)
-    {
-      ROS_ERROR("Error getting latest time from frame '%s' to frame '%s': %s (Error code: %d)",
-                frame.c_str(), fixed_frame_.c_str(), error_string.c_str(), error_code);
-      return false;
-    }
-
-    if (latest_time > sync_time_)
-    {
-      time = sync_time_;
-    }
-  }
-  break;
   }
-  return true;
 }
 
 
@@ -201,10 +173,7 @@ bool FrameManager::getTransform(const st
                                 Ogre::Vector3& position,
                                 Ogre::Quaternion& orientation)
 {
-  if (!adjustTime(frame, time))
-  {
-    return false;
-  }
+  adjustTime(time);
 
   boost::mutex::scoped_lock lock(cache_mutex_);
 
@@ -243,10 +212,7 @@ bool FrameManager::transform(const std::
                              Ogre::Vector3& position,
                              Ogre::Quaternion& orientation)
 {
-  if (!adjustTime(frame, time))
-  {
-    return false;
-  }
+  adjustTime(time);
 
   position = Ogre::Vector3::ZERO;
   orientation = Ogre::Quaternion::IDENTITY;
@@ -261,7 +227,20 @@ bool FrameManager::transform(const std::
   {
     tf2::doTransform(pose, pose, tf_buffer_->lookupTransform(fixed_frame_, frame, time));
   }
-  catch (std::runtime_error& e)
+  catch (const tf2::ExtrapolationException& e)
+  {
+    if (sync_mode_ == SyncApprox)
+      return false;
+    // We don't have tf info for sync_time_. Reset sync_time_ to latest available time of frame
+    auto tf = tf_buffer_->lookupTransform(frame, frame, ros::Time());
+    if (sync_time_ > tf.header.stamp && tf.header.stamp != ros::Time())
+    {
+      sync_delta_ += (sync_time_ - tf.header.stamp).toSec(); // increase sync delta by observed amount
+      sync_time_ = tf.header.stamp;
+    }
+    return false;
+  }
+  catch (const std::runtime_error& e)
   {
     ROS_DEBUG("Error transforming from frame '%s' to frame '%s': %s", frame.c_str(),
               fixed_frame_.c_str(), e.what());
@@ -292,10 +271,7 @@ bool FrameManager::frameHasProblems(cons
 
 bool FrameManager::transformHasProblems(const std::string& frame, ros::Time time, std::string& error)
 {
-  if (!adjustTime(frame, time))
-  {
-    return false;
-  }
+  adjustTime(time);
 
   std::string tf_error;
   bool transform_succeeded = tf_buffer_->canTransform(fixed_frame_, frame, time, &tf_error);
diff -pruN 1.14.14+dfsg-2/src/rviz/frame_manager.h 1.14.15+dfsg-3/src/rviz/frame_manager.h
--- 1.14.14+dfsg-2/src/rviz/frame_manager.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/frame_manager.h	2022-08-01 08:39:42.000000000 +0000
@@ -38,8 +38,8 @@
 #include <tf2_ros/buffer.h>
 #include <geometry_msgs/Pose.h>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 
 #include <boost/thread/mutex.hpp>
 
@@ -67,9 +67,10 @@ class FrameManager : public QObject
 public:
   enum SyncMode
   {
-    SyncOff = 0,
-    SyncExact,
-    SyncApprox
+    SyncOff = 0, // use latest TF updates
+    SyncExact,   // sync to incoming messages of a display (emitting timeSignal())
+    SyncApprox,
+    SyncFrame, // synchronize frame lookups to start of update() loop
   };
 
   /// Constructor, will create a TransformListener (and Buffer) automatically if not provided
@@ -192,9 +193,11 @@ public:
   template <class M>
   void registerFilterForTransformStatusCheck(tf2_ros::MessageFilter<M>* filter, Display* display)
   {
-    filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
-    filter->registerFailureCallback(boost::bind(
-        &FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, this, _1, _2, display));
+    filter->registerCallback(
+        boost::bind(&FrameManager::messageCallback<M>, this, boost::placeholders::_1, display));
+    filter->registerFailureCallback(
+        boost::bind(&FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, this,
+                    boost::placeholders::_1, boost::placeholders::_2, display));
   }
 
   /** @brief Return the current fixed frame name. */
@@ -227,7 +230,7 @@ Q_SIGNALS:
   void fixedFrameChanged();
 
 private:
-  bool adjustTime(const std::string& frame, ros::Time& time);
+  void adjustTime(ros::Time& time);
 
   template <class M>
   void messageCallback(const ros::MessageEvent<M const>& msg_evt, Display* display)
@@ -304,7 +307,6 @@ private:
   std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
   std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
   std::string fixed_frame_;
-  tf2::CompactFrameID fixed_frame_id_;
 
   bool pause_;
 
@@ -314,8 +316,8 @@ private:
   ros::Time sync_time_;
 
   // used for approx. syncing
-  double sync_delta_;
-  double current_delta_;
+  double current_delta_; // current time delay between received sync msg's time stamp and now()
+  double sync_delta_;    // sliding average of current_delta_, used to compute sync_time_
 };
 
 } // namespace rviz
diff -pruN 1.14.14+dfsg-2/src/rviz/frame_position_tracking_view_controller.cpp 1.14.15+dfsg-3/src/rviz/frame_position_tracking_view_controller.cpp
--- 1.14.14+dfsg-2/src/rviz/frame_position_tracking_view_controller.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/frame_position_tracking_view_controller.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,9 +27,9 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreCamera.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/frame_position_tracking_view_controller.h 1.14.15+dfsg-3/src/rviz/frame_position_tracking_view_controller.h
--- 1.14.14+dfsg-2/src/rviz/frame_position_tracking_view_controller.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/frame_position_tracking_view_controller.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,8 +30,8 @@
 #ifndef RVIZ_FRAME_POSITION_TRACKING_VIEW_CONTROLLER_H
 #define RVIZ_FRAME_POSITION_TRACKING_VIEW_CONTROLLER_H
 
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreVector3.h>
+#include <OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <rviz/view_controller.h>
 #include <rviz/rviz_export.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/geometry.cpp 1.14.15+dfsg-3/src/rviz/geometry.cpp
--- 1.14.14+dfsg-2/src/rviz/geometry.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/geometry.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,11 +27,11 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreRay.h>
-#include <OGRE/OgrePlane.h>
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreViewport.h>
+#include <OgreRay.h>
+#include <OgrePlane.h>
+#include <OgreCamera.h>
+#include <OgreSceneNode.h>
+#include <OgreViewport.h>
 
 #include "geometry.h"
 
diff -pruN 1.14.14+dfsg-2/src/rviz/geometry.h 1.14.15+dfsg-3/src/rviz/geometry.h
--- 1.14.14+dfsg-2/src/rviz/geometry.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/geometry.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,7 +30,7 @@
 #ifndef GEOMETRY_H
 #define GEOMETRY_H
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/image/image_display_base.cpp 1.14.15+dfsg-3/src/rviz/image/image_display_base.cpp
--- 1.14.14+dfsg-2/src/rviz/image/image_display_base.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/image/image_display_base.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -70,7 +70,7 @@ ImageDisplayBase::ImageDisplayBase() : D
 
 ImageDisplayBase::~ImageDisplayBase()
 {
-  unsubscribe();
+  ImageDisplayBase::unsubscribe();
 }
 
 void ImageDisplayBase::onInitialize()
@@ -181,15 +181,18 @@ void ImageDisplayBase::subscribe()
 
       if (targetFrame_.empty())
       {
-        sub_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
+        sub_->registerCallback(
+            boost::bind(&ImageDisplayBase::incomingMessage, this, boost::placeholders::_1));
       }
       else
       {
         tf_filter_.reset(new tf2_ros::MessageFilter<sensor_msgs::Image>(
             *sub_, *context_->getTF2BufferPtr(), targetFrame_, queue_size_property_->getInt(),
             update_nh_));
-        tf_filter_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
-        tf_filter_->registerFailureCallback(boost::bind(&ImageDisplayBase::failedMessage, this, _1, _2));
+        tf_filter_->registerCallback(
+            boost::bind(&ImageDisplayBase::incomingMessage, this, boost::placeholders::_1));
+        tf_filter_->registerFailureCallback(boost::bind(
+            &ImageDisplayBase::failedMessage, this, boost::placeholders::_1, boost::placeholders::_2));
       }
     }
     setStatus(StatusProperty::Ok, "Topic", "OK");
diff -pruN 1.14.14+dfsg-2/src/rviz/image/ros_image_texture.cpp 1.14.15+dfsg-3/src/rviz/image/ros_image_texture.cpp
--- 1.14.14+dfsg-2/src/rviz/image/ros_image_texture.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/image/ros_image_texture.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -35,7 +35,7 @@
 #include <boost/algorithm/string/erase.hpp>
 #include <boost/foreach.hpp>
 
-#include <OGRE/OgreTextureManager.h>
+#include <OgreTextureManager.h>
 
 #include <sensor_msgs/image_encodings.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/image/ros_image_texture.h 1.14.15+dfsg-3/src/rviz/image/ros_image_texture.h
--- 1.14.14+dfsg-2/src/rviz/image/ros_image_texture.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/image/ros_image_texture.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,9 +32,9 @@
 
 #include <sensor_msgs/Image.h>
 
-#include <OGRE/OgreTexture.h>
-#include <OGRE/OgreImage.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreTexture.h>
+#include <OgreImage.h>
+#include <OgreSharedPtr.h>
 
 #include <boost/shared_ptr.hpp>
 #include <boost/thread/mutex.hpp>
diff -pruN 1.14.14+dfsg-2/src/rviz/mesh_loader.cpp 1.14.15+dfsg-3/src/rviz/mesh_loader.cpp
--- 1.14.14+dfsg-2/src/rviz/mesh_loader.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/mesh_loader.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -28,28 +28,28 @@
  */
 
 #include "mesh_loader.h"
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 #include <resource_retriever/retriever.h>
 
 #include <boost/filesystem.hpp>
 #include <boost/algorithm/string.hpp>
 
-#include <OGRE/OgreSkeleton.h>
-#include <OGRE/OgreSkeletonManager.h>
-#include <OGRE/OgreSkeletonSerializer.h>
-#include <OGRE/OgreMeshManager.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTexture.h>
-#include <OGRE/OgrePass.h>
-#include <OGRE/OgreTechnique.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreTextureUnitState.h>
-#include <OGRE/OgreMeshSerializer.h>
-#include <OGRE/OgreSubMesh.h>
-#include <OGRE/OgreHardwareBufferManager.h>
-#include <OGRE/OgreSharedPtr.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreSkeleton.h>
+#include <OgreSkeletonManager.h>
+#include <OgreSkeletonSerializer.h>
+#include <OgreMeshManager.h>
+#include <OgreTextureManager.h>
+#include <OgreMaterialManager.h>
+#include <OgreTexture.h>
+#include <OgrePass.h>
+#include <OgreTechnique.h>
+#include <OgreMaterial.h>
+#include <OgreTextureUnitState.h>
+#include <OgreMeshSerializer.h>
+#include <OgreSubMesh.h>
+#include <OgreHardwareBufferManager.h>
+#include <OgreSharedPtr.h>
+#include <OgreTechnique.h>
 
 #include <tinyxml2.h>
 
@@ -271,7 +271,7 @@ void buildMesh(const aiScene* scene,
     if (input_mesh->HasTextureCoords(0))
     {
       vertex_decl->addElement(0, offset, Ogre::VET_FLOAT2, Ogre::VES_TEXTURE_COORDINATES, 0);
-      offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT2);
+      // offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT2);
     }
 
     // todo vertex colors
@@ -700,8 +700,7 @@ Ogre::SkeletonPtr loadSkeletonFromResour
     Ogre::SkeletonSerializer ser;
     Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
     Ogre::SkeletonPtr skeleton = Ogre::SkeletonManager::getSingleton().create(
-        skeleton_path.filename().string().c_str(),
-        Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, true);
+        skeleton_path.filename().string(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, true);
     ser.importSkeleton(stream, skeleton.get());
 
     return skeleton;
diff -pruN 1.14.14+dfsg-2/src/rviz/mesh_loader.h 1.14.15+dfsg-3/src/rviz/mesh_loader.h
--- 1.14.14+dfsg-2/src/rviz/mesh_loader.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/mesh_loader.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,8 +30,8 @@
 #ifndef RVIZ_MESH_LOADER_H
 #define RVIZ_MESH_LOADER_H
 
-#include <OGRE/OgreMesh.h>
-#include <OGRE/OgreSkeleton.h>
+#include <OgreMesh.h>
+#include <OgreSkeleton.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/message_filter_display.h 1.14.15+dfsg-3/src/rviz/message_filter_display.h
--- 1.14.14+dfsg-2/src/rviz/message_filter_display.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/message_filter_display.h	2022-08-01 08:39:42.000000000 +0000
@@ -111,7 +111,7 @@ public:
 
     tf_filter_->connectInput(sub_);
     tf_filter_->registerCallback(
-        boost::bind(&MessageFilterDisplay<MessageType>::incomingMessage, this, _1));
+        boost::bind(&MessageFilterDisplay<MessageType>::incomingMessage, this, boost::placeholders::_1));
     context_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
   }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/msg_conversions.h 1.14.15+dfsg-3/src/rviz/msg_conversions.h
--- 1.14.14+dfsg-2/src/rviz/msg_conversions.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/msg_conversions.h	2022-08-01 08:39:42.000000000 +0000
@@ -29,8 +29,8 @@
 #ifndef MSG_CONVERSIONS_H
 #define MSG_CONVERSIONS_H
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 
 #include <geometry_msgs/Point.h>
 #include <geometry_msgs/Vector3.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/apply_visibility_bits.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/apply_visibility_bits.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/apply_visibility_bits.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/apply_visibility_bits.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,8 +29,8 @@
 
 #include <stdint.h>
 
-#include <OGRE/OgreMovableObject.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreMovableObject.h>
+#include <OgreSceneNode.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/arrow.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/arrow.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/arrow.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/arrow.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -30,10 +30,10 @@
 #include "arrow.h"
 #include "shape.h"
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 
 #include <sstream>
 
@@ -60,7 +60,7 @@ Arrow::Arrow(Ogre::SceneManager* scene_m
 
   set(shaft_length, shaft_diameter, head_length, head_diameter);
 
-  setOrientation(Ogre::Quaternion::IDENTITY);
+  Arrow::setOrientation(Ogre::Quaternion::IDENTITY);
 }
 
 Arrow::~Arrow()
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/arrow.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/arrow.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/arrow.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/arrow.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,7 +32,7 @@
 #ifndef OGRE_TOOLS_ARROW_H
 #define OGRE_TOOLS_ARROW_H
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/axes.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/axes.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/axes.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/axes.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -30,10 +30,10 @@
 #include "axes.h"
 #include "shape.h"
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 
 #include <sstream>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/axes.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/axes.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/axes.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/axes.h	2022-08-01 08:39:42.000000000 +0000
@@ -38,8 +38,8 @@
 
 #include <vector>
 
-#include <OGRE/OgrePrerequisites.h>
-#include <OGRE/OgreColourValue.h>
+#include <OgrePrerequisites.h>
+#include <OgreColourValue.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/billboard_line.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/billboard_line.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/billboard_line.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/billboard_line.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,13 +29,13 @@
 
 #include "billboard_line.h"
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreBillboardChain.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreBillboardChain.h>
+#include <OgreMaterialManager.h>
+#include <OgreTechnique.h>
 
 #include <sstream>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/billboard_line.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/billboard_line.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/billboard_line.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/billboard_line.h	2022-08-01 08:39:42.000000000 +0000
@@ -35,10 +35,10 @@
 #include <stdint.h>
 
 #include <vector>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreColourValue.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreColourValue.h>
+#include <OgreMaterial.h>
+#include <OgreSharedPtr.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/camera_base.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/camera_base.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/camera_base.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/camera_base.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,11 +29,11 @@
 
 #include "camera_base.h"
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <OgreCamera.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 
 #include <stdint.h>
 #include <sstream>
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/camera_base.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/camera_base.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/camera_base.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/camera_base.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,8 +30,8 @@
 #ifndef OGRE_TOOLS_CAMERA_BASE_H_
 #define OGRE_TOOLS_CAMERA_BASE_H_
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/compatibility.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/compatibility.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/compatibility.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/compatibility.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,13 +32,13 @@
 #define OGRE_HELPERS_COMPATIBILITY_H
 
 #include <rviz/ogre_helpers/version_check.h>
-#include <OGRE/OgreSimpleRenderable.h>
+#include <OgreSimpleRenderable.h>
+#include <OgreSceneNode.h>
 
-#if OGRE_VERSION < OGRE_VERSION_CHECK(1, 10, 0)
-#include <OGRE/OgreSceneManager.h>
+#if OGRE_VERSION < OGRE_VERSION_CHECK(1, 10, 8)
+#include <OgreSceneManager.h>
 #else
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreMaterialManager.h>
 #endif
 
 #include <string>
@@ -48,14 +48,14 @@ namespace rviz
 /* This header provides helper functions to maintain compatibility with Ogre versions 1.9 ... 1.12+.
  *
  * setMaterial() allows setting the material of a renderable by either name or MaterialPtr.
- * OGRE 1.10 added:   renderable.setMaterial(const Ogre::MaterialPtr &)
+ * OGRE 1.10.8 added: renderable.setMaterial(const Ogre::MaterialPtr &)
  * OGRE 1.11 removed: renderable.setMaterial(const std::string       &)
  *
  * removeAndDestroyChildNode(parent, child) allows removal of a SceneNode*.
- * OGRE 1.10 added: SceneNode::removeAndDestroyChild(SceneNode* child)
+ * OGRE 1.10.8 added: SceneNode::removeAndDestroyChild(SceneNode* child)
  */
 
-#if OGRE_VERSION < OGRE_VERSION_CHECK(1, 10, 0)
+#if OGRE_VERSION < OGRE_VERSION_CHECK(1, 10, 8)
 inline void setMaterial(Ogre::SimpleRenderable& renderable, const std::string& material_name)
 {
   renderable.setMaterial(material_name);
@@ -85,7 +85,7 @@ inline void setMaterial(Ogre::SimpleRend
 }
 #endif
 
-#if OGRE_VERSION < OGRE_VERSION_CHECK(1, 10, 0)
+#if OGRE_VERSION < OGRE_VERSION_CHECK(1, 10, 8)
 inline void removeAndDestroyChildNode(Ogre::SceneNode* parent, Ogre::SceneNode* child)
 {
   child->removeAndDestroyAllChildren();
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/grid.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/grid.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/grid.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/grid.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -30,13 +30,13 @@
 #include "grid.h"
 #include "billboard_line.h"
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreManualObject.h>
+#include <OgreMaterialManager.h>
+#include <OgreTechnique.h>
 
 #include <sstream>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/grid.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/grid.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/grid.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/grid.h	2022-08-01 08:39:42.000000000 +0000
@@ -34,9 +34,9 @@
 
 #include <vector>
 
-#include <OGRE/OgreColourValue.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreColourValue.h>
+#include <OgreMaterial.h>
+#include <OgreSharedPtr.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/initialization.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/initialization.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/initialization.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/initialization.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -1,7 +1,7 @@
 #include "initialization.h"
 
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreRenderSystem.h>
+#include <OgreRoot.h>
+#include <OgreRenderSystem.h>
 
 #include <exception>
 #include <stdexcept>
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/line.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/line.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/line.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/line.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,11 +31,11 @@
 
 #include <sstream>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreManualObject.h>
+#include <OgreMaterialManager.h>
+#include <OgreTechnique.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/line.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/line.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/line.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/line.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,9 +32,9 @@
 
 #include "object.h"
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreSceneNode.h>
+#include <OgreMaterial.h>
+#include <OgreSharedPtr.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/mesh_shape.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/mesh_shape.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/mesh_shape.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/mesh_shape.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,13 +29,13 @@
 
 #include "mesh_shape.h"
 
-#include <OGRE/OgreMesh.h>
-#include <OGRE/OgreMeshManager.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreManualObject.h>
+#include <OgreMesh.h>
+#include <OgreMeshManager.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreEntity.h>
+#include <OgreMaterialManager.h>
+#include <OgreManualObject.h>
 
 #include <ros/console.h>
 #include <boost/lexical_cast.hpp>
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/movable_text.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/movable_text.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/movable_text.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/movable_text.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -42,20 +42,16 @@
 #include "movable_text.h"
 #include <rviz/ogre_helpers/version_check.h>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreHardwareBufferManager.h>
-#include <OGRE/Overlay/OgreFontManager.h>
-#include <OGRE/Overlay/OgreFont.h>
-#if OGRE_VERSION < OGRE_VERSION_CHECK(1, 12, 0)
-#include <OGRE/OgreUTFString.h>
-#else
-#include <OGRE/Overlay/OgreUTFString.h>
-#endif
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreRoot.h>
+#include <OgreCamera.h>
+#include <OgreSceneNode.h>
+#include <OgreMaterialManager.h>
+#include <OgreHardwareBufferManager.h>
+#include <Overlay/OgreFontManager.h>
+#include <Overlay/OgreFont.h>
+#include <OgreUTFString.h>
 
 #include <sstream>
 
@@ -466,6 +462,7 @@ void MovableText::_updateColors()
 {
   assert(mpFont);
   assert(!mpMaterial.isNull());
+  assert(mRenderOp.vertexData);
 
   // Convert to system-specific
   RGBA color;
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/movable_text.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/movable_text.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/movable_text.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/movable_text.h	2022-08-01 08:39:42.000000000 +0000
@@ -43,10 +43,9 @@
 #define OGRE_TOOLS_MOVABLE_TEXT_H
 
 #include <rviz/ogre_helpers/version_check.h>
-#include <OGRE/OgrePrerequisites.h>
-#include <OGRE/OgreMovableObject.h>
-#include <OGRE/OgreRenderable.h>
-#include <rviz/ogre_helpers/version_check.h>
+#include <OgrePrerequisites.h>
+#include <OgreMovableObject.h>
+#include <OgreRenderable.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/object.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/object.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/object.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/object.h	2022-08-01 08:39:42.000000000 +0000
@@ -31,7 +31,7 @@
 #define OGRE_TOOLS_OBJECT_H
 
 #include <rviz/rviz_export.h>
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/ogre_logging.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/ogre_logging.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/ogre_logging.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/ogre_logging.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -27,8 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <OGRE/OgreLogManager.h>
-#include <OGRE/OgreLog.h>
+#include <OgreLogManager.h>
+#include <OgreLog.h>
 
 #include <ros/ros.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/ogre_render_queue_clearer.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/ogre_render_queue_clearer.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/ogre_render_queue_clearer.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/ogre_render_queue_clearer.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,8 +29,8 @@
 
 #include "ogre_render_queue_clearer.h"
 
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgrePass.h>
+#include <OgreRoot.h>
+#include <OgrePass.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/ogre_render_queue_clearer.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/ogre_render_queue_clearer.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/ogre_render_queue_clearer.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/ogre_render_queue_clearer.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,7 +30,7 @@
 #ifndef OGRERENDERQUEUECLEARER_H_
 #define OGRERENDERQUEUECLEARER_H_
 
-#include <OGRE/OgreFrameListener.h>
+#include <OgreFrameListener.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/ogre_vector.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/ogre_vector.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/ogre_vector.h	1970-01-01 00:00:00.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/ogre_vector.h	2022-08-01 08:39:42.000000000 +0000
@@ -0,0 +1,8 @@
+// OgrePrerequisites.h is needed for version_check to work
+#include <OgrePrerequisites.h>
+#include <rviz/ogre_helpers/version_check.h>
+#if OGRE_VERSION < OGRE_VERSION_CHECK(1, 12, 0)
+#include <OgreVector3.h>
+#else
+#include <OgreVector.h>
+#endif
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/orbit_camera.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/orbit_camera.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/orbit_camera.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/orbit_camera.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -30,12 +30,12 @@
 #include "orbit_camera.h"
 #include "shape.h"
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreViewport.h>
 
 #include <cmath>
 #include <stdint.h>
@@ -63,7 +63,7 @@ OrbitCamera::OrbitCamera(Ogre::SceneMana
   focal_point_object_->setColor(1.0f, 1.0f, 0.0f, 0.5f);
   focal_point_object_->getRootNode()->setVisible(false);
 
-  update();
+  OrbitCamera::update();
 }
 
 OrbitCamera::~OrbitCamera()
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/orbit_camera.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/orbit_camera.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/orbit_camera.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/orbit_camera.h	2022-08-01 08:39:42.000000000 +0000
@@ -31,7 +31,7 @@
 #define OGRE_TOOLS_ORBIT_CAMERA_H_
 
 #include "camera_base.h"
-#include <OGRE/OgreVector3.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/orthographic.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/orthographic.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/orthographic.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/orthographic.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,7 +29,7 @@
 
 #include "orthographic.h"
 
-#include <OGRE/OgreMatrix4.h>
+#include <OgreMatrix4.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/point_cloud.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/point_cloud.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/point_cloud.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/point_cloud.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,19 +31,18 @@
 #include <ros/assert.h>
 #include <qglobal.h>
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreBillboardSet.h>
-#include <OGRE/OgreBillboard.h>
-#include <OGRE/OgreTexture.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreSharedPtr.h>
-#include <OGRE/OgreTechnique.h>
-#include <OGRE/OgreCamera.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreManualObject.h>
+#include <OgreMaterialManager.h>
+#include <OgreBillboard.h>
+#include <OgreTexture.h>
+#include <OgreTextureManager.h>
+#include <OgreSharedPtr.h>
+#include <OgreTechnique.h>
+#include <OgreCamera.h>
 
 #include <sstream>
 
@@ -446,29 +445,22 @@ void PointCloud::addPoints(Point* points
   }
   else
   {
-    if (render_mode_ == RM_POINTS)
+    switch (render_mode_)
     {
+    case RM_POINTS:
       vertices = g_point_vertices;
-    }
-    else if (render_mode_ == RM_SQUARES)
-    {
+      break;
+    case RM_SQUARES:
+    case RM_FLAT_SQUARES:
+    case RM_TILES:
       vertices = g_billboard_vertices;
-    }
-    else if (render_mode_ == RM_FLAT_SQUARES)
-    {
-      vertices = g_billboard_vertices;
-    }
-    else if (render_mode_ == RM_SPHERES)
-    {
+      break;
+    case RM_SPHERES:
       vertices = g_billboard_sphere_vertices;
-    }
-    else if (render_mode_ == RM_TILES)
-    {
-      vertices = g_billboard_vertices;
-    }
-    else if (render_mode_ == RM_BOXES)
-    {
+      break;
+    case RM_BOXES:
       vertices = g_box_vertices;
+      break;
     }
   }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/point_cloud.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/point_cloud.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/point_cloud.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/point_cloud.h	2022-08-01 08:39:42.000000000 +0000
@@ -30,16 +30,16 @@
 #ifndef OGRE_TOOLS_OGRE_POINT_CLOUD_H
 #define OGRE_TOOLS_OGRE_POINT_CLOUD_H
 
-#include <OGRE/OgreSimpleRenderable.h>
-#include <OGRE/OgreMovableObject.h>
-#include <OGRE/OgreString.h>
-#include <OGRE/OgreAxisAlignedBox.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreColourValue.h>
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreHardwareBufferManager.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreSimpleRenderable.h>
+#include <OgreMovableObject.h>
+#include <OgreString.h>
+#include <OgreAxisAlignedBox.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreMaterial.h>
+#include <OgreColourValue.h>
+#include <OgreRoot.h>
+#include <OgreHardwareBufferManager.h>
+#include <OgreSharedPtr.h>
 
 #include <stdint.h>
 
@@ -96,9 +96,9 @@ typedef std::vector<PointCloudRenderable
  * \class PointCloud
  * \brief A visual representation of a set of points.
  *
- * Displays a set of points using any number of Ogre BillboardSets.  PointCloud is optimized for sets of
- * points that change
- * rapidly, rather than for large clouds that never change.
+ * Displays a set of points using vertex and geometry shaders.
+ * PointCloud is optimized for sets of points that change rapidly,
+ * rather than for large clouds that never change.
  *
  * Most of the functions in PointCloud are not safe to call from any thread but the render thread.
  * Exceptions are clear() and addPoints(), which
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/qt_ogre_render_window.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/qt_ogre_render_window.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/qt_ogre_render_window.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/qt_ogre_render_window.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,13 +31,13 @@
 #include "render_system.h"
 #include <rviz/ogre_helpers/version_check.h>
 
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreRenderWindow.h>
-#include <OGRE/OgreStringConverter.h>
-#include <OGRE/OgreGpuProgramManager.h>
-#include <OGRE/OgreRenderTargetListener.h>
+#include <OgreRoot.h>
+#include <OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgreRenderWindow.h>
+#include <OgreStringConverter.h>
+#include <OgreGpuProgramManager.h>
+#include <OgreRenderTargetListener.h>
 
 #include <ros/console.h>
 #include <ros/assert.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/qt_ogre_render_window.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/qt_ogre_render_window.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/qt_ogre_render_window.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/qt_ogre_render_window.h	2022-08-01 08:39:42.000000000 +0000
@@ -33,8 +33,8 @@
 
 #include "render_widget.h"
 
-#include <OGRE/OgreColourValue.h>
-#include <OGRE/OgreRenderTargetListener.h>
+#include <OgreColourValue.h>
+#include <OgreRenderTargetListener.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/render_system.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/render_system.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/render_system.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/render_system.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -55,9 +55,9 @@
 #include <ros/console.h>
 
 #include <rviz/ogre_helpers/version_check.h>
-#include <OGRE/OgreRenderWindow.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/Overlay/OgreOverlaySystem.h>
+#include <OgreRenderWindow.h>
+#include <OgreSceneManager.h>
+#include <Overlay/OgreOverlaySystem.h>
 
 #include <rviz/env_config.h>
 #include <rviz/ogre_helpers/ogre_logging.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/render_system.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/render_system.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/render_system.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/render_system.h	2022-08-01 08:39:42.000000000 +0000
@@ -29,7 +29,7 @@
 #ifndef RENDER_SYSTEM_H
 #define RENDER_SYSTEM_H
 
-#include <OGRE/OgreRoot.h>
+#include <OgreRoot.h>
 #include <stdint.h>
 
 #include <rviz/rviz_export.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/render_widget.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/render_widget.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/render_widget.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/render_widget.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,7 +31,7 @@
 #include <rviz/ogre_helpers/render_system.h>
 #include <rviz/ogre_helpers/version_check.h>
 
-#include <OGRE/OgreRenderWindow.h>
+#include <OgreRenderWindow.h>
 
 #include <QtGlobal>
 #include <QApplication>
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/shape.cpp 1.14.15+dfsg-3/src/rviz/ogre_helpers/shape.cpp
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/shape.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/shape.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,14 +31,14 @@
 #include <ros/assert.h>
 
 #include <rviz/ogre_helpers/version_check.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreEntity.h>
+#include <OgreMaterialManager.h>
+#include <OgreTextureManager.h>
+#include <OgreTechnique.h>
 #include <stdint.h>
 
 namespace rviz
diff -pruN 1.14.14+dfsg-2/src/rviz/ogre_helpers/shape.h 1.14.15+dfsg-3/src/rviz/ogre_helpers/shape.h
--- 1.14.14+dfsg-2/src/rviz/ogre_helpers/shape.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/ogre_helpers/shape.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,9 +32,9 @@
 
 #include "object.h"
 
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreMaterial.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreSharedPtr.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/pluginlib_factory.h 1.14.15+dfsg-3/src/rviz/pluginlib_factory.h
--- 1.14.14+dfsg-2/src/rviz/pluginlib_factory.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/pluginlib_factory.h	2022-08-01 08:39:42.000000000 +0000
@@ -43,6 +43,8 @@
 #include <rviz/class_id_recording_factory.h>
 #include <rviz/load_resource.h>
 
+#include <ros/console.h>
+
 namespace rviz
 {
 template <class Type>
diff -pruN 1.14.14+dfsg-2/src/rviz/properties/display_visibility_property.cpp 1.14.15+dfsg-3/src/rviz/properties/display_visibility_property.cpp
--- 1.14.14+dfsg-2/src/rviz/properties/display_visibility_property.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/properties/display_visibility_property.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -50,7 +50,7 @@ DisplayVisibilityProperty::DisplayVisibi
   , display_(display)
 {
   custom_name_ = (name.size() != 0);
-  update();
+  DisplayVisibilityProperty::update();
 }
 
 DisplayVisibilityProperty::~DisplayVisibilityProperty()
diff -pruN 1.14.14+dfsg-2/src/rviz/properties/parse_color.h 1.14.15+dfsg-3/src/rviz/properties/parse_color.h
--- 1.14.14+dfsg-2/src/rviz/properties/parse_color.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/properties/parse_color.h	2022-08-01 08:39:42.000000000 +0000
@@ -32,7 +32,7 @@
 #include <QColor>
 #include <QString>
 
-#include <OGRE/OgreColourValue.h>
+#include <OgreColourValue.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/properties/property.cpp 1.14.15+dfsg-3/src/rviz/properties/property.cpp
--- 1.14.14+dfsg-2/src/rviz/properties/property.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/properties/property.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -70,7 +70,7 @@ Property::Property(const QString& name,
   , is_read_only_(false)
   , save_(true)
 {
-  setName(name);
+  Property::setName(name);
   if (parent)
   {
     parent->addChild(this);
diff -pruN 1.14.14+dfsg-2/src/rviz/properties/quaternion_property.h 1.14.15+dfsg-3/src/rviz/properties/quaternion_property.h
--- 1.14.14+dfsg-2/src/rviz/properties/quaternion_property.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/properties/quaternion_property.h	2022-08-01 08:39:42.000000000 +0000
@@ -29,7 +29,7 @@
 #ifndef QUATERNION_PROPERTY_H
 #define QUATERNION_PROPERTY_H
 
-#include <OGRE/OgreQuaternion.h>
+#include <OgreQuaternion.h>
 
 #include <rviz/properties/property.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/properties/splitter_handle.cpp 1.14.15+dfsg-3/src/rviz/properties/splitter_handle.cpp
--- 1.14.14+dfsg-2/src/rviz/properties/splitter_handle.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/properties/splitter_handle.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -49,9 +49,7 @@ SplitterHandle::SplitterHandle(QTreeView
 
 bool SplitterHandle::eventFilter(QObject* event_target, QEvent* event)
 {
-  if (event_target == parent_ &&
-      (event->type() == QEvent::Resize || event->type() == QEvent::LayoutRequest ||
-       event->type() == QEvent::Show))
+  if (event_target == parent_ && event->type() == QEvent::Resize)
   {
     updateGeometry();
   }
@@ -61,13 +59,14 @@ bool SplitterHandle::eventFilter(QObject
 void SplitterHandle::updateGeometry()
 {
   int w = 7;
-  int new_column_width = int(first_column_size_ratio_ * parent_->contentsRect().width());
-  parent_->setColumnWidth(0, new_column_width);
-  parent_->setColumnWidth(1, parent_->viewport()->contentsRect().width() - new_column_width);
-
-  int new_x = new_column_width - w / 2 + parent_->columnViewportPosition(0);
-  if (new_x != x() || parent_->height() != height())
-    setGeometry(new_x, 0, w, parent_->height());
+  const auto& content = parent_->contentsRect();
+  int new_column_width = int(first_column_size_ratio_ * content.width());
+  parent_->header()->resizeSection(0, new_column_width); // fixed size for name column
+  parent_->header()->resizeSection(1, content.width() - new_column_width);
+
+  int new_x = content.x() + new_column_width - w / 2;
+  if (new_x != x() || content.height() != height())
+    setGeometry(new_x, content.y(), w, content.height());
 }
 
 void SplitterHandle::setRatio(float ratio)
@@ -81,49 +80,60 @@ float SplitterHandle::getRatio()
   return first_column_size_ratio_;
 }
 
+void SplitterHandle::setDesiredWidth(int width)
+{
+  const auto& content = parent_->contentsRect();
+  int new_column_width = qBound(parent_->header()->minimumSectionSize(), // minimum
+                                width,                                   // desired
+                                content.width());                        // maximum
+
+  if (new_column_width != parent_->header()->sectionSize(0))
+  {
+    first_column_size_ratio_ = new_column_width / (float)content.width();
+    updateGeometry();
+  }
+}
+
 void SplitterHandle::mousePressEvent(QMouseEvent* event)
 {
   if (event->button() == Qt::LeftButton)
   {
-    // position of mouse press inside this QWidget
-    x_press_offset_ = event->x();
+    // position of mouse press relative to splitter line / the center of the widget
+    x_press_offset_ = event->x() - width() / 2;
   }
 }
 
 void SplitterHandle::mouseMoveEvent(QMouseEvent* event)
 {
-  int padding = 55;
-
   if (event->buttons() & Qt::LeftButton)
   {
     QPoint pos_rel_parent = parent_->mapFromGlobal(event->globalPos());
-
-    int new_x = pos_rel_parent.x() - x_press_offset_ - parent_->columnViewportPosition(0);
-
-    if (new_x > parent_->width() - width() - padding)
-    {
-      new_x = parent_->width() - width() - padding;
-    }
-
-    if (new_x < padding)
-    {
-      new_x = padding;
-    }
-
-    if (new_x != x())
-    {
-      int new_column_width = new_x + width() / 2 - parent_->contentsRect().x();
-      first_column_size_ratio_ = new_column_width / (float)parent_->contentsRect().width();
-      updateGeometry();
-    }
+    setDesiredWidth(pos_rel_parent.x() - parent_->contentsRect().x() - x_press_offset_);
   }
 }
 
+// adjust splitter position to optimally fit content
+void SplitterHandle::mouseDoubleClickEvent(QMouseEvent* /*event*/)
+{
+  int available_width = parent_->contentsRect().width();
+  int default_width = 0.5f * available_width;
+  // missing width to default
+  int col0 = static_cast<QAbstractItemView*>(parent_)->sizeHintForColumn(0) - default_width;
+  int col1 = static_cast<QAbstractItemView*>(parent_)->sizeHintForColumn(1) - default_width;
+
+  if (col0 <= 0 && col1 <= 0) // each column fits
+    setDesiredWidth(default_width);
+  else if (col0 + col1 <= 0) // both columns fit together, but require a non-default splitting
+    setDesiredWidth(default_width + col0 + 0.5f * std::abs(col0 + col1)); // uniformly split extra space
+  else
+    setDesiredWidth(default_width + col0 - 0.5f * (col0 + col1)); // uniformly cut missing space
+}
+
 void SplitterHandle::paintEvent(QPaintEvent* /*event*/)
 {
   QPainter painter(this);
   painter.setPen(color_);
-  painter.drawLine(1 + width() / 2, 0, 1 + width() / 2, height());
+  painter.drawLine(width() / 2, 0, width() / 2, height());
 }
 
 } // end namespace rviz
diff -pruN 1.14.14+dfsg-2/src/rviz/properties/splitter_handle.h 1.14.15+dfsg-3/src/rviz/properties/splitter_handle.h
--- 1.14.14+dfsg-2/src/rviz/properties/splitter_handle.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/properties/splitter_handle.h	2022-08-01 08:39:42.000000000 +0000
@@ -53,6 +53,9 @@ public:
   /** @brief Get the ratio of the parent's left column to the parent widget width. */
   float getRatio();
 
+  /** @brief Set desired width of first column - subject to clamping */
+  void setDesiredWidth(int width);
+
   /** @brief Catch resize events sent to parent to update splitter's
    * geometry.  Always returns false. */
   bool eventFilter(QObject* event_target, QEvent* event) override;
@@ -70,6 +73,7 @@ public:
 protected:
   void mousePressEvent(QMouseEvent* event) override;
   void mouseMoveEvent(QMouseEvent* event) override;
+  void mouseDoubleClickEvent(QMouseEvent* event) override;
   void paintEvent(QPaintEvent* event) override;
 
 private:
diff -pruN 1.14.14+dfsg-2/src/rviz/properties/status_list.cpp 1.14.15+dfsg-3/src/rviz/properties/status_list.cpp
--- 1.14.14+dfsg-2/src/rviz/properties/status_list.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/properties/status_list.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -37,7 +37,7 @@ namespace rviz
 {
 StatusList::StatusList(const QString& name, Property* parent) : StatusProperty("", "", Ok, parent)
 {
-  setName(name);
+  StatusList::setName(name);
   setShouldBeSaved(false);
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/properties/vector_property.h 1.14.15+dfsg-3/src/rviz/properties/vector_property.h
--- 1.14.14+dfsg-2/src/rviz/properties/vector_property.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/properties/vector_property.h	2022-08-01 08:39:42.000000000 +0000
@@ -29,7 +29,7 @@
 #ifndef VECTOR_PROPERTY_H
 #define VECTOR_PROPERTY_H
 
-#include <OGRE/OgreVector3.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
 
 #include <rviz/properties/property.h>
 #include <rviz/rviz_export.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/render_panel.cpp 1.14.15+dfsg-3/src/rviz/render_panel.cpp
--- 1.14.14+dfsg-2/src/rviz/render_panel.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/render_panel.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -33,8 +33,8 @@
 #include <utility>
 
 
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreCamera.h>
+#include <OgreSceneManager.h>
+#include <OgreCamera.h>
 
 #include <rviz/display.h>
 #include <rviz/view_controller.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/render_panel.h 1.14.15+dfsg-3/src/rviz/render_panel.h
--- 1.14.14+dfsg-2/src/rviz/render_panel.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/render_panel.h	2022-08-01 08:39:42.000000000 +0000
@@ -33,7 +33,7 @@
 #include "ogre_helpers/qt_ogre_render_window.h"
 
 #ifndef Q_MOC_RUN
-#include <OGRE/OgreSceneManager.h>
+#include <OgreSceneManager.h>
 
 #include <boost/thread/mutex.hpp>
 #endif
diff -pruN 1.14.14+dfsg-2/src/rviz/robot/link_updater.h 1.14.15+dfsg-3/src/rviz/robot/link_updater.h
--- 1.14.14+dfsg-2/src/rviz/robot/link_updater.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/robot/link_updater.h	2022-08-01 08:39:42.000000000 +0000
@@ -33,7 +33,7 @@
 #include <string>
 #include <rviz/properties/status_property.h>
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/robot/robot.cpp 1.14.15+dfsg-3/src/rviz/robot/robot.cpp
--- 1.14.14+dfsg-2/src/rviz/robot/robot.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/robot/robot.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -41,12 +41,12 @@
 
 #include <urdf_model/model.h>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreResourceGroupManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreEntity.h>
+#include <OgreMaterialManager.h>
+#include <OgreMaterial.h>
+#include <OgreResourceGroupManager.h>
 
 #include <ros/console.h>
 #include <ros/assert.h>
@@ -99,7 +99,7 @@ Robot::Robot(Ogre::SceneNode* root_node,
 
 Robot::~Robot()
 {
-  clear();
+  Robot::clear();
 
   scene_manager_->destroySceneNode(root_visual_node_);
   scene_manager_->destroySceneNode(root_collision_node_);
@@ -666,7 +666,6 @@ void Robot::calculateJointCheckboxes()
     links_with_geom_checked += checked ? 1 : 0;
     links_with_geom_unchecked += checked ? 0 : 1;
   }
-  int links_with_geom = links_with_geom_checked + links_with_geom_unchecked;
 
   // check all child links and joints recursively
   std::vector<std::string>::const_iterator child_joint_it = link->getChildJointNames().begin();
@@ -685,7 +684,7 @@ void Robot::calculateJointCheckboxes()
       links_with_geom_unchecked += child_links_with_geom_unchecked;
     }
   }
-  links_with_geom = links_with_geom_checked + links_with_geom_unchecked;
+  int links_with_geom = links_with_geom_checked + links_with_geom_unchecked;
 
   if (!links_with_geom)
   {
@@ -705,13 +704,13 @@ void Robot::update(const LinkUpdater& up
   {
     RobotLink* link = link_it->second;
 
-    link->setToNormalMaterial();
-
     Ogre::Vector3 visual_position, collision_position;
     Ogre::Quaternion visual_orientation, collision_orientation;
     if (updater.getLinkTransforms(link->getName(), visual_position, visual_orientation,
                                   collision_position, collision_orientation))
     {
+      link->setToNormalMaterial();
+
       // Check if visual_orientation, visual_position, collision_orientation, and collision_position are
       // NaN.
       if (visual_orientation.isNaN())
diff -pruN 1.14.14+dfsg-2/src/rviz/robot/robot.h 1.14.15+dfsg-3/src/rviz/robot/robot.h
--- 1.14.14+dfsg-2/src/rviz/robot/robot.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/robot/robot.h	2022-08-01 08:39:42.000000000 +0000
@@ -35,13 +35,13 @@
 #include <string>
 #include <map>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreAny.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreAny.h>
 
 #include <urdf/model.h> // can be replaced later by urdf_model/types.h
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/robot/robot_joint.cpp 1.14.15+dfsg-3/src/rviz/robot/robot_joint.cpp
--- 1.14.14+dfsg-2/src/rviz/robot/robot_joint.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/robot/robot_joint.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,7 +31,7 @@
 #include <rviz/robot/robot_link.h>
 #include <rviz/robot/robot.h>
 
-#include <OGRE/OgreSceneNode.h>
+#include <OgreSceneNode.h>
 
 #include <rviz/properties/float_property.h>
 #include <rviz/properties/vector_property.h>
@@ -210,7 +210,8 @@ void RobotJoint::calculateJointCheckboxe
   links_with_geom_unchecked = 0;
 
   RobotLink* link = robot_->getLink(child_link_name_);
-  if (link && link->hasGeometry())
+  assert(link);
+  if (link->hasGeometry())
   {
     bool checked = link->getLinkProperty()->getValue().toBool();
     links_with_geom_checked += checked ? 1 : 0;
@@ -230,11 +231,9 @@ void RobotJoint::calculateJointCheckboxe
     }
   }
 
-  std::vector<std::string>::const_iterator child_joint_it = link->getChildJointNames().begin();
-  std::vector<std::string>::const_iterator child_joint_end = link->getChildJointNames().end();
-  for (; child_joint_it != child_joint_end; ++child_joint_it)
+  for (const std::string& child_joint_name : link->getChildJointNames())
   {
-    RobotJoint* child_joint = robot_->getJoint(*child_joint_it);
+    RobotJoint* child_joint = robot_->getJoint(child_joint_name);
     if (child_joint)
     {
       int child_links_with_geom;
@@ -271,7 +270,8 @@ void RobotJoint::getChildLinkState(int&
   links_with_geom_unchecked = 0;
 
   RobotLink* link = robot_->getLink(child_link_name_);
-  if (link && link->hasGeometry())
+  assert(link);
+  if (link->hasGeometry())
   {
     bool checked = link->getLinkProperty()->getValue().toBool();
     links_with_geom_checked += checked ? 1 : 0;
diff -pruN 1.14.14+dfsg-2/src/rviz/robot/robot_joint.h 1.14.15+dfsg-3/src/rviz/robot/robot_joint.h
--- 1.14.14+dfsg-2/src/rviz/robot/robot_joint.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/robot/robot_joint.h	2022-08-01 08:39:42.000000000 +0000
@@ -36,10 +36,10 @@
 #include <QObject>
 
 #ifndef Q_MOC_RUN
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreAny.h>
-#include <OGRE/OgreMaterial.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreAny.h>
+#include <OgreMaterial.h>
 #endif
 
 #include <urdf/model.h>
@@ -48,7 +48,7 @@
 #include <rviz/ogre_helpers/object.h>
 #include <rviz/selection/forwards.h>
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace Ogre
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/robot/robot_link.cpp 1.14.15+dfsg-3/src/rviz/robot/robot_link.cpp
--- 1.14.14+dfsg-2/src/rviz/robot/robot_link.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/robot/robot_link.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -29,16 +29,16 @@
 
 #include <boost/filesystem.hpp>
 
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreRibbonTrail.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSubEntity.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreSharedPtr.h>
-#include <OGRE/OgreTechnique.h>
+#include <OgreEntity.h>
+#include <OgreMaterial.h>
+#include <OgreMaterialManager.h>
+#include <OgreRibbonTrail.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSubEntity.h>
+#include <OgreTextureManager.h>
+#include <OgreSharedPtr.h>
+#include <OgreTechnique.h>
 
 #include <ros/console.h>
 
@@ -163,11 +163,10 @@ RobotLink::RobotLink(Robot* robot,
   , collision_node_(nullptr)
   , trail_(nullptr)
   , axes_(nullptr)
-  , material_alpha_(1.0)
   , robot_alpha_(1.0)
   , only_render_depth_(false)
   , is_selectable_(true)
-  , using_color_(false)
+  , material_mode_flags_(ORIGINAL)
 {
   link_property_ = new Property(link->name.c_str(), true, "", nullptr, SLOT(updateVisibility()), this);
   link_property_->setIcon(rviz::loadPixmap("package://rviz/icons/classes/RobotLink.png"));
@@ -202,8 +201,9 @@ RobotLink::RobotLink(Robot* robot,
   collision_node_ = robot_->getCollisionNode()->createChildSceneNode();
 
   // create material for coloring links
+  std::string material_name = "robot link " + link->name + ":color material";
   color_material_ = Ogre::MaterialPtr(new Ogre::Material(
-      nullptr, "robot link color material", 0, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME));
+      nullptr, material_name, 0, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME));
   color_material_->setReceiveShadows(false);
   color_material_->getTechnique(0)->setLightingEnabled(true);
 
@@ -383,32 +383,36 @@ void RobotLink::setOnlyRenderDepth(bool
 void RobotLink::updateAlpha()
 {
   float link_alpha = alpha_property_->getFloat();
-  M_SubEntityToMaterial::iterator it = materials_.begin();
-  M_SubEntityToMaterial::iterator end = materials_.end();
-  for (; it != end; ++it)
+  for (auto& item : materials_)
   {
-    const Ogre::MaterialPtr& material = it->second;
+    Ogre::MaterialPtr& active = item.second.first;
+    const Ogre::MaterialPtr& original = item.second.second;
 
     if (only_render_depth_)
     {
-      material->setColourWriteEnabled(false);
-      material->setDepthWriteEnabled(true);
+      active->setColourWriteEnabled(false);
+      active->setDepthWriteEnabled(true);
     }
     else
     {
-      Ogre::ColourValue color = material->getTechnique(0)->getPass(0)->getDiffuse();
-      color.a = robot_alpha_ * material_alpha_ * link_alpha;
-      material->setDiffuse(color);
+      Ogre::ColourValue color = active->getTechnique(0)->getPass(0)->getDiffuse();
+      const float material_alpha = original->getTechnique(0)->getPass(0)->getDiffuse().a;
+      color.a = robot_alpha_ * material_alpha * link_alpha;
+      active->setDiffuse(color);
 
-      if (color.a < 0.9998)
+      if (color.a < 0.9998) // transparent
       {
-        material->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
-        material->setDepthWriteEnabled(false);
+        active->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
+        active->setDepthWriteEnabled(false);
       }
-      else
+      else if (active == original)
+      {
+        active->setSceneBlending(Ogre::SBT_REPLACE);
+        active->setDepthWriteEnabled(true);
+      }
+      else // restore original material
       {
-        material->setSceneBlending(Ogre::SBT_REPLACE);
-        material->setDepthWriteEnabled(true);
+        original->copyDetailsTo(active);
       }
     }
   }
@@ -456,9 +460,6 @@ void RobotLink::updateVisibility()
 Ogre::MaterialPtr RobotLink::getMaterialForLink(const urdf::LinkConstSharedPtr& link,
                                                 urdf::MaterialConstSharedPtr material)
 {
-  Ogre::MaterialPtr mat = Ogre::MaterialPtr(new Ogre::Material(
-      nullptr, "robot link material", 0, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME));
-
   // only the first visual's material actually comprises color values, all others only have the name
   // hence search for the first visual with given material name (better fix the bug in urdf parser)
   if (material && !material->name.empty())
@@ -475,6 +476,13 @@ Ogre::MaterialPtr RobotLink::getMaterial
   if (!material && link->visual && link->visual->material)
     material = link->visual->material; // fallback to visual's material
 
+  std::string name = "robot link " + link->name;
+  if (material)
+    name += ":" + material->name;
+
+  Ogre::MaterialPtr mat = Ogre::MaterialPtr(
+      new Ogre::Material(nullptr, name, 0, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME));
+
   if (!material)
   {
     // clone default material (for modification by link)
@@ -488,8 +496,6 @@ Ogre::MaterialPtr RobotLink::getMaterial
     const urdf::Color& col = material->color;
     mat->getTechnique(0)->setAmbient(col.r * 0.5, col.g * 0.5, col.b * 0.5);
     mat->getTechnique(0)->setDiffuse(col.r, col.g, col.b, col.a);
-
-    material_alpha_ = col.a;
   }
   else
   {
@@ -655,19 +661,18 @@ void RobotLink::createEntityForGeometryE
       Ogre::SubEntity* sub = entity->getSubEntity(i);
       const std::string& material_name = sub->getMaterialName();
 
+      Ogre::MaterialPtr active, original;
       if (material_name == "BaseWhite" || material_name == "BaseWhiteNoLighting")
-      {
-        sub->setMaterial(default_material_);
-      }
+        original = default_material_;
       else
-      {
-        // create a new material copy for each instance of a RobotLink
-        Ogre::MaterialPtr mat = Ogre::MaterialPtr(new Ogre::Material(
-            nullptr, material_name, 0, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME));
-        *mat = *sub->getMaterial();
-        sub->setMaterial(mat);
-      }
-      materials_[sub] = sub->getMaterial();
+        original = sub->getMaterial();
+
+      // create a new material copy for each instance of a RobotLink to allow modification per link
+      active = Ogre::MaterialPtr(new Ogre::Material(
+          nullptr, material_name, 0, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME));
+      *active = *original;
+      sub->setMaterial(active);
+      materials_[sub] = std::make_pair(active, original);
     }
   }
 }
@@ -896,40 +901,36 @@ void RobotLink::setTransforms(const Ogre
 
 void RobotLink::setToErrorMaterial()
 {
-  for (size_t i = 0; i < visual_meshes_.size(); i++)
-  {
-    visual_meshes_[i]->setMaterialName("BaseWhiteNoLighting",
-                                       Ogre::ResourceGroupManager::INTERNAL_RESOURCE_GROUP_NAME);
-  }
-  for (size_t i = 0; i < collision_meshes_.size(); i++)
-  {
-    collision_meshes_[i]->setMaterialName("BaseWhiteNoLighting",
-                                          Ogre::ResourceGroupManager::INTERNAL_RESOURCE_GROUP_NAME);
-  }
+  setMaterialMode(material_mode_flags_ | ERROR);
 }
 
 void RobotLink::setToNormalMaterial()
 {
-  if (using_color_)
-  {
-    for (size_t i = 0; i < visual_meshes_.size(); i++)
-    {
-      visual_meshes_[i]->setMaterial(color_material_);
-    }
-    for (size_t i = 0; i < collision_meshes_.size(); i++)
-    {
-      collision_meshes_[i]->setMaterial(color_material_);
-    }
-  }
-  else
+  setMaterialMode(material_mode_flags_ & ~ERROR);
+}
+
+void RobotLink::setMaterialMode(unsigned char mode_flags)
+{
+  if (material_mode_flags_ == mode_flags)
+    return; // nothing to change
+
+  material_mode_flags_ = mode_flags;
+
+  if (mode_flags == ORIGINAL)
   {
-    M_SubEntityToMaterial::iterator it = materials_.begin();
-    M_SubEntityToMaterial::iterator end = materials_.end();
-    for (; it != end; ++it)
-    {
-      it->first->setMaterial(it->second);
-    }
+    for (const auto& item : materials_)
+      item.first->setMaterial(item.second.first);
+    return;
   }
+
+  auto error_material = Ogre::MaterialManager::getSingleton().getByName(
+      "BaseWhiteNoLighting", Ogre::ResourceGroupManager::INTERNAL_RESOURCE_GROUP_NAME);
+  auto material = mode_flags == COLOR ? color_material_ : error_material;
+
+  for (const auto& mesh : visual_meshes_)
+    mesh->setMaterial(material);
+  for (const auto& mesh : collision_meshes_)
+    mesh->setMaterial(material);
 }
 
 void RobotLink::setColor(float red, float green, float blue)
@@ -941,14 +942,12 @@ void RobotLink::setColor(float red, floa
   color_material_->getTechnique(0)->setAmbient(0.5 * color);
   color_material_->getTechnique(0)->setDiffuse(color);
 
-  using_color_ = true;
-  setToNormalMaterial();
+  setMaterialMode(COLOR | (material_mode_flags_ & ERROR));
 }
 
 void RobotLink::unsetColor()
 {
-  using_color_ = false;
-  setToNormalMaterial();
+  setMaterialMode(ORIGINAL | (material_mode_flags_ & ERROR));
 }
 
 bool RobotLink::setSelectable(bool selectable)
diff -pruN 1.14.14+dfsg-2/src/rviz/robot/robot_link.h 1.14.15+dfsg-3/src/rviz/robot/robot_link.h
--- 1.14.14+dfsg-2/src/rviz/robot/robot_link.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/robot/robot_link.h	2022-08-01 08:39:42.000000000 +0000
@@ -36,11 +36,11 @@
 #include <QObject>
 
 #ifndef Q_MOC_RUN
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
-#include <OGRE/OgreAny.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
+#include <OgreAny.h>
+#include <OgreMaterial.h>
+#include <OgreSharedPtr.h>
 #endif
 
 #include <urdf/model.h> // can be replaced later by urdf_model/types.h
@@ -49,7 +49,7 @@
 #include <rviz/ogre_helpers/object.h>
 #include <rviz/selection/forwards.h>
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 namespace Ogre
 {
@@ -79,6 +79,14 @@ typedef boost::shared_ptr<RobotLinkSelec
 class RobotLink : public QObject
 {
   Q_OBJECT
+
+  enum MaterialMode
+  {
+    ORIGINAL = 0,
+    COLOR = 1,
+    ERROR = 2,
+  };
+
 public:
   RobotLink(Robot* robot,
             const urdf::LinkConstSharedPtr& link,
@@ -177,6 +185,7 @@ private Q_SLOTS:
   void updateAxes();
 
 private:
+  void setMaterialMode(unsigned char mode_flags);
   void setRenderQueueGroup(Ogre::uint8 group);
   bool getEnabled() const;
   void createEntityForGeometryElement(const urdf::LinkConstSharedPtr& link,
@@ -214,7 +223,9 @@ protected:
   FloatProperty* alpha_property_;
 
 private:
-  typedef std::map<Ogre::SubEntity*, Ogre::MaterialPtr> M_SubEntityToMaterial;
+  // maintain the original material of each SubEntity to restore it after unsetColor()
+  using M_SubEntityToMaterial =
+      std::map<Ogre::SubEntity*, std::pair<Ogre::MaterialPtr, Ogre::MaterialPtr>>;
   M_SubEntityToMaterial materials_;
   Ogre::MaterialPtr default_material_;
   std::string default_material_name_;
@@ -231,9 +242,7 @@ private:
 
   Axes* axes_;
 
-  float material_alpha_; ///< If material is not a texture, this saves the alpha value set in the URDF,
-                         /// otherwise is 1.0.
-  float robot_alpha_;    ///< Alpha value from top-level robot alpha Property (set via setRobotAlpha()).
+  float robot_alpha_; ///< Alpha value from top-level robot alpha Property (set via setRobotAlpha()).
 
   bool only_render_depth_;
   bool is_selectable_;
@@ -244,7 +253,7 @@ private:
   RobotLinkSelectionHandlerPtr selection_handler_;
 
   Ogre::MaterialPtr color_material_;
-  bool using_color_;
+  unsigned char material_mode_flags_;
 
   friend class RobotLinkSelectionHandler;
 };
diff -pruN 1.14.14+dfsg-2/src/rviz/robot/tf_link_updater.cpp 1.14.15+dfsg-3/src/rviz/robot/tf_link_updater.cpp
--- 1.14.14+dfsg-2/src/rviz/robot/tf_link_updater.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/robot/tf_link_updater.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,8 +31,8 @@
 #include <rviz/frame_manager.h>
 #include <rviz/helpers/tf_prefix.h>
 
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 
 namespace rviz
 {
diff -pruN 1.14.14+dfsg-2/src/rviz/selection/forwards.h 1.14.15+dfsg-3/src/rviz/selection/forwards.h
--- 1.14.14+dfsg-2/src/rviz/selection/forwards.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/selection/forwards.h	2022-08-01 08:39:42.000000000 +0000
@@ -34,8 +34,8 @@
 #include <set>
 #include <map>
 #include <boost/unordered_map.hpp>
-#include <OGRE/OgrePixelFormat.h>
-#include <OGRE/OgreColourValue.h>
+#include <OgrePixelFormat.h>
+#include <OgreColourValue.h>
 
 #include <ros/console.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/selection/selection_handler.cpp 1.14.15+dfsg-3/src/rviz/selection/selection_handler.cpp
--- 1.14.14+dfsg-2/src/rviz/selection/selection_handler.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/selection/selection_handler.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -34,12 +34,12 @@
 
 #include <ros/assert.h>
 
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreWireBoundingBox.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreSubEntity.h>
+#include <OgreSceneNode.h>
+#include <OgreSceneManager.h>
+#include <OgreManualObject.h>
+#include <OgreWireBoundingBox.h>
+#include <OgreEntity.h>
+#include <OgreSubEntity.h>
 
 #include <rviz/selection/selection_manager.h>
 #include <rviz/ogre_helpers/compatibility.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/selection/selection_handler.h 1.14.15+dfsg-3/src/rviz/selection/selection_handler.h
--- 1.14.14+dfsg-2/src/rviz/selection/selection_handler.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/selection/selection_handler.h	2022-08-01 08:39:42.000000000 +0000
@@ -37,7 +37,7 @@
 #include <boost/shared_ptr.hpp>
 #include <boost/unordered_map.hpp>
 
-#include <OGRE/OgreMovableObject.h>
+#include <OgreMovableObject.h>
 #endif
 
 #include <rviz/selection/forwards.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/selection/selection_manager.cpp 1.14.15+dfsg-3/src/rviz/selection/selection_manager.cpp
--- 1.14.14+dfsg-2/src/rviz/selection/selection_manager.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/selection/selection_manager.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,23 +31,23 @@
 
 #include <QTimer>
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreHardwarePixelBuffer.h>
-#include <OGRE/OgreManualObject.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreRenderSystem.h>
-#include <OGRE/OgreRenderTexture.h>
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreSubEntity.h>
-#include <OGRE/OgreTextureManager.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreWireBoundingBox.h>
-#include <OGRE/OgreSharedPtr.h>
-#include <OGRE/OgreTechnique.h>
-#include <OGRE/OgreRectangle2D.h>
+#include <OgreCamera.h>
+#include <OgreEntity.h>
+#include <OgreHardwarePixelBuffer.h>
+#include <OgreManualObject.h>
+#include <OgreMaterialManager.h>
+#include <OgreRenderSystem.h>
+#include <OgreRenderTexture.h>
+#include <OgreRoot.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreSubEntity.h>
+#include <OgreTextureManager.h>
+#include <OgreViewport.h>
+#include <OgreWireBoundingBox.h>
+#include <OgreSharedPtr.h>
+#include <OgreTechnique.h>
+#include <OgreRectangle2D.h>
 
 #include <sensor_msgs/image_encodings.h>
 #include <sensor_msgs/Image.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/selection/selection_manager.h 1.14.15+dfsg-3/src/rviz/selection/selection_manager.h
--- 1.14.14+dfsg-2/src/rviz/selection/selection_manager.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/selection/selection_manager.h	2022-08-01 08:39:42.000000000 +0000
@@ -43,12 +43,12 @@
 #include <boost/unordered_map.hpp>
 #include <boost/thread/recursive_mutex.hpp>
 
-#include <OGRE/OgreTexture.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreMovableObject.h>
-#include <OGRE/OgreRenderQueueListener.h>
-#include <OGRE/OgreSharedPtr.h>
+#include <OgreTexture.h>
+#include <OgreMaterial.h>
+#include <OgreMaterialManager.h>
+#include <OgreMovableObject.h>
+#include <OgreRenderQueueListener.h>
+#include <OgreSharedPtr.h>
 #endif
 
 #include <vector>
diff -pruN 1.14.14+dfsg-2/src/rviz/time_panel.cpp 1.14.15+dfsg-3/src/rviz/time_panel.cpp
--- 1.14.14+dfsg-2/src/rviz/time_panel.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/time_panel.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -53,17 +53,23 @@ TimePanel::TimePanel(QWidget* parent) :
   ros_time_label_ = makeTimeLabel();
   ros_elapsed_label_ = makeTimeLabel();
 
-  experimental_cb_ = new QCheckBox("Experimental");
-  experimental_cb_->setSizePolicy(QSizePolicy(QSizePolicy::Minimum, QSizePolicy::Minimum));
-
-  pause_button_ = new QPushButton("Pause");
+  pause_button_ = new QPushButton(QIcon::fromTheme("media-playback-pause"), "Pause");
   pause_button_->setToolTip("Freeze ROS time.");
   pause_button_->setCheckable(true);
 
   sync_mode_selector_ = new QComboBox(this);
   sync_mode_selector_->addItem("Off");
+  sync_mode_selector_->setItemData(FrameManager::SyncOff, "Display data using latest TF data",
+                                   Qt::ToolTipRole);
   sync_mode_selector_->addItem("Exact");
+  sync_mode_selector_->setItemData(FrameManager::SyncExact, "Synchronize TF lookups to a source display",
+                                   Qt::ToolTipRole);
   sync_mode_selector_->addItem("Approximate");
+  sync_mode_selector_->setItemData(
+      FrameManager::SyncApprox, "Synchronize to a source display in a smooth fashion", Qt::ToolTipRole);
+  sync_mode_selector_->addItem("Frame");
+  sync_mode_selector_->setItemData(FrameManager::SyncFrame, "Synchronize TF lookups within a frame",
+                                   Qt::ToolTipRole);
   sync_mode_selector_->setSizeAdjustPolicy(QComboBox::AdjustToContents);
   sync_mode_selector_->setToolTip(
       "Allows you to synchronize the ROS time and Tf transforms to a given source.");
@@ -73,41 +79,27 @@ TimePanel::TimePanel(QWidget* parent) :
   sync_source_selector_->setSizeAdjustPolicy(QComboBox::AdjustToContents);
   sync_source_selector_->setToolTip("Time source to use for synchronization.");
 
-  experimental_widget_ = new QWidget(this);
-  QHBoxLayout* experimental_layout = new QHBoxLayout(this);
-  experimental_layout->addWidget(pause_button_);
-  experimental_layout->addWidget(new QLabel("Synchronization:"));
-  experimental_layout->addWidget(sync_mode_selector_);
-  experimental_layout->addWidget(new QLabel("Source:"));
-  experimental_layout->addWidget(sync_source_selector_);
-  experimental_layout->addSpacing(20);
-  experimental_layout->setContentsMargins(0, 0, 20, 0);
-  experimental_widget_->setLayout(experimental_layout);
-
-  old_widget_ = new QWidget(this);
-  QHBoxLayout* old_layout = new QHBoxLayout(this);
-  old_layout->addWidget(new QLabel("ROS Elapsed:"));
-  old_layout->addWidget(ros_elapsed_label_);
-  old_layout->addWidget(new QLabel("Wall Time:"));
-  old_layout->addWidget(wall_time_label_);
-  old_layout->addWidget(new QLabel("Wall Elapsed:"));
-  old_layout->addWidget(wall_elapsed_label_);
-  old_layout->setContentsMargins(0, 0, 20, 0);
-  old_widget_->setLayout(old_layout);
-
   QHBoxLayout* layout = new QHBoxLayout(this);
+  layout->addWidget(pause_button_);
+  layout->addSpacing(10);
+
+  layout->addWidget(new QLabel("Synchronization:"));
+  layout->addWidget(sync_mode_selector_);
+  layout->addWidget(sync_source_selector_);
+  layout->addSpacing(10);
 
-  layout->addWidget(experimental_widget_);
   layout->addWidget(new QLabel("ROS Time:"));
   layout->addWidget(ros_time_label_);
-  layout->addWidget(old_widget_);
-  layout->addStretch(100);
-  layout->addWidget(experimental_cb_);
+  layout->addWidget(new QLabel("ROS Elapsed:"));
+  layout->addWidget(ros_elapsed_label_);
+  layout->addWidget(new QLabel("Wall Time:"));
+  layout->addWidget(wall_time_label_);
+  layout->addWidget(new QLabel("Wall Elapsed:"));
+  layout->addWidget(wall_elapsed_label_);
 
-  layout->addStretch();
   layout->setContentsMargins(11, 5, 11, 5);
+  this->setLayout(layout);
 
-  connect(experimental_cb_, SIGNAL(toggled(bool)), this, SLOT(experimentalToggled(bool)));
   connect(pause_button_, SIGNAL(toggled(bool)), this, SLOT(pauseToggled(bool)));
   connect(sync_mode_selector_, SIGNAL(activated(int)), this, SLOT(syncModeSelected(int)));
   connect(sync_source_selector_, SIGNAL(activated(int)), this, SLOT(syncSourceSelected(int)));
@@ -134,10 +126,6 @@ void TimePanel::load(const Config& confi
     syncModeSelected(sync_mode);
   }
   config.mapGetString("SyncSource", &config_sync_source_);
-  bool experimental = false;
-  config.mapGetBool("Experimental", &experimental);
-  experimental_cb_->setChecked(experimental);
-  experimentalToggled(experimental);
 }
 
 void TimePanel::save(Config config) const
@@ -145,7 +133,6 @@ void TimePanel::save(Config config) cons
   Panel::save(config);
   config.mapSetValue("SyncMode", sync_mode_selector_->currentIndex());
   config.mapSetValue("SyncSource", sync_source_selector_->currentText());
-  config.mapSetValue("Experimental", experimental_cb_->checkState() == Qt::Checked);
 }
 
 void TimePanel::onDisplayAdded(Display* display)
@@ -166,8 +153,7 @@ void TimePanel::onDisplayAdded(Display*
   }
   else
   {
-    connect(display, SIGNAL(timeSignal(rviz::Display*, ros::Time)), this,
-            SLOT(onTimeSignal(rviz::Display*, ros::Time)));
+    connect(display, SIGNAL(timeSignal(ros::Time)), this, SLOT(onTimeSignal(ros::Time)));
   }
 }
 
@@ -181,8 +167,12 @@ void TimePanel::onDisplayRemoved(Display
   }
 }
 
-void TimePanel::onTimeSignal(Display* display, ros::Time time)
+void TimePanel::onTimeSignal(ros::Time time)
 {
+  Display* display = qobject_cast<Display*>(sender());
+  if (!display)
+    return;
+
   QString name = display->getName();
   int index = sync_source_selector_->findData(QVariant((qulonglong)display));
 
@@ -235,25 +225,6 @@ void TimePanel::pauseToggled(bool checke
   vis_manager_->getFrameManager()->setPause(checked);
 }
 
-void TimePanel::experimentalToggled(bool checked)
-{
-  old_widget_->setVisible(!checked);
-  experimental_widget_->setVisible(checked);
-  if (vis_manager_ && vis_manager_->getFrameManager())
-  {
-    if (!checked)
-    {
-      pauseToggled(false);
-      syncModeSelected(0);
-    }
-    else
-    {
-      pauseToggled(pause_button_->isChecked());
-      syncModeSelected(sync_mode_selector_->currentIndex());
-    }
-  }
-}
-
 void TimePanel::syncSourceSelected(int /*index*/)
 {
   // clear whatever was loaded from the config
@@ -264,7 +235,7 @@ void TimePanel::syncSourceSelected(int /
 void TimePanel::syncModeSelected(int mode)
 {
   vis_manager_->getFrameManager()->setSyncMode((FrameManager::SyncMode)mode);
-  sync_source_selector_->setEnabled(mode != FrameManager::SyncOff);
+  sync_source_selector_->setVisible(mode >= FrameManager::SyncExact && mode <= FrameManager::SyncApprox);
   vis_manager_->notifyConfigChanged();
 }
 
diff -pruN 1.14.14+dfsg-2/src/rviz/time_panel.h 1.14.15+dfsg-3/src/rviz/time_panel.h
--- 1.14.14+dfsg-2/src/rviz/time_panel.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/time_panel.h	2022-08-01 08:39:42.000000000 +0000
@@ -62,7 +62,6 @@ protected Q_SLOTS:
   void pauseToggled(bool checked);
   void syncModeSelected(int index);
   void syncSourceSelected(int index);
-  void experimentalToggled(bool checked);
 
   /** Read time values from VisualizationManager and update displays. */
   void update();
@@ -70,7 +69,7 @@ protected Q_SLOTS:
   void onDisplayAdded(rviz::Display* display);
   void onDisplayRemoved(rviz::Display* display);
 
-  void onTimeSignal(rviz::Display* display, ros::Time time);
+  void onTimeSignal(ros::Time time);
 
   void load(const Config& config) override;
   void save(Config config) const override;
@@ -82,13 +81,8 @@ protected:
   /** Fill a single time label with the given time value (in seconds). */
   void fillTimeLabel(QLineEdit* label, double time);
 
-  QWidget* old_widget_;
-  QWidget* experimental_widget_;
-
   QString config_sync_source_;
 
-  QCheckBox* experimental_cb_;
-
   QPushButton* pause_button_;
   QComboBox* sync_source_selector_;
   QComboBox* sync_mode_selector_;
diff -pruN 1.14.14+dfsg-2/src/rviz/tool_manager.cpp 1.14.15+dfsg-3/src/rviz/tool_manager.cpp
--- 1.14.14+dfsg-2/src/rviz/tool_manager.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/tool_manager.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -149,7 +149,7 @@ void ToolManager::handleChar(QKeyEvent*
     else
     {
       // if no, check if the current tool accesses all key events
-      if (current_tool_->accessAllKeys())
+      if (current_tool_ && current_tool_->accessAllKeys())
       {
         // if yes, pass the key
         current_tool_->processKeyEvent(event, panel);
@@ -161,7 +161,7 @@ void ToolManager::handleChar(QKeyEvent*
       }
     }
   }
-  else
+  else if (current_tool_)
   {
     // if the incoming key triggers no other tool,
     // just hand down the key event
diff -pruN 1.14.14+dfsg-2/src/rviz/validate_floats.h 1.14.15+dfsg-3/src/rviz/validate_floats.h
--- 1.14.14+dfsg-2/src/rviz/validate_floats.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/validate_floats.h	2022-08-01 08:39:42.000000000 +0000
@@ -38,8 +38,8 @@
 #include <geometry_msgs/PoseStamped.h>
 #include <geometry_msgs/Twist.h>
 #include <std_msgs/ColorRGBA.h>
-#include <OGRE/OgreVector3.h>
-#include <OGRE/OgreQuaternion.h>
+#include <rviz/ogre_helpers/ogre_vector.h>
+#include <OgreQuaternion.h>
 
 #include <boost/array.hpp>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/validate_quaternions.h 1.14.15+dfsg-3/src/rviz/validate_quaternions.h
--- 1.14.14+dfsg-2/src/rviz/validate_quaternions.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/validate_quaternions.h	2022-08-01 08:39:42.000000000 +0000
@@ -31,7 +31,7 @@
 #define RVIZ_VALIDATE_QUATERNIONS_H
 
 #include <geometry_msgs/PoseStamped.h>
-#include <OGRE/OgreQuaternion.h>
+#include <OgreQuaternion.h>
 #include <ros/ros.h>
 #include <tf2/LinearMath/Quaternion.h>
 
diff -pruN 1.14.14+dfsg-2/src/rviz/view_controller.cpp 1.14.15+dfsg-3/src/rviz/view_controller.cpp
--- 1.14.14+dfsg-2/src/rviz/view_controller.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/view_controller.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -31,9 +31,9 @@
 #include <QFont>
 #include <QKeyEvent>
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreCamera.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
 
 #include <rviz/display_context.h>
 #include <rviz/frame_manager.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/view_controller.h 1.14.15+dfsg-3/src/rviz/view_controller.h
--- 1.14.14+dfsg-2/src/rviz/view_controller.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/view_controller.h	2022-08-01 08:39:42.000000000 +0000
@@ -36,7 +36,7 @@
 #include <utility>
 
 
-#include <OGRE/OgrePrerequisites.h>
+#include <OgrePrerequisites.h>
 
 #include <rviz/properties/property.h>
 #include <rviz/rviz_export.h>
diff -pruN 1.14.14+dfsg-2/src/rviz/visualization_frame.cpp 1.14.15+dfsg-3/src/rviz/visualization_frame.cpp
--- 1.14.14+dfsg-2/src/rviz/visualization_frame.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/visualization_frame.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -53,15 +53,15 @@
 
 #include <boost/algorithm/string/split.hpp>
 #include <boost/algorithm/string/trim.hpp>
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 #include <boost/filesystem.hpp>
 
 #include <ros/console.h>
 #include <ros/package.h>
 #include <ros/init.h>
 
-#include <OGRE/OgreRenderWindow.h>
-#include <OGRE/OgreMeshManager.h>
+#include <OgreRenderWindow.h>
+#include <OgreMeshManager.h>
 
 #include <rviz/ogre_helpers/initialization.h>
 
@@ -733,7 +733,7 @@ void VisualizationFrame::loadDisplayConf
   if (!valid_load_path)
   {
     actual_load_path = (fs::path(package_path_) / "default.rviz");
-    if (!(valid_load_path = fs::is_regular_file(actual_load_path)))
+    if (!fs::is_regular_file(actual_load_path))
     {
       ROS_ERROR("Default display config '%s' not found.  RViz will be very empty at first.",
                 actual_load_path.c_str());
@@ -1320,6 +1320,23 @@ QWidget* VisualizationFrame::getParentWi
   return this;
 }
 
+void VisualizationFrame::onPanelDeleted(QObject* dock)
+{
+  for (int i = 0; i < custom_panels_.size(); ++i)
+  {
+    if (custom_panels_[i].dock == dock)
+    {
+      auto& record = custom_panels_[i];
+      record.delete_action->deleteLater();
+      delete_view_menu_->removeAction(record.delete_action);
+      delete_view_menu_->setDisabled(delete_view_menu_->actions().isEmpty());
+      custom_panels_.removeAt(i);
+      setDisplayConfigModified();
+      return;
+    }
+  }
+}
+
 void VisualizationFrame::onDeletePanel()
 {
   // This should only be called as a SLOT from a QAction in the
@@ -1334,13 +1351,6 @@ void VisualizationFrame::onDeletePanel()
       if (custom_panels_[i].delete_action == action)
       {
         delete custom_panels_[i].dock;
-        custom_panels_.removeAt(i);
-        setDisplayConfigModified();
-        action->deleteLater();
-        if (delete_view_menu_->actions().size() == 1 && delete_view_menu_->actions().first() == action)
-        {
-          delete_view_menu_->setEnabled(false);
-        }
         return;
       }
     }
@@ -1393,6 +1403,7 @@ QDockWidget* VisualizationFrame::addPane
   record.panel = panel;
   record.name = name;
   record.delete_action = delete_view_menu_->addAction(name, this, SLOT(onDeletePanel()));
+  connect(record.dock, &QObject::destroyed, this, &VisualizationFrame::onPanelDeleted);
   custom_panels_.append(record);
   delete_view_menu_->setEnabled(true);
 
diff -pruN 1.14.14+dfsg-2/src/rviz/visualization_frame.h 1.14.15+dfsg-3/src/rviz/visualization_frame.h
--- 1.14.14+dfsg-2/src/rviz/visualization_frame.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/visualization_frame.h	2022-08-01 08:39:42.000000000 +0000
@@ -269,6 +269,7 @@ protected Q_SLOTS:
 
   void reset();
 
+  void onPanelDeleted(QObject* dock);
   void onHelpDestroyed();
 
   void hideLeftDock(bool hide);
diff -pruN 1.14.14+dfsg-2/src/rviz/visualization_manager.cpp 1.14.15+dfsg-3/src/rviz/visualization_manager.cpp
--- 1.14.14+dfsg-2/src/rviz/visualization_manager.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/visualization_manager.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -35,18 +35,18 @@
 #include <QTimer>
 #include <QWindow>
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreLight.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreMaterial.h>
-#include <OGRE/OgreRenderWindow.h>
-#include <OGRE/OgreSharedPtr.h>
-#include <OGRE/OgreCamera.h>
+#include <OgreRoot.h>
+#include <OgreSceneManager.h>
+#include <OgreSceneNode.h>
+#include <OgreLight.h>
+#include <OgreViewport.h>
+#include <OgreMaterialManager.h>
+#include <OgreMaterial.h>
+#include <OgreRenderWindow.h>
+#include <OgreSharedPtr.h>
+#include <OgreCamera.h>
 
 #include <boost/filesystem.hpp>
 #include <utility>
diff -pruN 1.14.14+dfsg-2/src/rviz/visualizer_app.cpp 1.14.15+dfsg-3/src/rviz/visualizer_app.cpp
--- 1.14.14+dfsg-2/src/rviz/visualizer_app.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/rviz/visualizer_app.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -33,9 +33,9 @@
 #include <boost/program_options.hpp>
 #include <boost/filesystem.hpp>
 
-#include <OGRE/OgreMaterialManager.h>
-#include <OGRE/OgreGpuProgramManager.h>
-#include <OGRE/OgreHighLevelGpuProgramManager.h>
+#include <OgreMaterialManager.h>
+#include <OgreGpuProgramManager.h>
+#include <OgreHighLevelGpuProgramManager.h>
 #include <std_srvs/Empty.h>
 
 #ifdef Q_OS_MAC
diff -pruN 1.14.14+dfsg-2/src/test/CMakeLists.txt 1.14.15+dfsg-3/src/test/CMakeLists.txt
--- 1.14.14+dfsg-2/src/test/CMakeLists.txt	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/CMakeLists.txt	2022-08-01 08:39:42.000000000 +0000
@@ -3,25 +3,16 @@ find_package(rostest REQUIRED)
 
 # This is a test utility which publishes images of different types.
 add_executable(send_images EXCLUDE_FROM_ALL send_images.cpp)
-if(NOT WIN32)
-  set_target_properties(send_images PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(send_images ${catkin_LIBRARIES})
 add_dependencies(tests send_images)
 
 # This is a test utility which can publish different kinds of markers.
 add_executable(marker_test EXCLUDE_FROM_ALL marker_test.cpp)
-if(NOT WIN32)
-  set_target_properties(marker_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(marker_test ${catkin_LIBRARIES})
 add_dependencies(tests marker_test)
 
 # This is a test utility which can publish different kinds of mesh markers.
 add_executable(mesh_marker_test EXCLUDE_FROM_ALL mesh_marker_test.cpp)
-if(NOT WIN32)
-  set_target_properties(mesh_marker_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(mesh_marker_test ${catkin_LIBRARIES})
 add_dependencies(tests mesh_marker_test)
 
@@ -53,81 +44,51 @@ catkin_add_gtest(uniform_string_stream_t
 
 # This is an example node which serves an rviz logo as an interactive marker.
 add_executable(rviz_logo_marker EXCLUDE_FROM_ALL rviz_logo_marker.cpp)
-if(NOT WIN32)
-  set_target_properties(rviz_logo_marker PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(rviz_logo_marker ${catkin_LIBRARIES})
 add_dependencies(tests rviz_logo_marker)
 
 # This is an example node which publishes different kinds of point clouds.
 add_executable(cloud_test EXCLUDE_FROM_ALL cloud_test.cpp)
-if(NOT WIN32)
-  set_target_properties(cloud_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(cloud_test ${catkin_LIBRARIES})
 add_dependencies(tests cloud_test)
 
 # This is an example node which serves an interactive marker.
 add_executable(interactive_marker_test interactive_marker_test.cpp)
-if(NOT WIN32)
-  set_target_properties(interactive_marker_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(interactive_marker_test ${catkin_LIBRARIES})
 add_dependencies(tests interactive_marker_test)
 
 # This is another example node that publishes images.
 add_executable(image_test EXCLUDE_FROM_ALL image_test.cpp)
-if(NOT WIN32)
-  set_target_properties(image_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(image_test ${catkin_LIBRARIES})
 add_dependencies(tests image_test)
 
 # This is a node that sends lots of point clouds.
 add_executable(send_lots_of_points EXCLUDE_FROM_ALL send_lots_of_points_node.cpp)
-if(NOT WIN32)
-  set_target_properties(send_lots_of_points PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(send_lots_of_points ${catkin_LIBRARIES})
 add_dependencies(tests send_lots_of_points)
 
 # Yet another example which sends point clouds.
 add_executable(send_point_cloud_2 EXCLUDE_FROM_ALL send_point_cloud_2.cpp)
-if(NOT WIN32)
-  set_target_properties(send_point_cloud_2 PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(send_point_cloud_2 ${catkin_LIBRARIES})
 add_dependencies(tests send_point_cloud_2)
 
 # This is a node which sends grid cells.
 add_executable(send_grid_cells EXCLUDE_FROM_ALL send_grid_cells_node.cpp)
-if(NOT WIN32)
-  set_target_properties(send_grid_cells PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(send_grid_cells ${catkin_LIBRARIES})
 add_dependencies(tests send_grid_cells)
 
 # This is a test program that uses the rviz panel interface.
 add_executable(render_panel_test render_panel_test.cpp)
-if(NOT WIN32)
-  set_target_properties(render_panel_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(render_panel_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
 add_dependencies(tests render_panel_test)
 
 # This is an executable which uses the rviz new display diaglog interface.
 add_executable(new_display_dialog_test new_display_dialog_test.cpp)
-if(NOT WIN32)
-  set_target_properties(new_display_dialog_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(new_display_dialog_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
 add_dependencies(tests new_display_dialog_test)
 
 # This is an executable which uses the rviz color editor test.
 add_executable(color_editor_test color_editor_test.cpp)
-if(NOT WIN32)
-  set_target_properties(color_editor_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(color_editor_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
 add_dependencies(tests color_editor_test)
 
@@ -143,17 +104,11 @@ add_dependencies(tests property_with_ros
 
 # This is an executable that uses the line_edit_with_button property interface.
 add_executable(line_edit_with_button_test line_edit_with_button_test.cpp)
-if(NOT WIN32)
-  set_target_properties(line_edit_with_button_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(line_edit_with_button_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
 add_dependencies(tests line_edit_with_button_test)
 
 # This is an executable which tests the connect/disconnect behavior of signals and slots in Qt.
 add_executable(connect_test connect_test.cpp)
-if(NOT WIN32)
-  set_target_properties(connect_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(connect_test ${QT_LIBRARIES})
 add_dependencies(tests connect_test)
 
@@ -166,17 +121,11 @@ add_executable(render_points_test
   render_points_test.cpp
   ../rviz/ogre_helpers/orbit_camera.cpp
 )
-if(NOT WIN32)
-  set_target_properties(render_points_test PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(render_points_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
 add_dependencies(tests render_points_test)
 
 # This is an example application which creates two ogre render windows.
 add_executable(two_render_widgets two_render_widgets.cpp)
-if(NOT WIN32)
-  set_target_properties(two_render_widgets PROPERTIES COMPILE_FLAGS "-std=c++11")
-endif()
 target_link_libraries(two_render_widgets rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
 add_dependencies(tests two_render_widgets)
 
diff -pruN 1.14.14+dfsg-2/src/test/property_test.cpp 1.14.15+dfsg-3/src/test/property_test.cpp
--- 1.14.14+dfsg-2/src/test/property_test.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/property_test.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -105,8 +105,8 @@ TEST(Property, children)
 
 TEST(VectorProperty, default_value)
 {
-  VectorProperty* vp = new VectorProperty();
-  Ogre::Vector3 vec = vp->getVector();
+  VectorProperty vp;
+  Ogre::Vector3 vec = vp.getVector();
   EXPECT_EQ(0, vec.x);
   EXPECT_EQ(0, vec.y);
   EXPECT_EQ(0, vec.z);
@@ -114,11 +114,11 @@ TEST(VectorProperty, default_value)
 
 TEST(VectorProperty, set_and_get)
 {
-  VectorProperty* vp = new VectorProperty();
+  VectorProperty vp;
   Ogre::Vector3 vec(1, 2, 3);
-  vp->setVector(vec);
+  vp.setVector(vec);
 
-  Ogre::Vector3 vec2 = vp->getVector();
+  Ogre::Vector3 vec2 = vp.getVector();
   EXPECT_EQ(1, vec2.x);
   EXPECT_EQ(2, vec2.y);
   EXPECT_EQ(3, vec2.z);
@@ -126,17 +126,17 @@ TEST(VectorProperty, set_and_get)
 
 TEST(VectorProperty, set_string)
 {
-  VectorProperty* vp = new VectorProperty();
-  vp->setValue(QString("1;2;3"));
+  VectorProperty vp;
+  vp.setValue(QString("1;2;3"));
 
-  Ogre::Vector3 vec = vp->getVector();
+  Ogre::Vector3 vec = vp.getVector();
   EXPECT_EQ(1, vec.x);
   EXPECT_EQ(2, vec.y);
   EXPECT_EQ(3, vec.z);
 
-  vp->setValue(QString("chubby!"));
+  vp.setValue(QString("chubby!"));
 
-  vec = vp->getVector();
+  vec = vp.getVector();
   EXPECT_EQ(1, vec.x);
   EXPECT_EQ(2, vec.y);
   EXPECT_EQ(3, vec.z);
@@ -144,12 +144,12 @@ TEST(VectorProperty, set_string)
 
 TEST(VectorProperty, set_child)
 {
-  VectorProperty* vp = new VectorProperty();
-  vp->subProp("X")->setValue(0.9);
-  vp->subProp("Y")->setValue(1.1);
-  vp->subProp("Z")->setValue(1.3);
+  VectorProperty vp;
+  vp.subProp("X")->setValue(0.9);
+  vp.subProp("Y")->setValue(1.1);
+  vp.subProp("Z")->setValue(1.3);
 
-  Ogre::Vector3 vec = vp->getVector();
+  Ogre::Vector3 vec = vp.getVector();
   EXPECT_EQ(0.9f, vec.x);
   EXPECT_EQ(1.1f, vec.y);
   EXPECT_EQ(1.3f, vec.z);
@@ -157,10 +157,10 @@ TEST(VectorProperty, set_child)
 
 TEST(VectorProperty, get_child)
 {
-  VectorProperty* vp = new VectorProperty("v", Ogre::Vector3(1, 2, 3));
-  EXPECT_EQ(1, vp->subProp("X")->getValue().toFloat());
-  EXPECT_EQ(2, vp->subProp("Y")->getValue().toFloat());
-  EXPECT_EQ(3, vp->subProp("Z")->getValue().toFloat());
+  VectorProperty vp("v", Ogre::Vector3(1, 2, 3));
+  EXPECT_EQ(1, vp.subProp("X")->getValue().toFloat());
+  EXPECT_EQ(2, vp.subProp("Y")->getValue().toFloat());
+  EXPECT_EQ(3, vp.subProp("Z")->getValue().toFloat());
 }
 
 TEST(VectorProperty, set_value_events)
@@ -181,8 +181,8 @@ TEST(VectorProperty, set_value_events)
 
 TEST(QuaternionProperty, default_value)
 {
-  QuaternionProperty* qp = new QuaternionProperty();
-  Ogre::Quaternion quat = qp->getQuaternion();
+  QuaternionProperty qp;
+  Ogre::Quaternion quat = qp.getQuaternion();
   EXPECT_EQ(0, quat.x);
   EXPECT_EQ(0, quat.y);
   EXPECT_EQ(0, quat.z);
@@ -191,11 +191,11 @@ TEST(QuaternionProperty, default_value)
 
 TEST(QuaternionProperty, set_and_get)
 {
-  QuaternionProperty* qp = new QuaternionProperty();
+  QuaternionProperty qp;
   Ogre::Quaternion quat(4, 1, 2, 3);
-  qp->setQuaternion(quat);
+  qp.setQuaternion(quat);
 
-  Ogre::Quaternion quat2 = qp->getQuaternion();
+  Ogre::Quaternion quat2 = qp.getQuaternion();
   EXPECT_EQ(1, quat2.x);
   EXPECT_EQ(2, quat2.y);
   EXPECT_EQ(3, quat2.z);
@@ -204,18 +204,18 @@ TEST(QuaternionProperty, set_and_get)
 
 TEST(QuaternionProperty, set_string)
 {
-  QuaternionProperty* qp = new QuaternionProperty();
-  qp->setValue(QString("1;2;3;4"));
+  QuaternionProperty qp;
+  qp.setValue(QString("1;2;3;4"));
 
-  Ogre::Quaternion quat = qp->getQuaternion();
+  Ogre::Quaternion quat = qp.getQuaternion();
   EXPECT_EQ(1, quat.x);
   EXPECT_EQ(2, quat.y);
   EXPECT_EQ(3, quat.z);
   EXPECT_EQ(4, quat.w);
 
-  qp->setValue(QString("chubby!"));
+  qp.setValue(QString("chubby!"));
 
-  quat = qp->getQuaternion();
+  quat = qp.getQuaternion();
   EXPECT_EQ(1, quat.x);
   EXPECT_EQ(2, quat.y);
   EXPECT_EQ(3, quat.z);
@@ -224,13 +224,13 @@ TEST(QuaternionProperty, set_string)
 
 TEST(QuaternionProperty, set_child)
 {
-  QuaternionProperty* qp = new QuaternionProperty();
-  qp->subProp("X")->setValue(0.9);
-  qp->subProp("Y")->setValue(1.1);
-  qp->subProp("Z")->setValue(1.3);
-  qp->subProp("W")->setValue(1.5);
+  QuaternionProperty qp;
+  qp.subProp("X")->setValue(0.9);
+  qp.subProp("Y")->setValue(1.1);
+  qp.subProp("Z")->setValue(1.3);
+  qp.subProp("W")->setValue(1.5);
 
-  Ogre::Quaternion quat = qp->getQuaternion();
+  Ogre::Quaternion quat = qp.getQuaternion();
   EXPECT_EQ(0.9f, quat.x);
   EXPECT_EQ(1.1f, quat.y);
   EXPECT_EQ(1.3f, quat.z);
@@ -239,11 +239,11 @@ TEST(QuaternionProperty, set_child)
 
 TEST(QuaternionProperty, get_child)
 {
-  QuaternionProperty* qp = new QuaternionProperty("v", Ogre::Quaternion(4, 1, 2, 3));
-  EXPECT_EQ(1, qp->subProp("X")->getValue().toFloat());
-  EXPECT_EQ(2, qp->subProp("Y")->getValue().toFloat());
-  EXPECT_EQ(3, qp->subProp("Z")->getValue().toFloat());
-  EXPECT_EQ(4, qp->subProp("W")->getValue().toFloat());
+  QuaternionProperty qp("v", Ogre::Quaternion(4, 1, 2, 3));
+  EXPECT_EQ(1, qp.subProp("X")->getValue().toFloat());
+  EXPECT_EQ(2, qp.subProp("Y")->getValue().toFloat());
+  EXPECT_EQ(3, qp.subProp("Z")->getValue().toFloat());
+  EXPECT_EQ(4, qp.subProp("W")->getValue().toFloat());
 }
 
 TEST(QuaternionProperty, set_value_events)
@@ -265,8 +265,8 @@ TEST(QuaternionProperty, set_value_event
 
 TEST(ColorProperty, default_value)
 {
-  ColorProperty* qp = new ColorProperty();
-  QColor color = qp->getColor();
+  ColorProperty qp;
+  QColor color = qp.getColor();
   EXPECT_EQ(0, color.red());
   EXPECT_EQ(0, color.green());
   EXPECT_EQ(0, color.blue());
@@ -274,11 +274,11 @@ TEST(ColorProperty, default_value)
 
 TEST(ColorProperty, set_and_get)
 {
-  ColorProperty* qp = new ColorProperty();
+  ColorProperty qp;
   QColor color(1, 2, 3);
-  qp->setColor(color);
+  qp.setColor(color);
 
-  QColor color2 = qp->getColor();
+  QColor color2 = qp.getColor();
   EXPECT_EQ(1, color2.red());
   EXPECT_EQ(2, color2.green());
   EXPECT_EQ(3, color2.blue());
@@ -286,17 +286,17 @@ TEST(ColorProperty, set_and_get)
 
 TEST(ColorProperty, set_string)
 {
-  ColorProperty* qp = new ColorProperty();
-  qp->setValue(QString("1;2;3"));
+  ColorProperty qp;
+  qp.setValue(QString("1;2;3"));
 
-  QColor color = qp->getColor();
+  QColor color = qp.getColor();
   EXPECT_EQ(1, color.red());
   EXPECT_EQ(2, color.green());
   EXPECT_EQ(3, color.blue());
 
-  qp->setValue(QString("chubby!"));
+  qp.setValue(QString("chubby!"));
 
-  color = qp->getColor();
+  color = qp.getColor();
   EXPECT_EQ(1, color.red());
   EXPECT_EQ(2, color.green());
   EXPECT_EQ(3, color.blue());
@@ -304,10 +304,10 @@ TEST(ColorProperty, set_string)
 
 TEST(ColorProperty, set_string_limits)
 {
-  ColorProperty* qp = new ColorProperty();
-  qp->setValue(QString("-1;2000;3"));
+  ColorProperty qp;
+  qp.setValue(QString("-1;2000;3"));
 
-  QColor color = qp->getColor();
+  QColor color = qp.getColor();
   EXPECT_EQ(0, color.red());
   EXPECT_EQ(255, color.green());
   EXPECT_EQ(3, color.blue());
diff -pruN 1.14.14+dfsg-2/src/test/render_points_test.cpp 1.14.15+dfsg-3/src/test/render_points_test.cpp
--- 1.14.14+dfsg-2/src/test/render_points_test.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/render_points_test.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -34,8 +34,8 @@
 #include <QApplication>
 #include <QVBoxLayout>
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreSceneNode.h>
+#include <OgreCamera.h>
+#include <OgreSceneNode.h>
 
 using namespace rviz;
 
diff -pruN 1.14.14+dfsg-2/src/test/render_points_test.h 1.14.15+dfsg-3/src/test/render_points_test.h
--- 1.14.14+dfsg-2/src/test/render_points_test.h	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/render_points_test.h	2022-08-01 08:39:42.000000000 +0000
@@ -44,10 +44,10 @@
 #include <rviz/ogre_helpers/billboard_line.h>
 #include <rviz/ogre_helpers/render_system.h>
 
-#include <OGRE/OgreRoot.h>
-#include <OGRE/OgreSceneManager.h>
-#include <OGRE/OgreViewport.h>
-#include <OGRE/OgreLight.h>
+#include <OgreRoot.h>
+#include <OgreSceneManager.h>
+#include <OgreViewport.h>
+#include <OgreLight.h>
 
 #include <ros/time.h>
 #endif
diff -pruN 1.14.14+dfsg-2/src/test/rviz_logo_marker.cpp 1.14.15+dfsg-3/src/test/rviz_logo_marker.cpp
--- 1.14.14+dfsg-2/src/test/rviz_logo_marker.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/rviz_logo_marker.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -99,7 +99,8 @@ int main(int argc, char** argv)
   ros::init(argc, argv, "rviz_logo_marker");
   ros::NodeHandle n;
 
-  ros::Timer publish_timer = n.createTimer(ros::Duration(0.1), boost::bind(&publishCallback, _1));
+  ros::Timer publish_timer =
+      n.createTimer(ros::Duration(0.1), boost::bind(&publishCallback, boost::placeholders::_1));
 
   server = new interactive_markers::InteractiveMarkerServer("rviz_logo");
   makeMarker();
diff -pruN 1.14.14+dfsg-2/src/test/send_covariance_msgs.py 1.14.15+dfsg-3/src/test/send_covariance_msgs.py
--- 1.14.14+dfsg-2/src/test/send_covariance_msgs.py	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/send_covariance_msgs.py	2022-08-01 08:39:42.000000000 +0000
@@ -72,7 +72,7 @@ while not rospy.is_shutdown():
         pi / 2, pi / 3, 0
     )
 
-    pose_with_cov.pose.covariance[0] = linear_deviation ** 2.0
+    pose_with_cov.pose.covariance[0] = linear_deviation**2.0
     pose_with_cov.pose.covariance[6 + 1] = 0.0001
     pose_with_cov.pose.covariance[12 + 2] = 0.0001
     pose_with_cov.pose.covariance[18 + 3] = 0.01
diff -pruN 1.14.14+dfsg-2/src/test/send_tf_timing.py 1.14.15+dfsg-3/src/test/send_tf_timing.py
--- 1.14.14+dfsg-2/src/test/send_tf_timing.py	1970-01-01 00:00:00.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/send_tf_timing.py	2022-08-01 08:39:42.000000000 +0000
@@ -0,0 +1,103 @@
+#!/usr/bin/env python
+
+from __future__ import print_function
+
+import rospy
+import math
+import numpy as np
+
+import tf2_ros
+from geometry_msgs.msg import TransformStamped
+from sensor_msgs import point_cloud2
+from sensor_msgs.msg import PointCloud2
+from sensor_msgs.msg import PointField
+from std_msgs.msg import Header
+
+width = 100
+height = 100
+
+
+def create_pc(t):
+    fields = [
+        PointField("x", 0, PointField.FLOAT32, 1),
+        PointField("y", 4, PointField.FLOAT32, 1),
+        PointField("z", 8, PointField.FLOAT32, 1),
+        PointField("intensity", 12, PointField.FLOAT32, 1),
+    ]
+
+    header = Header()
+    header.frame_id = "base_link"
+    header.stamp = rospy.Time.now()
+
+    # concentric waves
+    x, y = np.meshgrid(np.linspace(-2, 2, width), np.linspace(-2, 2, height))
+    z = 0.2 * np.sin(3 * np.sqrt(x**2 + y**2) - t)
+    points = np.array([x, y, z, z]).reshape(4, -1).T
+
+    return point_cloud2.create_cloud(header, fields, points)
+
+
+if __name__ == "__main__":
+    rospy.init_node("send_tf_v2")
+
+    # transform identical to rot
+    tf_static = TransformStamped()
+    tf_static.header.stamp = rospy.Time.now()
+    tf_static.header.frame_id = "rot"
+    tf_static.child_frame_id = "rot2"
+    tf_static.transform.rotation.w = 1
+    br_static = tf2_ros.StaticTransformBroadcaster()
+    br_static.sendTransform(tf_static)
+
+    br = tf2_ros.TransformBroadcaster()
+    fast_pub = rospy.Publisher("fast", PointCloud2, queue_size=10)
+    slow_pub = rospy.Publisher("slow", PointCloud2, queue_size=1)
+    old = create_pc(0.0)
+
+    # base_link moving linearly back and forth
+    tf_base = TransformStamped()
+    tf_base.header.frame_id = "map"
+    tf_base.child_frame_id = "base_link"
+    tf_base.transform.rotation.w = 1
+
+    # transform rotating about base_link
+    tf_rot = TransformStamped()
+    tf_rot.header.frame_id = "base_link"
+    tf_rot.child_frame_id = "rot"
+    tf_rot.transform.rotation.w = 1
+
+    tf_slow = TransformStamped()
+    tf_slow.header.frame_id = "base_link"
+    tf_slow.child_frame_id = "slow"
+    tf_slow.transform.translation.z = 1
+    tf_slow.transform.rotation.w = 1
+
+    fast_rate = rospy.Rate(100)
+    slow_rate = rospy.Rate(1)
+    frequency = 0.1
+    radius = 2
+    while not rospy.is_shutdown():
+        tf_base.header.stamp = rospy.Time.now()
+        t = 2 * math.pi * tf_base.header.stamp.to_sec() * frequency
+        tf_base.transform.translation.x = 10 * math.cos(t)
+        br.sendTransform(tf_base)
+
+        tf_rot.header.stamp = tf_base.header.stamp
+        tf_rot.transform.translation.x = radius * math.cos(2 * t)
+        tf_rot.transform.translation.y = radius * math.sin(2 * t)
+        tf_rot.transform.translation.z = 0
+        br.sendTransform(tf_rot)
+
+        pc = create_pc(2 * t)
+        fast_pub.publish(pc)
+        fast_rate.sleep()
+        print(".", end="")
+        if slow_rate.remaining() < rospy.Duration():
+            # publish slow TF
+            tf_slow.header.stamp = old.header.stamp
+            br.sendTransform(tf_slow)
+            # re-publish old PC
+            slow_pub.publish(old)
+            old = pc  # store current PC
+            slow_rate.last_time = rospy.Time.now()
+            print("+")
diff -pruN 1.14.14+dfsg-2/src/test/tf_sync_display.rviz 1.14.15+dfsg-3/src/test/tf_sync_display.rviz
--- 1.14.14+dfsg-2/src/test/tf_sync_display.rviz	1970-01-01 00:00:00.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/tf_sync_display.rviz	2022-08-01 08:39:42.000000000 +0000
@@ -0,0 +1,227 @@
+Panels:
+  - Class: rviz/Displays
+    Help Height: 128
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /Global Options1
+        - /TF1/Frames1
+        - /fast1
+      Splitter Ratio: 0.5
+    Tree Height: 714
+  - Class: rviz/Selection
+    Name: Selection
+  - Class: rviz/Tool Properties
+    Expanded:
+      - /2D Pose Estimate1
+      - /2D Nav Goal1
+      - /Publish Point1
+    Name: Tool Properties
+    Splitter Ratio: 0.5886790156364441
+  - Class: rviz/Views
+    Expanded:
+      - /Current View1
+    Name: Views
+    Splitter Ratio: 0.5
+  - Class: rviz/Time
+    Name: Time
+    SyncMode: 2
+    SyncSource: fast
+Preferences:
+  PromptSaveOnExit: true
+Toolbars:
+  toolButtonStyle: 2
+Visualization Manager:
+  Class: ""
+  Displays:
+    - Alpha: 1
+      Class: rviz/Axes
+      Enabled: true
+      Length: 1
+      Name: BaseLink
+      Radius: 0.10000000149011612
+      Reference Frame: base_link
+      Show Trail: false
+      Value: true
+    - Alpha: 1
+      Class: rviz/Axes
+      Enabled: true
+      Length: 1
+      Name: Rot
+      Radius: 0.10000000149011612
+      Reference Frame: rot
+      Show Trail: false
+      Value: true
+    - Class: rviz/TF
+      Enabled: false
+      Frame Timeout: 15
+      Frames:
+        All Enabled: true
+      Marker Alpha: 1
+      Marker Scale: 1
+      Name: TF
+      Show Arrows: true
+      Show Axes: true
+      Show Names: true
+      Tree:
+        {}
+      Update Interval: 0
+      Value: false
+    - Alpha: 0.5
+      Cell Size: 1
+      Class: rviz/Grid
+      Color: 160; 160; 164
+      Enabled: false
+      Line Style:
+        Line Width: 0.029999999329447746
+        Value: Lines
+      Name: Grid
+      Normal Cell Count: 0
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Plane: XY
+      Plane Cell Count: 10
+      Reference Frame: <Fixed Frame>
+      Value: false
+    - Alpha: 1
+      Class: rviz/Axes
+      Enabled: true
+      Length: 1
+      Name: Rot2
+      Radius: 0.10000000149011612
+      Reference Frame: rot
+      Show Trail: false
+      Value: true
+    - Alpha: 1
+      Autocompute Intensity Bounds: true
+      Autocompute Value Bounds:
+        Max Value: 10
+        Min Value: -10
+        Value: true
+      Axis: Z
+      Channel Name: intensity
+      Class: rviz/PointCloud2
+      Color: 255; 255; 255
+      Color Transformer: Intensity
+      Decay Time: 0
+      Enabled: true
+      Invert Rainbow: false
+      Max Color: 255; 255; 255
+      Min Color: 0; 0; 0
+      Name: fast
+      Position Transformer: XYZ
+      Queue Size: 10
+      Selectable: true
+      Size (Pixels): 2
+      Size (m): 0.009999999776482582
+      Style: Points
+      Topic: /fast
+      Unreliable: false
+      Use Fixed Frame: true
+      Use rainbow: true
+      Value: true
+    - Alpha: 1
+      Autocompute Intensity Bounds: true
+      Autocompute Value Bounds:
+        Max Value: 10
+        Min Value: -10
+        Value: true
+      Axis: Z
+      Channel Name: intensity
+      Class: rviz/PointCloud2
+      Color: 255; 255; 255
+      Color Transformer: Intensity
+      Decay Time: 0
+      Enabled: false
+      Invert Rainbow: false
+      Max Color: 255; 255; 255
+      Min Color: 0; 0; 0
+      Name: slow
+      Position Transformer: XYZ
+      Queue Size: 10
+      Selectable: true
+      Size (Pixels): 3
+      Size (m): 0.009999999776482582
+      Style: Flat Squares
+      Topic: /slow
+      Unreliable: false
+      Use Fixed Frame: true
+      Use rainbow: true
+      Value: false
+    - Alpha: 1
+      Class: rviz/Axes
+      Enabled: false
+      Length: 1
+      Name: Slow
+      Radius: 0.10000000149011612
+      Reference Frame: slow
+      Show Trail: false
+      Value: false
+  Enabled: true
+  Global Options:
+    Background Color: 48; 48; 48
+    Default Light: true
+    Fixed Frame: map
+    Frame Rate: 30
+  Name: root
+  Tools:
+    - Class: rviz/Interact
+      Hide Inactive Objects: true
+    - Class: rviz/MoveCamera
+    - Class: rviz/Select
+    - Class: rviz/FocusCamera
+    - Class: rviz/Measure
+    - Class: rviz/SetInitialPose
+      Theta std deviation: 0.2617993950843811
+      Topic: /initialpose
+      X std deviation: 0.5
+      Y std deviation: 0.5
+    - Class: rviz/SetGoal
+      Topic: /move_base_simple/goal
+    - Class: rviz/PublishPoint
+      Single click: true
+      Topic: /clicked_point
+  Value: true
+  Views:
+    Current:
+      Class: rviz/Orbit
+      Distance: 18.42949676513672
+      Enable Stereo Rendering:
+        Stereo Eye Separation: 0.05999999865889549
+        Stereo Focal Distance: 1
+        Swap Stereo Eyes: false
+        Value: false
+      Field of View: 0.7853981852531433
+      Focal Point:
+        X: -7.236814975738525
+        Y: -5.540378570556641
+        Z: -5.354213714599609
+      Focal Shape Fixed Size: false
+      Focal Shape Size: 0.05000000074505806
+      Invert Z Axis: false
+      Name: Current View
+      Near Clip Distance: 0.009999999776482582
+      Pitch: 0.5453979969024658
+      Target Frame: base_link
+      Yaw: 0.6553990840911865
+    Saved: ~
+Window Geometry:
+  Displays:
+    collapsed: false
+  Height: 1061
+  Hide Left Dock: false
+  Hide Right Dock: false
+  QMainWindow State: 000000ff00000000fd00000004000000000000015600000387fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000387000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000387fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000387000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000034100fffffffb0000000800540069006d006501000000000000045000000000000000000000050f0000038700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Selection:
+    collapsed: false
+  Time:
+    collapsed: false
+  Tool Properties:
+    collapsed: false
+  Views:
+    collapsed: false
+  Width: 1920
+  X: 2560
+  Y: 0
diff -pruN 1.14.14+dfsg-2/src/test/tf_sync_frame.rviz 1.14.15+dfsg-3/src/test/tf_sync_frame.rviz
--- 1.14.14+dfsg-2/src/test/tf_sync_frame.rviz	1970-01-01 00:00:00.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/tf_sync_frame.rviz	2022-08-01 08:39:42.000000000 +0000
@@ -0,0 +1,160 @@
+Panels:
+  - Class: rviz/Displays
+    Help Height: 78
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /Global Options1
+      Splitter Ratio: 0.5
+    Tree Height: 839
+  - Class: rviz/Selection
+    Name: Selection
+  - Class: rviz/Tool Properties
+    Expanded:
+      - /2D Pose Estimate1
+      - /2D Nav Goal1
+      - /Publish Point1
+    Name: Tool Properties
+    Splitter Ratio: 0.5886790156364441
+  - Class: rviz/Views
+    Expanded:
+      - /Current View1
+    Name: Views
+    Splitter Ratio: 0.5
+  - Class: rviz/Time
+    Name: Time
+    SyncMode: 1
+    SyncSource: ""
+Preferences:
+  PromptSaveOnExit: true
+Toolbars:
+  toolButtonStyle: 2
+Visualization Manager:
+  Class: ""
+  Displays:
+    - Alpha: 1
+      Class: rviz/Axes
+      Enabled: true
+      Length: 1
+      Name: BaseLink
+      Radius: 0.10000000149011612
+      Reference Frame: base_link
+      Show Trail: false
+      Value: true
+    - Class: rviz/TF
+      Enabled: false
+      Frame Timeout: 15
+      Frames:
+        All Enabled: true
+      Marker Alpha: 1
+      Marker Scale: 1
+      Name: TF
+      Show Arrows: true
+      Show Axes: true
+      Show Names: true
+      Tree:
+        {}
+      Update Interval: 0
+      Value: false
+    - Alpha: 0.5
+      Cell Size: 1
+      Class: rviz/Grid
+      Color: 160; 160; 164
+      Enabled: false
+      Line Style:
+        Line Width: 0.029999999329447746
+        Value: Lines
+      Name: Grid
+      Normal Cell Count: 0
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Plane: XY
+      Plane Cell Count: 10
+      Reference Frame: <Fixed Frame>
+      Value: false
+    - Alpha: 1
+      Class: rviz/Axes
+      Enabled: true
+      Length: 1
+      Name: Rot
+      Radius: 0.10000000149011612
+      Reference Frame: rot
+      Show Trail: false
+      Value: true
+    - Alpha: 1
+      Class: rviz/Axes
+      Enabled: true
+      Length: 1
+      Name: Rot2
+      Radius: 0.10000000149011612
+      Reference Frame: rot2
+      Show Trail: false
+      Value: true
+  Enabled: true
+  Global Options:
+    Background Color: 48; 48; 48
+    Default Light: true
+    Fixed Frame: map
+    Frame Rate: 30
+  Name: root
+  Tools:
+    - Class: rviz/Interact
+      Hide Inactive Objects: true
+    - Class: rviz/MoveCamera
+    - Class: rviz/Select
+    - Class: rviz/FocusCamera
+    - Class: rviz/Measure
+    - Class: rviz/SetInitialPose
+      Theta std deviation: 0.2617993950843811
+      Topic: /initialpose
+      X std deviation: 0.5
+      Y std deviation: 0.5
+    - Class: rviz/SetGoal
+      Topic: /move_base_simple/goal
+    - Class: rviz/PublishPoint
+      Single click: true
+      Topic: /clicked_point
+  Value: true
+  Views:
+    Current:
+      Class: rviz/Orbit
+      Distance: 10.879761695861816
+      Enable Stereo Rendering:
+        Stereo Eye Separation: 0.05999999865889549
+        Stereo Focal Distance: 1
+        Swap Stereo Eyes: false
+        Value: false
+      Field of View: 0.7853981852531433
+      Focal Point:
+        X: 0
+        Y: 0
+        Z: 0
+      Focal Shape Fixed Size: false
+      Focal Shape Size: 0.05000000074505806
+      Invert Z Axis: false
+      Name: Current View
+      Near Clip Distance: 0.009999999776482582
+      Pitch: 0.7853981852531433
+      Target Frame: base_link
+      Yaw: 0.7853981852531433
+    Saved: ~
+Window Geometry:
+  Displays:
+    collapsed: false
+  Height: 1136
+  Hide Left Dock: false
+  Hide Right Dock: false
+  QMainWindow State: 000000ff00000000fd000000040000000000000156000003d2fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000003d2000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003d2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000003d2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007380000003efc0100000002fb0000000800540069006d00650100000000000007380000031200fffffffb0000000800540069006d00650100000000000004500000000000000000000004c7000003d200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Selection:
+    collapsed: false
+  Time:
+    collapsed: false
+  Tool Properties:
+    collapsed: false
+  Views:
+    collapsed: false
+  Width: 1848
+  X: 47
+  Y: 25
diff -pruN 1.14.14+dfsg-2/src/test/two_render_widgets.cpp 1.14.15+dfsg-3/src/test/two_render_widgets.cpp
--- 1.14.14+dfsg-2/src/test/two_render_widgets.cpp	2022-02-12 10:42:16.000000000 +0000
+++ 1.14.15+dfsg-3/src/test/two_render_widgets.cpp	2022-08-01 08:39:42.000000000 +0000
@@ -35,11 +35,11 @@
 #include <QVBoxLayout>
 #include <QPushButton>
 
-#include <OGRE/OgreCamera.h>
-#include <OGRE/OgreEntity.h>
-#include <OGRE/OgreRenderWindow.h>
-#include <OGRE/OgreSceneNode.h>
-#include <OGRE/OgreViewport.h>
+#include <OgreCamera.h>
+#include <OgreEntity.h>
+#include <OgreRenderWindow.h>
+#include <OgreSceneNode.h>
+#include <OgreViewport.h>
 
 using namespace rviz;
 
