From 39e18133d9e18216ab94898825f57e5272e02bc8 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Thu, 4 Jun 2020 20:59:45 -0700 Subject: [PATCH 1/7] restore compatibility with older Qt versions (#561) Signed-off-by: Dirk Thomas --- .../view_controllers/view_controller_test_fixture.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp index 1b2a0b4bc..5b997b8d0 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp @@ -101,6 +101,7 @@ class ViewControllerTestFixture : public DisplayTestFixture auto global_point = QPointF(); auto pixel_delta = QPoint(); auto angle_delta = QPoint(delta, 0); +#if (QT_VERSION >= QT_VERSION_CHECK(5, 14, 0)) auto mouseEvent = new QWheelEvent( point, global_point, @@ -110,6 +111,10 @@ class ViewControllerTestFixture : public DisplayTestFixture Qt::NoModifier, Qt::NoScrollPhase, false); +#else + auto mouseEvent = new QWheelEvent( + point, delta, Qt::NoButton, Qt::NoModifier, Qt::Orientation::Horizontal); +#endif return {render_panel_.get(), mouseEvent, 0, 0}; } From 0dc0f5bb52f57b57b631974241319ea80dc67373 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Mon, 8 Jun 2020 14:52:31 -0400 Subject: [PATCH 2/7] Suppress warnings when building with older Qt versions. (#562) Signed-off-by: Chris Lalancette --- .../view_controllers/view_controller_test_fixture.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp index 5b997b8d0..599e8596f 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp @@ -98,10 +98,10 @@ class ViewControllerTestFixture : public DisplayTestFixture rviz_common::ViewportMouseEvent generateMouseWheelEvent(int delta) { auto point = QPointF(); +#if (QT_VERSION >= QT_VERSION_CHECK(5, 14, 0)) auto global_point = QPointF(); auto pixel_delta = QPoint(); auto angle_delta = QPoint(delta, 0); -#if (QT_VERSION >= QT_VERSION_CHECK(5, 14, 0)) auto mouseEvent = new QWheelEvent( point, global_point, From cd756b538b97dbac4a4458a2f4ed9416d1ed9921 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Fri, 12 Jun 2020 09:15:02 -0400 Subject: [PATCH 3/7] Don't try to moc generate env_config.hpp file. (#550) This removes one more warning from rviz_common builds. Signed-off-by: Chris Lalancette --- rviz_common/CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/rviz_common/CMakeLists.txt b/rviz_common/CMakeLists.txt index b207044a4..506533f41 100644 --- a/rviz_common/CMakeLists.txt +++ b/rviz_common/CMakeLists.txt @@ -70,7 +70,6 @@ configure_file(src/rviz_common/env_config.cpp.in ${ENV_CONFIG_CPP} @ONLY) # These need to be added in the add_library() call set(rviz_common_headers_to_moc - ${ENV_CONFIG_HPP} src/rviz_common/add_display_dialog.hpp src/rviz_common/help_panel.hpp include/rviz_common/properties/enum_property.hpp @@ -206,7 +205,6 @@ set(rviz_common_source_files src/rviz_common/interaction/selection_renderer.cpp src/rviz_common/interaction/view_picker.cpp src/rviz_common/splash_screen.cpp - # src/rviz_common/time_panel.cpp src/rviz_common/transformation/identity_frame_transformer.cpp src/rviz_common/tool_manager.cpp src/rviz_common/tool_properties_panel.cpp From b255e54f28dbb11cca37bfdc3f75d38469a6eddd Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Wed, 17 Jun 2020 10:50:49 -0700 Subject: [PATCH 4/7] rewrite hack to avoid CMake warning with assimp 5.0.1 and older, apply cross platform (#565) Signed-off-by: Dirk Thomas --- rviz_assimp_vendor/CMakeLists.txt | 71 +------------------ .../rviz_assimp_vendor-extras.cmake.in | 27 +------ 2 files changed, 6 insertions(+), 92 deletions(-) diff --git a/rviz_assimp_vendor/CMakeLists.txt b/rviz_assimp_vendor/CMakeLists.txt index fa125307c..77dc8526b 100644 --- a/rviz_assimp_vendor/CMakeLists.txt +++ b/rviz_assimp_vendor/CMakeLists.txt @@ -52,77 +52,12 @@ macro(build_assimp) ) endmacro() -# Copy and fix the assimp config files on Ubuntu, in order to suppress a warning. -# This should be removed once upstream is updated to assimp-0.5.1, see: +# Override ON so that the following CMake logic in assimp 5.0.1 and older +# doesn't result in a CMake warning: if(ON) # https://github.com/ros2/rviz/issues/524 # https://bugs.launchpad.net/ubuntu/+source/assimp/+bug/1869405 -### BEGIN HACKS -set(IS_UBUNTU_FOCAL FALSE) -if(UNIX AND NOT APPLE) - find_program(LSB_RELEASE_EXEC lsb_release) - if(EXISTS "${LSB_RELEASE_EXEC}") - execute_process(COMMAND ${LSB_RELEASE_EXEC} -is - OUTPUT_VARIABLE LSB_RELEASE_ID_SHORT - OUTPUT_STRIP_TRAILING_WHITESPACE - ) - execute_process(COMMAND ${LSB_RELEASE_EXEC} -sr - OUTPUT_VARIABLE LSB_RELEASE_RELEASE_SHORT - OUTPUT_STRIP_TRAILING_WHITESPACE - ) - else() - set(LSB_RELEASE_ID_SHORT "Unknown") - set(LSB_RELEASE_RELEASE_SHORT "Unknown") - endif() - - if(${LSB_RELEASE_ID_SHORT} STREQUAL "Ubuntu" AND ${LSB_RELEASE_RELEASE_SHORT} STREQUAL "20.04") - set(IS_UBUNTU_FOCAL TRUE) - endif() -endif() - -if(IS_UBUNTU_FOCAL) - file(GLOB_RECURSE assimp_target_files "/usr/lib/*/cmake/assimp-5.0/assimpTargets.cmake") - list(LENGTH assimp_target_files assimp_target_files_len) - if(assimp_target_files_len EQUAL 0) - message(FATAL_ERROR "failed to find assimpTargets.cmake as expected") - endif() - if(NOT assimp_target_files_len EQUAL 1) - message(FATAL_ERROR "found multiple assimpTargets.cmake files, unexpectedly") - endif() - list(GET assimp_target_files 0 assimp_target_file) +set(ON 1) - get_filename_component(assimp_target_dir "${assimp_target_file}" DIRECTORY) - set(new_assimp_target_dir "${CMAKE_CURRENT_BINARY_DIR}/assimp-0.5") - - file(READ "${assimp_target_dir}/assimpTargets.cmake" assimp_targets_content) - string(REPLACE - "if(ON)" - "set(WORKAROUND ON)\nif(WORKAROUND)" - assimp_targets_content - ${assimp_targets_content}) - file(WRITE "${new_assimp_target_dir}/assimpTargets.cmake" "${assimp_targets_content}") - file(READ "${assimp_target_dir}/assimpTargets-release.cmake" assimp_targets_content) - string(REPLACE - "if(ON)" - "set(WORKAROUND ON)\nif(WORKAROUND)" - assimp_targets_content - ${assimp_targets_content}) - file(WRITE "${new_assimp_target_dir}/assimpTargets-release.cmake" "${assimp_targets_content}") - file( - COPY "${assimp_target_dir}/assimp-config.cmake" - DESTINATION "${new_assimp_target_dir}") - file( - COPY "${assimp_target_dir}/assimp-config-version.cmake" - DESTINATION "${new_assimp_target_dir}") - set(assimp_DIR "${new_assimp_target_dir}") - - install( - DIRECTORY - ${new_assimp_target_dir}/ - DESTINATION - ${CMAKE_INSTALL_PREFIX}/opt/rviz_assimp_vendor_custom_config - ) -endif() -### END HACKS find_package(assimp QUIET) if(NOT assimp_FOUND OR "${assimp_VERSION}" VERSION_LESS 4.1.0) diff --git a/rviz_assimp_vendor/rviz_assimp_vendor-extras.cmake.in b/rviz_assimp_vendor/rviz_assimp_vendor-extras.cmake.in index 971971563..8e41fe662 100644 --- a/rviz_assimp_vendor/rviz_assimp_vendor-extras.cmake.in +++ b/rviz_assimp_vendor/rviz_assimp_vendor-extras.cmake.in @@ -1,29 +1,8 @@ -# Use custom CMake config files for assimp on Ubuntu to work around a cmake warning. -# This should be removed once upstream is updated to assimp-0.5.1, see: +# Override ON so that the following CMake logic in assimp 5.0.1 and older +# doesn't result in a CMake warning: if(ON) # https://github.com/ros2/rviz/issues/524 # https://bugs.launchpad.net/ubuntu/+source/assimp/+bug/1869405 -### BEGIN HACKS -set(IS_UBUNTU FALSE) -if(UNIX AND NOT APPLE) - find_program(LSB_RELEASE_EXEC lsb_release) - if(EXISTS "${LSB_RELEASE_EXEC}") - execute_process(COMMAND ${LSB_RELEASE_EXEC} -is - OUTPUT_VARIABLE LSB_RELEASE_ID_SHORT - OUTPUT_STRIP_TRAILING_WHITESPACE - ) - else() - set(LSB_RELEASE_ID_SHORT "Unknown") - endif() - - if(${LSB_RELEASE_ID_SHORT} STREQUAL "Ubuntu") - set(IS_UBUNTU TRUE) - endif() -endif() - -if(IS_UBUNTU) - set(assimp_DIR "${@PROJECT_NAME@_DIR}/../../../opt/rviz_assimp_vendor_custom_config") -endif() -### END HACKS +set(ON 1) find_package(assimp QUIET) From 0ba40aeab2155eed0a5f6aa9d5bb45968707ebc9 Mon Sep 17 00:00:00 2001 From: ymd-stella <7959916+ymd-stella@users.noreply.github.com> Date: Thu, 18 Jun 2020 04:21:53 +0900 Subject: [PATCH 5/7] Use dedicated TransformListener thread (#551) Signed-off-by: ymd-stella --- .../transformation/tf_wrapper.cpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/rviz_default_plugins/src/rviz_default_plugins/transformation/tf_wrapper.cpp b/rviz_default_plugins/src/rviz_default_plugins/transformation/tf_wrapper.cpp index a499d4c08..eb8a44a3e 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/transformation/tf_wrapper.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/transformation/tf_wrapper.cpp @@ -123,8 +123,16 @@ void TFWrapper::initialize( bool using_dedicated_thread) { initializeBuffer(clock, rviz_ros_node.lock()->get_raw_node(), using_dedicated_thread); - tf_listener_ = std::make_shared( - *buffer_, rviz_ros_node.lock()->get_raw_node(), false); + if (using_dedicated_thread) { + // TODO(pull/551): The TransformListener needs very quick spinning so it uses its own node + // here. Remove this in favor of a multithreaded spinner and ensure that the listener callback + // queue does not fill up. + tf_listener_ = std::make_shared( + *buffer_, true); + } else { + tf_listener_ = std::make_shared( + *buffer_, rviz_ros_node.lock()->get_raw_node(), false); + } } void TFWrapper::initializeBuffer( From 68cecc62fb08acbe8a6acc47dc357572c3286a8b Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Wed, 17 Jun 2020 13:22:37 -0700 Subject: [PATCH 6/7] restore alphabetical include order (#563) Signed-off-by: Karsten Knese --- rviz_common/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rviz_common/CMakeLists.txt b/rviz_common/CMakeLists.txt index 506533f41..f5bc05bac 100644 --- a/rviz_common/CMakeLists.txt +++ b/rviz_common/CMakeLists.txt @@ -38,8 +38,8 @@ find_package(rviz_ogre_vendor REQUIRED) find_package(Qt5 REQUIRED COMPONENTS Widgets) -find_package(pluginlib REQUIRED) find_package(geometry_msgs REQUIRED) +find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(resource_retriever REQUIRED) find_package(rviz_assimp_vendor REQUIRED) @@ -270,8 +270,8 @@ target_compile_definitions(rviz_common PRIVATE "RVIZ_COMMON_BUILDING_LIBRARY") ament_export_targets(rviz_common) ament_export_dependencies( rviz_rendering - pluginlib geometry_msgs + pluginlib rclcpp sensor_msgs std_msgs From 686f593a7cdf8eef76325e3614a08e1de0e0b143 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Thu, 18 Jun 2020 15:33:55 -0400 Subject: [PATCH 7/7] Don't install test header files in rviz_rendering. (#564) * Don't install test header files in rviz_rendering. This change started as a relatively simple try at not installing test includes when installing rviz_rendering. As you can see, it ballooned into quite a large change, so here is an explanation of why. We shouldn't install test include header files when installing the package; that just ends up on the end user system, and is a non-supported API. Worse, we don't want to compile test code in our main library. Yet rviz_rendering is currently doing both of these things. Unfortunately, it is somewhat tricky to make that code and header file private. The problem is that that test code is used in rviz_rendering, rviz_common, rviz_default_plugins, and rviz_rendering_tests. One solution might be to extract that test code into its own package, and then have all of the other packages depend on it. The problem is that that test package would both be depended on by rviz_rendering (for tests), and depends itself on rviz_rendering (for its functionality), creating a dependency loop. The solution I opted for here is to copy the test code into the appropriate packages. This leads to some duplication of functionality, but it effectively breaks the dependency loop and succeeds in eliminating the test code from our installed library. Signed-off-by: Chris Lalancette --- rviz_common/CMakeLists.txt | 2 + rviz_common/test/display_context_fixture.cpp | 4 +- rviz_common/test/display_context_fixture.hpp | 4 +- rviz_common/test/ogre_testing_environment.cpp | 56 +++++ rviz_common/test/ogre_testing_environment.hpp | 51 ++++ rviz_default_plugins/CMakeLists.txt | 18 +- .../displays/display_test_fixture.cpp | 4 +- .../displays/display_test_fixture.hpp | 4 +- .../grid_cells/grid_cells_display_test.cpp | 11 +- .../displays/image/image_display_test.cpp | 8 +- .../displays/image/ros_image_texture_test.cpp | 8 +- .../displays/map/map_display_test.cpp | 15 +- .../displays/marker/marker_common_test.cpp | 65 +++-- .../marker/markers/arrow_marker_test.cpp | 2 +- .../marker/markers/line_marker_test.cpp | 26 +- .../marker/markers/markers_test_fixture.hpp | 2 +- .../markers/mesh_resource_marker_test.cpp | 23 +- .../marker/markers/points_marker_test.cpp | 11 +- .../marker/markers/shape_marker_test.cpp | 15 +- .../markers/text_view_facing_marker_test.cpp | 9 +- .../markers/triangle_list_marker_test.cpp | 9 +- .../odometry/odometry_display_test.cpp | 43 ++-- .../displays/path/path_display_test.cpp | 31 ++- .../point/point_stamped_display_test.cpp | 7 +- .../pointcloud/point_cloud_common_test.cpp | 15 +- .../point_cloud_selection_handler_test.cpp | 7 +- .../xyz_pc_transformer_test.cpp | 2 +- .../pose_array/pose_array_display_test.cpp | 34 +-- .../displays/range/range_display_test.cpp | 11 +- .../displays/tf/frame_info_test.cpp | 7 +- .../ogre_testing_environment.cpp | 63 +++++ .../ogre_testing_environment.hpp | 55 +++++ .../rviz_default_plugins/robot/robot_test.cpp | 10 +- .../scene_graph_introspection.cpp | 233 ++++++++++++++++++ ...lper.hpp => scene_graph_introspection.hpp} | 75 +++++- .../scene_graph_introspection_helper.cpp | 87 ------- .../tools/measure/measure_tool_test.cpp | 9 +- .../tools/pose/pose_tool_test.cpp | 11 +- .../fps/fps_view_controller_test.cpp | 2 +- .../orbit/orbit_view_controller_test.cpp | 2 +- .../ortho/ortho_view_controller_test.cpp | 2 +- .../xy_orbit_view_controller_test.cpp | 2 +- rviz_rendering/CMakeLists.txt | 20 +- .../rviz_rendering/render_system.hpp | 1 + .../ogre_render_window_impl.cpp | 2 +- .../ogre_render_window_impl.hpp | 2 +- .../src/rviz_rendering/render_system.cpp | 2 +- .../objects/billboard_line_test.cpp | 2 +- .../objects/covariance_visual_test.cpp | 4 +- .../test/rviz_rendering/objects/grid_test.cpp | 2 +- .../test/rviz_rendering/objects/line_test.cpp | 2 +- .../objects/movable_text_test.cpp | 2 +- .../objects/point_cloud_renderable_test.cpp | 2 +- .../objects/point_cloud_test.cpp | 2 +- .../objects/wrench_visual_test.cpp | 4 +- .../ogre_testing_environment.cpp | 23 +- .../ogre_testing_environment.hpp | 21 +- .../scene_graph_introspection.cpp | 62 +---- .../scene_graph_introspection.hpp | 31 --- rviz_rendering_tests/CMakeLists.txt | 1 + .../test/mesh_loader_test.cpp | 8 +- .../test/ogre_testing_environment.cpp | 56 +++++ .../test/ogre_testing_environment.hpp | 51 ++++ 63 files changed, 895 insertions(+), 460 deletions(-) create mode 100644 rviz_common/test/ogre_testing_environment.cpp create mode 100644 rviz_common/test/ogre_testing_environment.hpp create mode 100644 rviz_default_plugins/test/rviz_default_plugins/ogre_testing_environment.cpp create mode 100644 rviz_default_plugins/test/rviz_default_plugins/ogre_testing_environment.hpp create mode 100644 rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection.cpp rename rviz_default_plugins/test/rviz_default_plugins/{scene_graph_introspection_helper.hpp => scene_graph_introspection.hpp} (54%) delete mode 100644 rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection_helper.cpp rename rviz_rendering/{src => include}/rviz_rendering/render_system.hpp (99%) rename rviz_rendering/{include => }/test/rviz_rendering/ogre_testing_environment.hpp (82%) rename rviz_rendering/{include => }/test/rviz_rendering/scene_graph_introspection.hpp (80%) create mode 100644 rviz_rendering_tests/test/ogre_testing_environment.cpp create mode 100644 rviz_rendering_tests/test/ogre_testing_environment.hpp diff --git a/rviz_common/CMakeLists.txt b/rviz_common/CMakeLists.txt index f5bc05bac..5cb81889f 100644 --- a/rviz_common/CMakeLists.txt +++ b/rviz_common/CMakeLists.txt @@ -410,6 +410,7 @@ if(BUILD_TESTING) test/interaction/mock_selection_renderer.hpp test/interaction/selection_test_fixture.hpp test/display_context_fixture.cpp + test/ogre_testing_environment.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET selection_manager_test) target_link_libraries(selection_manager_test @@ -423,6 +424,7 @@ if(BUILD_TESTING) test/interaction/selection_handler_test.cpp test/interaction/selection_test_fixture.hpp test/display_context_fixture.cpp + test/ogre_testing_environment.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET selection_handler_test) target_link_libraries(selection_handler_test diff --git a/rviz_common/test/display_context_fixture.cpp b/rviz_common/test/display_context_fixture.cpp index ba9109165..1d7acb3fd 100644 --- a/rviz_common/test/display_context_fixture.cpp +++ b/rviz_common/test/display_context_fixture.cpp @@ -37,7 +37,7 @@ void DisplayContextFixture::SetUpTestCase() { - testing_environment_ = std::make_shared(); + testing_environment_ = std::make_shared(); testing_environment_->setUpOgreTestEnvironment(); scene_manager_ = Ogre::Root::getSingletonPtr()->createSceneManager(); @@ -66,5 +66,5 @@ void DisplayContextFixture::TearDownTestCase() } Ogre::SceneManager * DisplayContextFixture::scene_manager_ = nullptr; -std::shared_ptr +std::shared_ptr DisplayContextFixture::testing_environment_ = nullptr; diff --git a/rviz_common/test/display_context_fixture.hpp b/rviz_common/test/display_context_fixture.hpp index 4a03ac0c1..afb5b2352 100644 --- a/rviz_common/test/display_context_fixture.hpp +++ b/rviz_common/test/display_context_fixture.hpp @@ -43,7 +43,7 @@ #include "rclcpp/clock.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "ogre_testing_environment.hpp" #include "mock_display_context.hpp" #include "mock_window_manager_interface.hpp" @@ -59,7 +59,7 @@ class DisplayContextFixture : public testing::Test static void TearDownTestCase(); - static std::shared_ptr testing_environment_; + static std::shared_ptr testing_environment_; static Ogre::SceneManager * scene_manager_; std::shared_ptr context_; diff --git a/rviz_common/test/ogre_testing_environment.cpp b/rviz_common/test/ogre_testing_environment.cpp new file mode 100644 index 000000000..3e6459c5b --- /dev/null +++ b/rviz_common/test/ogre_testing_environment.cpp @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2017, Bosch Software Innovations GmbH. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "ogre_testing_environment.hpp" + +#include + +#include + +#include "rviz_rendering/render_system.hpp" + +namespace rviz_common +{ + +void OgreTestingEnvironment::setUpOgreTestEnvironment(bool debug) +{ + if (!debug) { + const std::string & name = ""; + auto lm = new Ogre::LogManager(); + lm->createLog(name, false, debug, true); + } + setUpRenderSystem(); +} + +void OgreTestingEnvironment::setUpRenderSystem() +{ + rviz_rendering::RenderSystem::get(); +} + +} // end namespace rviz_common diff --git a/rviz_common/test/ogre_testing_environment.hpp b/rviz_common/test/ogre_testing_environment.hpp new file mode 100644 index 000000000..6837217a1 --- /dev/null +++ b/rviz_common/test/ogre_testing_environment.hpp @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2017, Bosch Software Innovations GmbH. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef OGRE_TESTING_ENVIRONMENT_HPP_ +#define OGRE_TESTING_ENVIRONMENT_HPP_ + +namespace rviz_common +{ +class OgreTestingEnvironment +{ +public: + /** + * Set up a testing environment to run tests needing Ogre. + * + * @param: bool debug, if true, all logging of Ogre is send to std::out, if false no logging + * occurs. Since the logging pollutes the test output, it defaults to false + */ + void setUpOgreTestEnvironment(bool debug = false); + + void setUpRenderSystem(); +}; + +} // namespace rviz_common + +#endif // OGRE_TESTING_ENVIRONMENT_HPP_ diff --git a/rviz_default_plugins/CMakeLists.txt b/rviz_default_plugins/CMakeLists.txt index 3704fa3a5..f6c48b6c1 100644 --- a/rviz_default_plugins/CMakeLists.txt +++ b/rviz_default_plugins/CMakeLists.txt @@ -337,6 +337,8 @@ if(BUILD_TESTING) ament_find_gmock() add_library(display_test_fixture test/rviz_default_plugins/displays/display_test_fixture.cpp + test/rviz_default_plugins/ogre_testing_environment.cpp + test/rviz_default_plugins/scene_graph_introspection.cpp ) target_include_directories(display_test_fixture PRIVATE ${GMOCK_INCLUDE_DIRS} ${TEST_INCLUDE_DIRS}) target_link_libraries(display_test_fixture ${GMOCK_LIBRARIES}) @@ -351,7 +353,6 @@ if(BUILD_TESTING) ament_add_gmock(fps_view_controller_test test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET fps_view_controller_test) target_include_directories(fps_view_controller_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -361,7 +362,6 @@ if(BUILD_TESTING) ament_add_gmock(frame_info_test test/rviz_default_plugins/displays/tf/frame_info_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET frame_info_test) target_include_directories(frame_info_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -397,7 +397,6 @@ if(BUILD_TESTING) test/rviz_default_plugins/displays/marker/markers/triangle_list_marker_test.cpp test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.cpp test/rviz_default_plugins/displays/marker/marker_messages.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET marker_test) target_include_directories(marker_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -408,7 +407,6 @@ if(BUILD_TESTING) ament_add_gmock(marker_common_test test/rviz_default_plugins/displays/marker/marker_common_test.cpp test/rviz_default_plugins/displays/marker/marker_messages.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET marker_common_test) target_include_directories(marker_common_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -418,7 +416,6 @@ if(BUILD_TESTING) ament_add_gmock(map_display_test test/rviz_default_plugins/displays/map/map_display_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET map_display_test) target_include_directories(map_display_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -428,7 +425,6 @@ if(BUILD_TESTING) ament_add_gmock(measure_tool_test test/rviz_default_plugins/tools/measure/measure_tool_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET measure_tool_test) target_include_directories(measure_tool_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -438,7 +434,6 @@ if(BUILD_TESTING) ament_add_gmock(odometry_display_test test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET odometry_display_test) target_include_directories(odometry_display_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -458,7 +453,6 @@ if(BUILD_TESTING) ament_add_gmock(orbit_view_controller_test test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET orbit_view_controller_test) target_include_directories(orbit_view_controller_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -469,7 +463,6 @@ if(BUILD_TESTING) ament_add_gmock(ortho_view_controller_test test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET ortho_view_controller_test) target_include_directories(ortho_view_controller_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -488,7 +481,6 @@ if(BUILD_TESTING) ament_add_gmock(path_display_test test/rviz_default_plugins/displays/path/path_display_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET path_display_test) target_include_directories(path_display_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -511,7 +503,6 @@ if(BUILD_TESTING) test/rviz_default_plugins/pointcloud_messages.hpp test/rviz_default_plugins/pointcloud_messages.cpp test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET point_cloud_common_test) target_include_directories(point_cloud_common_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -546,7 +537,6 @@ if(BUILD_TESTING) ament_add_gmock(point_display_test test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET point_display_test) target_include_directories(point_display_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -556,7 +546,6 @@ if(BUILD_TESTING) ament_add_gmock(pose_array_display_test test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET pose_array_display_test) target_include_directories(pose_array_display_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -566,7 +555,6 @@ if(BUILD_TESTING) ament_add_gmock(pose_tool_test test/rviz_default_plugins/tools/pose/pose_tool_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET pose_tool_test) target_include_directories(pose_tool_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -576,7 +564,6 @@ if(BUILD_TESTING) ament_add_gmock(range_display_test test/rviz_default_plugins/displays/range/range_display_test.cpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET range_display_test) target_include_directories(range_display_test PUBLIC ${TEST_INCLUDE_DIRS}) @@ -616,7 +603,6 @@ if(BUILD_TESTING) ament_add_gmock(xy_orbit_view_controller_test test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp test/rviz_default_plugins/view_controllers/view_controller_test_fixture.hpp - test/rviz_default_plugins/scene_graph_introspection_helper.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET xy_orbit_view_controller_test) target_include_directories(xy_orbit_view_controller_test PUBLIC ${TEST_INCLUDE_DIRS}) diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.cpp index a8687ce21..eb6364b11 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.cpp @@ -37,7 +37,7 @@ void DisplayTestFixture::SetUpTestCase() { - testing_environment_ = std::make_shared(); + testing_environment_ = std::make_shared(); testing_environment_->setUpOgreTestEnvironment(); scene_manager_ = Ogre::Root::getSingletonPtr()->createSceneManager(); @@ -106,5 +106,5 @@ void DisplayTestFixture::mockValidTransform(Ogre::Vector3 position, Ogre::Quater } Ogre::SceneManager * DisplayTestFixture::scene_manager_ = nullptr; -std::shared_ptr +std::shared_ptr DisplayTestFixture::testing_environment_ = nullptr; diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.hpp b/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.hpp index fd92a1730..d607dcfbd 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.hpp @@ -43,7 +43,7 @@ #include "rclcpp/clock.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../ogre_testing_environment.hpp" #include "../mock_display_context.hpp" #include "../mock_frame_manager.hpp" @@ -65,7 +65,7 @@ class DisplayTestFixture : public testing::Test void mockValidTransform(Ogre::Vector3 position, Ogre::Quaternion orientation); - static std::shared_ptr testing_environment_; + static std::shared_ptr testing_environment_; static Ogre::SceneManager * scene_manager_; std::shared_ptr context_; diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/grid_cells/grid_cells_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/grid_cells/grid_cells_display_test.cpp index b264645a0..ca3425ce1 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/grid_cells/grid_cells_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/grid_cells/grid_cells_display_test.cpp @@ -40,9 +40,8 @@ #include "rviz_default_plugins/displays/grid_cells/grid_cells_display.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../../scene_graph_introspection.hpp" #include "../display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" using namespace ::testing; // NOLINT @@ -97,7 +96,7 @@ TEST_F(GridCellsDisplayFixture, processMessage_with_invalid_transform_returns_ea auto msg = createGridCellsMessageWithTwoCells(); display_->processMessage(msg); - auto point_clouds = rviz_rendering::findAllPointClouds(scene_manager_->getRootSceneNode()); + auto point_clouds = rviz_default_plugins::findAllPointClouds(scene_manager_->getRootSceneNode()); EXPECT_THAT(point_clouds.size(), Eq(1u)); EXPECT_THAT(point_clouds[0]->getPoints().size(), Eq(0u)); } @@ -108,7 +107,7 @@ TEST_F(GridCellsDisplayFixture, processMessage_with_zero_size_does_not_add_messa auto msg = createGridCellsMessageWithTwoCells(0, 1); display_->processMessage(msg); - auto point_clouds = rviz_rendering::findAllPointClouds(scene_manager_->getRootSceneNode()); + auto point_clouds = rviz_default_plugins::findAllPointClouds(scene_manager_->getRootSceneNode()); EXPECT_THAT(point_clouds.size(), Eq(1u)); EXPECT_THAT(point_clouds[0]->getPoints().size(), Eq(0u)); } @@ -118,7 +117,7 @@ TEST_F(GridCellsDisplayFixture, processMessage_fills_pointcloud_with_correct_gri auto msg = createGridCellsMessageWithTwoCells(); display_->processMessage(msg); - auto point_clouds = rviz_rendering::findAllPointClouds(scene_manager_->getRootSceneNode()); + auto point_clouds = rviz_default_plugins::findAllPointClouds(scene_manager_->getRootSceneNode()); EXPECT_THAT(point_clouds.size(), Eq(1u)); EXPECT_THAT(point_clouds[0]->getPoints().size(), Eq(2u)); EXPECT_THAT( @@ -137,7 +136,7 @@ TEST_F(GridCellsDisplayFixture, processMessage_clears_cloud_on_new_message) { auto broken_msg = createGridCellsMessageWithTwoCells(0, 1); display_->processMessage(broken_msg); - auto point_clouds = rviz_rendering::findAllPointClouds(scene_manager_->getRootSceneNode()); + auto point_clouds = rviz_default_plugins::findAllPointClouds(scene_manager_->getRootSceneNode()); EXPECT_THAT(point_clouds.size(), Eq(1u)); EXPECT_THAT(point_clouds[0]->getPoints().size(), Eq(0u)); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_test.cpp index cb9119cab..28f9c49d5 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_test.cpp @@ -36,7 +36,7 @@ #include // NOLINT #include // NOLINT -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../../ogre_testing_environment.hpp" #include "rviz_common/viewport_mouse_event.hpp" #include "rviz_common/display_context.hpp" #include "rviz_common/panel_dock_widget.hpp" @@ -56,7 +56,7 @@ class ImageDisplayTestFixture : public Test public: static void SetUpTestCase() { - testing_environment_ = std::make_shared(); + testing_environment_ = std::make_shared(); testing_environment_->setUpOgreTestEnvironment(); } @@ -71,7 +71,7 @@ class ImageDisplayTestFixture : public Test ON_CALL(*context_, getWindowManager()).WillByDefault(Return(window_manager_.get())); } - static std::shared_ptr testing_environment_; + static std::shared_ptr testing_environment_; std::unique_ptr texture_; @@ -79,7 +79,7 @@ class ImageDisplayTestFixture : public Test std::shared_ptr window_manager_; }; -std::shared_ptr +std::shared_ptr ImageDisplayTestFixture::testing_environment_ = nullptr; TEST_F(ImageDisplayTestFixture, initialize_adds_render_panel_to_window) { diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/image/ros_image_texture_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/image/ros_image_texture_test.cpp index a01cd95e5..1bbfc7ea8 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/image/ros_image_texture_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/image/ros_image_texture_test.cpp @@ -36,7 +36,7 @@ #include "sensor_msgs/image_encodings.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../../ogre_testing_environment.hpp" #include "rviz_default_plugins/displays/image/ros_image_texture.hpp" @@ -48,14 +48,14 @@ class RosImageTextureTestFixture : public ::testing::Test protected: static void SetUpTestCase() { - testing_environment_ = std::make_shared(); + testing_environment_ = std::make_shared(); testing_environment_->setUpOgreTestEnvironment(); } - static std::shared_ptr testing_environment_; + static std::shared_ptr testing_environment_; }; -std::shared_ptr +std::shared_ptr RosImageTextureTestFixture::testing_environment_ = nullptr; TEST_F(RosImageTextureTestFixture, constructor_initializes_texture_with_default_image) { diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_test.cpp index 30b5b4867..dee4cf7ad 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_test.cpp @@ -39,8 +39,7 @@ #include #include "rviz_default_plugins/displays/map/map_display.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "../display_test_fixture.hpp" using namespace ::testing; // NOLINT @@ -100,7 +99,7 @@ class MapTestFixture : public DisplayTestFixture void expectNoManualObjects() { map_display_->showMap(); - auto manual_objects = rviz_rendering::findAllOgreObjectByType( + auto manual_objects = rviz_default_plugins::findAllOgreObjectByType( scene_manager_->getRootSceneNode(), "ManualObject"); EXPECT_THAT(manual_objects, IsEmpty()); @@ -147,7 +146,7 @@ TEST_F(MapTestFixture, showMap_shows_manual_object_if_current_map_is_valid) { map_display_->processMessage(createMapMessage()); - auto manual_objects = rviz_rendering::findAllOgreObjectByType( + auto manual_objects = rviz_default_plugins::findAllOgreObjectByType( scene_manager_->getRootSceneNode(), "ManualObject"); ASSERT_THAT(manual_objects, SizeIs(1)); @@ -170,7 +169,7 @@ TEST_F(MapTestFixture, showMap_defaults_empty_frame_id_to_map) { message->header.frame_id = ""; map_display_->processMessage(message); - auto manual_objects = rviz_rendering::findAllOgreObjectByType( + auto manual_objects = rviz_default_plugins::findAllOgreObjectByType( scene_manager_->getRootSceneNode(), "ManualObject"); ASSERT_THAT(manual_objects, SizeIs(1)); @@ -183,7 +182,7 @@ TEST_F(MapTestFixture, showMap_defaults_empty_frame_id_to_map) { TEST_F(MapTestFixture, showMap_does_not_display_anything_if_transform_fails) { map_display_->processMessage(createMapMessage()); - auto manual_objects = rviz_rendering::findAllOgreObjectByType( + auto manual_objects = rviz_default_plugins::findAllOgreObjectByType( scene_manager_->getRootSceneNode(), "ManualObject"); ASSERT_THAT(manual_objects, SizeIs(1)); @@ -199,7 +198,7 @@ TEST_F(MapTestFixture, reset_deletes_map) { map_display_->reset(); - auto manual_objects = rviz_rendering::findAllOgreObjectByType( + auto manual_objects = rviz_default_plugins::findAllOgreObjectByType( scene_manager_->getRootSceneNode(), "ManualObject"); ASSERT_THAT(manual_objects, SizeIs(0)); @@ -209,7 +208,7 @@ TEST_F(MapTestFixture, createSwatches_creates_more_swatches_if_map_is_too_big) { // one dimension is larger than 2^16 --> that's too much for one texture buffer map_display_->processMessage(createMapMessage(70000, 50)); - auto manual_objects = rviz_rendering::findAllOgreObjectByType( + auto manual_objects = rviz_default_plugins::findAllOgreObjectByType( scene_manager_->getRootSceneNode(), "ManualObject"); EXPECT_THAT(manual_objects, SizeIs(2)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp index cf52ca96a..c9df88b67 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp @@ -51,8 +51,7 @@ #include "rviz_default_plugins/displays/marker/markers/mesh_resource_marker.hpp" #include "rviz_default_plugins/displays/marker/markers/triangle_list_marker.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "marker_messages.hpp" #include "../display_test_fixture.hpp" @@ -95,7 +94,7 @@ TEST_F(MarkerCommonFixture, processMessage_creates_correct_marker_on_add_type) { createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::TEXT_VIEW_FACING)); - auto text = rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode()); + auto text = rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode()); ASSERT_TRUE(text); EXPECT_THAT(text->getCaption(), StrEq("Displaytext")); } @@ -122,8 +121,8 @@ TEST_F(MarkerCommonFixture, processMessage_deletes_correct_marker_on_delete_type visualization_msgs::msg::Marker::TEXT_VIEW_FACING, 0)); - ASSERT_FALSE(rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode())); - ASSERT_TRUE(rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode())); + ASSERT_FALSE(rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode())); + ASSERT_TRUE(rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode())); } TEST_F(MarkerCommonFixture, processMessage_with_deleteall_deletes_all_markers) { @@ -147,8 +146,8 @@ TEST_F(MarkerCommonFixture, processMessage_with_deleteall_deletes_all_markers) { visualization_msgs::msg::Marker::TEXT_VIEW_FACING, 3)); - ASSERT_FALSE(rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode())); - ASSERT_FALSE(rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode())); + ASSERT_FALSE(rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode())); + ASSERT_FALSE(rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode())); } TEST_F(MarkerCommonFixture, proccesMessage_add_all_markers_correctly) { @@ -157,40 +156,40 @@ TEST_F(MarkerCommonFixture, proccesMessage_add_all_markers_correctly) { auto marker = createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::TEXT_VIEW_FACING); common_->processMessage(marker); - ASSERT_TRUE(rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode())); + ASSERT_TRUE(rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode())); common_->deleteAllMarkers(); marker->type = visualization_msgs::msg::Marker::MESH_RESOURCE; common_->processMessage(marker); ASSERT_TRUE( - rviz_rendering::findEntityByMeshName( + rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), marker->mesh_resource)); common_->deleteAllMarkers(); marker->type = visualization_msgs::msg::Marker::ARROW; common_->processMessage(marker); - ASSERT_TRUE(rviz_rendering::findOneArrow(scene_manager_->getRootSceneNode())); + ASSERT_TRUE(rviz_default_plugins::findOneArrow(scene_manager_->getRootSceneNode())); common_->deleteAllMarkers(); marker->type = visualization_msgs::msg::Marker::LINE_LIST; common_->processMessage(marker); - ASSERT_TRUE(rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode())); + ASSERT_TRUE(rviz_default_plugins::findOneBillboardChain(scene_manager_->getRootSceneNode())); common_->deleteAllMarkers(); marker->type = visualization_msgs::msg::Marker::LINE_STRIP; common_->processMessage(marker); - ASSERT_TRUE(rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode())); + ASSERT_TRUE(rviz_default_plugins::findOneBillboardChain(scene_manager_->getRootSceneNode())); common_->deleteAllMarkers(); marker->type = visualization_msgs::msg::Marker::CYLINDER; common_->processMessage(marker); ASSERT_TRUE( - rviz_rendering::findEntityByMeshName( + rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), "rviz_cylinder.mesh")); common_->deleteAllMarkers(); @@ -202,7 +201,7 @@ TEST_F(MarkerCommonFixture, proccesMessage_add_all_markers_correctly) { marker->type = visualization_msgs::msg::Marker::TRIANGLE_LIST; marker->points.push_back(point); common_->processMessage(marker); - ASSERT_TRUE(rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode())); + ASSERT_TRUE(rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode())); common_->deleteAllMarkers(); } @@ -216,7 +215,7 @@ TEST_F(MarkerCommonFixture, processMessage_adds_two_markers_of_same_type_if_ids_ visualization_msgs::msg::Marker::ARROW, 0)); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); common_->processMessage( createSharedPtrMessage( @@ -224,7 +223,7 @@ TEST_F(MarkerCommonFixture, processMessage_adds_two_markers_of_same_type_if_ids_ visualization_msgs::msg::Marker::ARROW, 1)); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(2)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(2)); } TEST_F( @@ -237,12 +236,12 @@ TEST_F( common_->processMessage(marker); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); marker->ns = "new_ns"; common_->processMessage(marker); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(2)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(2)); } TEST_F(MarkerCommonFixture, processMessage_does_not_create_new_marker_if_id_already_exists) { @@ -254,7 +253,7 @@ TEST_F(MarkerCommonFixture, processMessage_does_not_create_new_marker_if_id_alre visualization_msgs::msg::Marker::ARROW, 0)); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); common_->processMessage( createSharedPtrMessage( @@ -262,7 +261,7 @@ TEST_F(MarkerCommonFixture, processMessage_does_not_create_new_marker_if_id_alre visualization_msgs::msg::Marker::ARROW, 0)); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); } TEST_F(MarkerCommonFixture, processMessage_updates_modified_marker) { @@ -272,14 +271,14 @@ TEST_F(MarkerCommonFixture, processMessage_updates_modified_marker) { visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::TEXT_VIEW_FACING); common_->processMessage(marker); - auto before_update = rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode()); + auto before_update = rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode()); ASSERT_TRUE(before_update); EXPECT_THAT(before_update->getCaption(), StrEq(marker->text)); marker->text = "New text"; common_->processMessage(marker); - auto after_update = rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode()); + auto after_update = rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode()); ASSERT_TRUE(after_update); EXPECT_THAT(after_update->getCaption(), StrEq("New text")); } @@ -293,7 +292,7 @@ TEST_F(MarkerCommonFixture, processMessage_using_modify_works_like_add) { visualization_msgs::msg::Marker::ARROW, 0)); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); common_->processMessage( createSharedPtrMessage( @@ -301,7 +300,7 @@ TEST_F(MarkerCommonFixture, processMessage_using_modify_works_like_add) { visualization_msgs::msg::Marker::ARROW, 0)); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); } TEST_F(MarkerCommonFixture, update_retransforms_frame_locked_messages) { @@ -330,7 +329,7 @@ TEST_F(MarkerCommonFixture, update_retransforms_frame_locked_messages) { common_->processMessage(marker); - auto pointCloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto pointCloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); ASSERT_TRUE(pointCloud); EXPECT_THAT(pointCloud->getParentSceneNode()->getPosition(), Vector3Eq(starting_position)); EXPECT_THAT( @@ -364,7 +363,7 @@ TEST_F(MarkerCommonFixture, update_does_not_retransform_normal_messages) { common_->processMessage(marker); - auto pointCloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto pointCloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); ASSERT_TRUE(pointCloud); EXPECT_THAT(pointCloud->getParentSceneNode()->getPosition(), Vector3Eq(starting_position)); EXPECT_THAT( @@ -427,15 +426,15 @@ TEST_F(MarkerCommonFixture, onEnableChanged_in_namespace_removes_all_markers_in_ marker->ns = "new_ns"; common_->processMessage(marker); - EXPECT_TRUE(rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode())); - EXPECT_TRUE(rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode())); + EXPECT_TRUE(rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode())); + EXPECT_TRUE(rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode())); auto namespace_property = dynamic_cast( display_->findProperty("Namespaces")->childAt(0)); namespace_property->setValue(false); - EXPECT_FALSE(rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode())); - EXPECT_TRUE(rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode())); + EXPECT_FALSE(rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode())); + EXPECT_TRUE(rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode())); } TEST_F(MarkerCommonFixture, processMessage_does_not_add_message_with_disabled_namespace) { @@ -447,7 +446,7 @@ TEST_F(MarkerCommonFixture, processMessage_does_not_add_message_with_disabled_na // this is necessary to initialize namespace as we don't load a config common_->processMessage(marker); - EXPECT_TRUE(rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode())); + EXPECT_TRUE(rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode())); auto namespace_property = dynamic_cast( display_->findProperty("Namespaces")->childAt(0)); @@ -456,6 +455,6 @@ TEST_F(MarkerCommonFixture, processMessage_does_not_add_message_with_disabled_na marker->type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; common_->processMessage(marker); - EXPECT_FALSE(rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode())); - EXPECT_FALSE(rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode())); + EXPECT_FALSE(rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode())); + EXPECT_FALSE(rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode())); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/arrow_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/arrow_marker_test.cpp index af9281fad..6527bd34c 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/arrow_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/arrow_marker_test.cpp @@ -43,7 +43,7 @@ #include "rviz_default_plugins/displays/marker/markers/arrow_marker.hpp" -#include "../../../scene_graph_introspection_helper.hpp" +#include "../../../scene_graph_introspection.hpp" #include "markers_test_fixture.hpp" #include "../marker_messages.hpp" diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/line_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/line_marker_test.cpp index 047fd0cc4..cfb82ab47 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/line_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/line_marker_test.cpp @@ -42,8 +42,7 @@ #include "rviz_default_plugins/displays/marker/markers/line_list_marker.hpp" #include "rviz_default_plugins/displays/marker/markers/line_strip_marker.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../../scene_graph_introspection_helper.hpp" +#include "../../../scene_graph_introspection.hpp" #include "markers_test_fixture.hpp" #include "../marker_messages.hpp" @@ -64,7 +63,7 @@ TEST_F(MarkersTestFixture, setMessage_does_not_add_anything_when_no_points_are_p marker_->setMessage(createDefaultMessage(visualization_msgs::msg::Marker::LINE_LIST)); - auto billboard_chain = rviz_rendering::findOneBillboardChain( + auto billboard_chain = rviz_default_plugins::findOneBillboardChain( scene_manager_->getRootSceneNode()); ASSERT_TRUE(billboard_chain); ASSERT_TRUE(billboard_chain->isVisible()); @@ -81,7 +80,8 @@ TEST_F(MarkersTestFixture, setMessage_sets_billboard_line_invisible_when_transfo marker_->setMessage(createDefaultMessage(visualization_msgs::msg::Marker::LINE_LIST)); - auto billboard_chain = rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode()); + auto billboard_chain = rviz_default_plugins::findOneBillboardChain( + scene_manager_->getRootSceneNode()); ASSERT_TRUE(billboard_chain); EXPECT_FALSE(billboard_chain->isVisible()); } @@ -105,7 +105,8 @@ TEST_F(MarkersTestFixture, setMessage_does_not_show_billboard_line_if_uneven_num marker_->setMessage(message); - auto billboard_chain = rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode()); + auto billboard_chain = rviz_default_plugins::findOneBillboardChain( + scene_manager_->getRootSceneNode()); ASSERT_TRUE(billboard_chain); EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); @@ -123,7 +124,8 @@ TEST_F(MarkersTestFixture, setMessage_clears_marker_upon_new_message) { marker_->setMessage(createDefaultMessage(visualization_msgs::msg::Marker::LINE_LIST)); - auto billboard_chain = rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode()); + auto billboard_chain = rviz_default_plugins::findOneBillboardChain( + scene_manager_->getRootSceneNode()); ASSERT_TRUE(billboard_chain); EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); @@ -143,7 +145,8 @@ TEST_F(MarkersTestFixture, setMessage_adds_billboard_line_with_one_color) { marker_->setMessage(message); - auto billboard_chain = rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode()); + auto billboard_chain = rviz_default_plugins::findOneBillboardChain( + scene_manager_->getRootSceneNode()); ASSERT_TRUE(billboard_chain); EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); @@ -177,7 +180,8 @@ TEST_F( marker_->setMessage(message); - auto billboard_chain = rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode()); + auto billboard_chain = rviz_default_plugins::findOneBillboardChain( + scene_manager_->getRootSceneNode()); ASSERT_TRUE(billboard_chain); EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); @@ -202,7 +206,8 @@ TEST_F(MarkersTestFixture, setMessage_shows_billboard_strip_for_uneven_number_of marker_->setMessage(message); - auto billboard_chain = rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode()); + auto billboard_chain = rviz_default_plugins::findOneBillboardChain( + scene_manager_->getRootSceneNode()); ASSERT_TRUE(billboard_chain); EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); @@ -222,7 +227,8 @@ TEST_F(MarkersTestFixture, setMessage_adds_many_points_into_same_chain) { marker_->setMessage(message); - auto billboard_chain = rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode()); + auto billboard_chain = rviz_default_plugins::findOneBillboardChain( + scene_manager_->getRootSceneNode()); ASSERT_TRUE(billboard_chain); EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.hpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.hpp index fc688459b..24c8b2a4a 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/markers_test_fixture.hpp @@ -42,7 +42,7 @@ #include // NOLINT -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../../../ogre_testing_environment.hpp" #include "../../display_test_fixture.hpp" #include "../../../mock_display_context.hpp" #include "../../../mock_frame_manager.hpp" diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/mesh_resource_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/mesh_resource_marker_test.cpp index 08852653a..87c95be52 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/mesh_resource_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/mesh_resource_marker_test.cpp @@ -44,8 +44,7 @@ #include "rviz_default_plugins/displays/marker/markers/mesh_resource_marker.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../../scene_graph_introspection_helper.hpp" +#include "../../../scene_graph_introspection.hpp" #include "markers_test_fixture.hpp" #include "../marker_messages.hpp" @@ -60,7 +59,7 @@ TEST_F(MarkersTestFixture, setMessage_with_no_transform_makes_node_invisible) { marker_->setMessage(message); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_TRUE(entity); EXPECT_FALSE(entity->isVisible()); @@ -74,7 +73,7 @@ TEST_F(MarkersTestFixture, setMessage_with_transform_sets_position_and_orientati marker_->setMessage(message); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_TRUE(entity); EXPECT_TRUE(entity->isVisible()); @@ -93,7 +92,7 @@ TEST_F(MarkersTestFixture, setMessage_does_not_attach_entity_when_mesh_is_missin marker_->setMessage(message); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_FALSE(entity); } @@ -108,7 +107,7 @@ TEST_F(MarkersTestFixture, setMessage_does_not_attache_entity_when_no_mesh_attac marker_->setMessage(message); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_FALSE(entity); } @@ -123,7 +122,7 @@ TEST_F(MarkersTestFixture, setMessage_attaches_default_material_to_correct_mesh) marker_->setMessage(message); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_TRUE(entity); EXPECT_THAT(entity->getMesh()->getName(), StrEq(message.mesh_resource)); @@ -142,7 +141,7 @@ TEST_F(MarkersTestFixture, setMessage_initially_sets_color_correctly) { marker_->setMessage(message); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_TRUE(entity); EXPECT_THAT( @@ -162,7 +161,7 @@ TEST_F(MarkersTestFixture, setMessage_changes_color_on_new_message_changing_colo message.color.b = 0.0f; marker_->setMessage(message); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_TRUE(entity); EXPECT_THAT( @@ -178,7 +177,7 @@ TEST_F(MarkersTestFixture, setMessage_uses_cloned_materials_to_make_selection_wo marker_->setMessage(message); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_TRUE(entity); auto entity_material_name = entity->getSubEntity(0)->getMaterialName(); @@ -196,7 +195,7 @@ TEST_F(MarkersTestFixture, setMessage_with_new_object_clears_old_entities_and_ma marker_->setMessage(message); // get everything that needs to be deleted later on - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), message.mesh_resource); ASSERT_TRUE(entity); EXPECT_EQ(1u, marker_->getMaterials().size()); @@ -207,7 +206,7 @@ TEST_F(MarkersTestFixture, setMessage_with_new_object_clears_old_entities_and_ma marker_->setMessage(message); // entity and material are cleaned up - auto deleted_entity = rviz_rendering::findEntityByMeshName( + auto deleted_entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), "package://rviz_default_plugins/test_meshes/pr2-base.dae"); ASSERT_FALSE(deleted_entity); EXPECT_FALSE( diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/points_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/points_marker_test.cpp index 6a9e250eb..26038a18b 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/points_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/points_marker_test.cpp @@ -37,8 +37,7 @@ #include "rviz_default_plugins/displays/marker/markers/points_marker.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../../scene_graph_introspection_helper.hpp" +#include "../../../scene_graph_introspection.hpp" #include "markers_test_fixture.hpp" #include "../marker_messages.hpp" @@ -50,7 +49,7 @@ TEST_F(MarkersTestFixture, setMessage_makes_the_point_cloud_node_invisible_if_in marker_->setMessage(createDefaultMessage(visualization_msgs::msg::Marker::POINTS)); - auto point_cloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto point_cloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); EXPECT_FALSE(point_cloud->isVisible()); } @@ -60,7 +59,7 @@ TEST_F(MarkersTestFixture, setMessage_sets_points_correctly) { marker_->setMessage(createMessageWithPoints(visualization_msgs::msg::Marker::SPHERE_LIST)); - auto point_cloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto point_cloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); float expected_bounding_radius = 2.236068f; EXPECT_TRUE(point_cloud->isVisible()); EXPECT_THAT(point_cloud->getBoundingRadius(), FloatEq(expected_bounding_radius)); @@ -81,7 +80,7 @@ TEST_F(MarkersTestFixture, setMessage_sets_single_color_correctly) { mockValidTransform(); marker_->setMessage(createMessageWithPoints(visualization_msgs::msg::Marker::SPHERE_LIST)); - auto point_cloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto point_cloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); Ogre::ColourValue expected_color(0.0f, 1.0f, 1.0f, 1.0f); EXPECT_THAT(point_cloud->getPoints()[0].color, Eq(expected_color)); @@ -93,7 +92,7 @@ TEST_F(MarkersTestFixture, setMessage_sets_per_point_color_correctly) { mockValidTransform(); marker_->setMessage(createMessageWithColorPerPoint(visualization_msgs::msg::Marker::POINTS)); - auto point_cloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto point_cloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); EXPECT_THAT(point_cloud->getPoints()[0].color, Eq(Ogre::ColourValue(1.0f, 0.0f, 0.5f, 0.5f))); EXPECT_THAT(point_cloud->getPoints()[1].color, Eq(Ogre::ColourValue(0.5f, 0.6f, 0.0f, 0.3f))); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/shape_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/shape_marker_test.cpp index 1e23e8c37..9808b2733 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/shape_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/shape_marker_test.cpp @@ -42,8 +42,7 @@ #include "rviz_default_plugins/displays/marker/markers/shape_marker.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../../scene_graph_introspection_helper.hpp" +#include "../../../scene_graph_introspection.hpp" #include "markers_test_fixture.hpp" #include "../marker_messages.hpp" @@ -56,7 +55,7 @@ TEST_F(MarkersTestFixture, no_transform_does_not_try_to_set_scene_node) { marker_->setMessage(createDefaultMessage(visualization_msgs::msg::Marker::CUBE)); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), "rviz_cube.mesh"); ASSERT_FALSE(entity->isVisible()); } @@ -73,7 +72,7 @@ TEST_F(MarkersTestFixture, positions_and_orientations_are_set_correctly) { EXPECT_THAT(marker_->getPosition(), Vector3Eq(position)); EXPECT_THAT(marker_->getOrientation(), QuaternionEq(Ogre::Quaternion(0, 0, 0.7071f, -0.7071f))); - auto entity = rviz_rendering::findEntityByMeshName( + auto entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), "rviz_cube.mesh"); auto shape_scene_node = entity @@ -90,18 +89,18 @@ TEST_F(MarkersTestFixture, different_types_result_in_different_meshes) { marker_->setMessage(createDefaultMessage(visualization_msgs::msg::Marker::SPHERE)); - auto cylinder_entity = rviz_rendering::findEntityByMeshName( + auto cylinder_entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), "rviz_cylinder.mesh"); - auto sphere_entity = rviz_rendering::findEntityByMeshName( + auto sphere_entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), "rviz_sphere.mesh"); EXPECT_FALSE(cylinder_entity); EXPECT_TRUE(sphere_entity); marker_->setMessage(createDefaultMessage(visualization_msgs::msg::Marker::CYLINDER)); - cylinder_entity = rviz_rendering::findEntityByMeshName( + cylinder_entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), "rviz_cylinder.mesh"); - sphere_entity = rviz_rendering::findEntityByMeshName( + sphere_entity = rviz_default_plugins::findEntityByMeshName( scene_manager_->getRootSceneNode(), "rviz_sphere.mesh"); EXPECT_TRUE(cylinder_entity); EXPECT_FALSE(sphere_entity); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/text_view_facing_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/text_view_facing_marker_test.cpp index 7514a215c..8a86a2d8c 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/text_view_facing_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/text_view_facing_marker_test.cpp @@ -42,8 +42,7 @@ #include "rviz_default_plugins/displays/marker/markers/text_view_facing_marker.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../../scene_graph_introspection_helper.hpp" +#include "../../../scene_graph_introspection.hpp" #include "markers_test_fixture.hpp" #include "../marker_messages.hpp" @@ -55,7 +54,7 @@ TEST_F(MarkersTestFixture, setMessage_sets_object_invisible_when_transform_fails marker_->setMessage(createDefaultMessage(visualization_msgs::msg::Marker::TEXT_VIEW_FACING)); - auto movable_text = rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode()); + auto movable_text = rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode()); ASSERT_TRUE(movable_text); EXPECT_FALSE(movable_text->isVisible()); @@ -69,7 +68,7 @@ TEST_F(MarkersTestFixture, setMessage_sets_correct_caption_for_valid_message) { message.text = "Message to display"; marker_->setMessage(message); - auto movable_text = rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode()); + auto movable_text = rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode()); ASSERT_TRUE(movable_text); EXPECT_TRUE(movable_text->isVisible()); EXPECT_THAT(movable_text->getCaption(), StrEq(message.text)); @@ -83,7 +82,7 @@ TEST_F(MarkersTestFixture, setMessage_sets_correct_transformation_for_valid_mess message.text = "Message to display"; marker_->setMessage(message); - auto movable_text = rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode()); + auto movable_text = rviz_default_plugins::findOneMovableText(scene_manager_->getRootSceneNode()); ASSERT_TRUE(movable_text); EXPECT_THAT(movable_text->getParentSceneNode()->getPosition(), Vector3Eq(Ogre::Vector3(0, 1, 0))); EXPECT_THAT(movable_text->getCharacterHeight(), Eq(message.scale.z)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/triangle_list_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/triangle_list_marker_test.cpp index 87f95b7d0..b916e4c6f 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/triangle_list_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/triangle_list_marker_test.cpp @@ -42,8 +42,7 @@ #include "rviz_default_plugins/displays/marker/markers/triangle_list_marker.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../../scene_graph_introspection_helper.hpp" +#include "../../../scene_graph_introspection.hpp" #include "markers_test_fixture.hpp" #include "../marker_messages.hpp" @@ -58,7 +57,7 @@ TEST_F(MarkersTestFixture, setMessage_does_nothing_on_wrong_number_of_points) { marker_->setMessage(message); - auto object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto object = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); ASSERT_FALSE(object); } @@ -74,7 +73,7 @@ TEST_F(MarkersTestFixture, setMessage_does_not_set_scene_node_without_transform) marker_->setMessage(message); - auto object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto object = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); ASSERT_FALSE(object->isVisible()); } @@ -90,6 +89,6 @@ TEST_F(MarkersTestFixture, setMessage_adds_new_object_on_correct_message) { marker_->setMessage(message); - auto object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto object = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); ASSERT_TRUE(object); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp index 604d64eed..8596bc509 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp @@ -40,8 +40,7 @@ #include "rviz_default_plugins/displays/odometry/odometry_display.hpp" #include "../display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../../scene_graph_introspection.hpp" using namespace ::testing; // NOLINT @@ -109,8 +108,8 @@ TEST_F(OdometryDisplayFixture, processMessage_returns_early_if_message_has_inval display_->processMessage(invalid_pose_message); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); EXPECT_THAT(arrows, IsEmpty()); EXPECT_THAT(axes, IsEmpty()); } @@ -123,8 +122,8 @@ TEST_F(OdometryDisplayFixture, processMessage_returns_early_if_message_has_inval display_->processMessage(invalid_orientation_message); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); EXPECT_THAT(arrows, IsEmpty()); EXPECT_THAT(axes, IsEmpty()); } @@ -135,8 +134,8 @@ TEST_F(OdometryDisplayFixture, processMessage_returns_early_if_transform_is_miss display_->processMessage(odometry_message); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); EXPECT_THAT(arrows, IsEmpty()); EXPECT_THAT(axes, IsEmpty()); } @@ -147,8 +146,8 @@ TEST_F( mockValidTransform(); auto odometry_message = createOdometryMessage(); display_->processMessage(odometry_message); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); ASSERT_THAT(arrows, SizeIs(1)); ASSERT_THAT(axes, SizeIs(1)); arrows[0]->removeAllChildren(); @@ -156,8 +155,8 @@ TEST_F( display_->processMessage(odometry_message); - arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); EXPECT_THAT(arrows, IsEmpty()); EXPECT_THAT(axes, IsEmpty()); } @@ -172,8 +171,8 @@ TEST_F(OdometryDisplayFixture, processMessage_sets_arrow_and_axes_according_to_m display_->processMessage(odometry_message); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); ASSERT_THAT(arrows, SizeIs(1)); ASSERT_THAT(axes, SizeIs(1)); EXPECT_THAT(arrows[0]->getPosition(), Vector3Eq(Ogre::Vector3(0, 1, 0))); @@ -193,10 +192,10 @@ TEST_F( EXPECT_TRUE( rviz_default_plugins::arrowIsVisible( - rviz_rendering::findOneArrow(scene_manager_->getRootSceneNode()))); + rviz_default_plugins::findOneArrow(scene_manager_->getRootSceneNode()))); EXPECT_FALSE( rviz_default_plugins::axesAreVisible( - rviz_rendering::findOneAxes(scene_manager_->getRootSceneNode()))); + rviz_default_plugins::findOneAxes(scene_manager_->getRootSceneNode()))); shape_property->setString("Axes"); odometry_message->pose.pose.position.x = 35; @@ -204,10 +203,10 @@ TEST_F( EXPECT_FALSE( rviz_default_plugins::arrowIsVisible( - rviz_rendering::findOneArrow(scene_manager_->getRootSceneNode()))); + rviz_default_plugins::findOneArrow(scene_manager_->getRootSceneNode()))); EXPECT_TRUE( rviz_default_plugins::axesAreVisible( - rviz_rendering::findOneAxes(scene_manager_->getRootSceneNode()))); + rviz_default_plugins::findOneAxes(scene_manager_->getRootSceneNode()))); } TEST_F(OdometryDisplayFixture, processMessage_sets_covariance_visual_according_to_message) { @@ -218,7 +217,7 @@ TEST_F(OdometryDisplayFixture, processMessage_sets_covariance_visual_according_t display_->processMessage(odometry_message); - auto all_spheres = rviz_rendering::findAllSpheres(scene_manager_->getRootSceneNode()); + auto all_spheres = rviz_default_plugins::findAllSpheres(scene_manager_->getRootSceneNode()); ASSERT_THAT(all_spheres, SizeIs(1)); auto sphere_scene_node = all_spheres[0]->getParentSceneNode(); auto cov_node_with_position_and_orientation = getParentAt(5, sphere_scene_node); @@ -234,9 +233,9 @@ TEST_F(OdometryDisplayFixture, reset_clears_all_objects) { display_->processMessage(odometry_message); display_->reset(); - auto all_spheres = rviz_rendering::findAllSpheres(scene_manager_->getRootSceneNode()); - auto all_cylynders = rviz_rendering::findAllCylinders(scene_manager_->getRootSceneNode()); - auto all_cones = rviz_rendering::findAllCones(scene_manager_->getRootSceneNode()); + auto all_spheres = rviz_default_plugins::findAllSpheres(scene_manager_->getRootSceneNode()); + auto all_cylynders = rviz_default_plugins::findAllCylinders(scene_manager_->getRootSceneNode()); + auto all_cones = rviz_default_plugins::findAllCones(scene_manager_->getRootSceneNode()); EXPECT_THAT(all_spheres, SizeIs(0)); EXPECT_THAT(all_cylynders, SizeIs(0)); EXPECT_THAT(all_cones, SizeIs(0)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/path/path_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/path/path_display_test.cpp index d404f130d..c809e3589 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/path/path_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/path/path_display_test.cpp @@ -42,8 +42,7 @@ #include "visualization_msgs/msg/marker.hpp" #include "rviz_rendering/objects/arrow.hpp" #include "rviz_rendering/objects/shape.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "rviz_default_plugins/displays/path/path_display.hpp" @@ -102,7 +101,7 @@ TEST_F(PathTestFixture, processMessage_adds_nothing_to_scene_if_invalid_transfor path_display_->processMessage(createPathMessage()); - auto object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto object = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); EXPECT_THAT(object->getNumSections(), Eq(0u)); } @@ -113,7 +112,7 @@ TEST_F(PathTestFixture, processMessage_adds_vertices_to_scene) { path_display_->processMessage(createPathMessage()); - auto object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto object = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); EXPECT_THAT(object->getSection(0)->getRenderOperation()->vertexData->vertexCount, Eq(2u)); } @@ -125,7 +124,7 @@ TEST_F(PathTestFixture, reset_clears_the_scene) { path_display_->processMessage(createPathMessage()); path_display_->reset(); - auto object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto object = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); EXPECT_THAT(object->getNumSections(), Eq(0u)); } @@ -149,10 +148,10 @@ TEST_F(PathTestFixture, reset_removes_all_axes) { mockValidTransform(position, orientation); path_display_->processMessage(createPathMessage()); - EXPECT_THAT(rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()), SizeIs(2)); + EXPECT_THAT(rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()), SizeIs(2)); path_display_->reset(); - EXPECT_THAT(rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()), SizeIs(0)); + EXPECT_THAT(rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()), SizeIs(0)); } TEST_F(PathTestFixture, reset_removes_all_arrows) { @@ -163,10 +162,10 @@ TEST_F(PathTestFixture, reset_removes_all_arrows) { mockValidTransform(position, orientation); path_display_->processMessage(createPathMessage()); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(2)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(2)); path_display_->reset(); - EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(0)); + EXPECT_THAT(rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(0)); } TEST_F(PathTestFixture, processMessage_transforms_the_vertices_correctly) { @@ -176,7 +175,7 @@ TEST_F(PathTestFixture, processMessage_transforms_the_vertices_correctly) { path_display_->processMessage(createPathMessage()); - auto object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto object = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); EXPECT_THAT(object->getSection(0)->getRenderOperation()->vertexData->vertexCount, Eq(2u)); // Use bounding box to indirectly assert the vertices @@ -193,7 +192,7 @@ TEST_F(PathTestFixture, processMessage_adds_billboard_line_to_scene) { path_display_->processMessage(createPathMessage()); - auto object = rviz_rendering::findOneBillboardChain(scene_manager_->getRootSceneNode()); + auto object = rviz_default_plugins::findOneBillboardChain(scene_manager_->getRootSceneNode()); EXPECT_THAT(object->getNumberOfChains(), Eq(1u)); EXPECT_THAT(object->getNumChainElements(0), Eq(2u)); @@ -210,10 +209,10 @@ TEST_F(PathTestFixture, processMessage_adds_axes_to_scene) { path_display_->processMessage(createPathMessage()); - auto axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); EXPECT_THAT(axes, SizeIs(2)); - auto axes_positions = rviz_rendering::getPositionsFromNodes(axes); + auto axes_positions = rviz_default_plugins::getPositionsFromNodes(axes); EXPECT_THAT(axes_positions, Contains(Vector3Eq(Ogre::Vector3(4, 2, 0)))); EXPECT_THAT(axes_positions, Contains(Vector3Eq(Ogre::Vector3(1, 1, 1)))); } @@ -227,15 +226,15 @@ TEST_F(PathTestFixture, processMessage_adds_arrows_to_scene) { path_display_->processMessage(createPathMessage()); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); EXPECT_THAT(arrows, SizeIs(2)); - auto arrow_positions = rviz_rendering::getPositionsFromNodes(arrows); + auto arrow_positions = rviz_default_plugins::getPositionsFromNodes(arrows); EXPECT_THAT(arrow_positions, Contains(Vector3Eq(Ogre::Vector3(1, 1, 1)))); EXPECT_THAT(arrow_positions, Contains(Vector3Eq(Ogre::Vector3(4, 2, 0)))); // default orientation is set to (0.5, -0.5, -0.5, -0.5) by arrow auto default_orientation = Ogre::Quaternion(0.5f, -0.5f, -0.5f, -0.5f); - auto arrow_orientations = rviz_rendering::getOrientationsFromNodes(arrows); + auto arrow_orientations = rviz_default_plugins::getOrientationsFromNodes(arrows); EXPECT_THAT(arrow_orientations, Each(QuaternionEq(default_orientation))); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp index 0f86071d3..2809ce767 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp @@ -43,8 +43,7 @@ #include "rviz_default_plugins/displays/point/point_stamped_display.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "../display_test_fixture.hpp" using namespace ::testing; // NOLINT @@ -94,7 +93,7 @@ TEST_F(PointStampedTestFixture, processMessage_adds_nothing_to_scene_if_invalid_ point_stamped_display_->processMessage(createPointMessage(0, 0, 0)); - auto objects = rviz_rendering::findAllEntitiesByMeshName( + auto objects = rviz_default_plugins::findAllEntitiesByMeshName( scene_manager_->getRootSceneNode(), "rviz_sphere.mesh"); EXPECT_THAT(objects.size(), Eq(0u)); } @@ -110,7 +109,7 @@ TEST_F( point_stamped_display_->processMessage(createPointMessage(1, 0, 0)); point_stamped_display_->processMessage(createPointMessage(-1, 0, 0)); - auto objects = rviz_rendering::findAllEntitiesByMeshName( + auto objects = rviz_default_plugins::findAllEntitiesByMeshName( scene_manager_->getRootSceneNode(), "rviz_sphere.mesh"); EXPECT_THAT(objects.size(), Eq(2u)); assertPointsPresent(objects, Ogre::Vector3(1, 0, 0)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp index 1c1e67582..f8567ee7b 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp @@ -40,8 +40,7 @@ #include "rviz_default_plugins/displays/pointcloud/point_cloud_common.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "../../pointcloud_messages.hpp" #include "../display_test_fixture.hpp" @@ -84,7 +83,7 @@ TEST_F(PointCloudCommonTestFixture, update_adds_pointcloud_to_scene_graph) { point_cloud_common_->addMessage(cloud); point_cloud_common_->update(0, 0); - auto point_cloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto point_cloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); EXPECT_THAT(point_cloud->getPoints()[0].position, Vector3Eq(Ogre::Vector3(1, 2, 3))); EXPECT_THAT(point_cloud->getPoints()[1].position, Vector3Eq(Ogre::Vector3(4, 5, 6))); @@ -109,7 +108,7 @@ TEST_F(PointCloudCommonTestFixture, update_removes_old_point_clouds) { point_cloud_common_->addMessage(cloud); point_cloud_common_->update(0, 0); - auto point_clouds = rviz_rendering::findAllPointClouds(scene_manager_->getRootSceneNode()); + auto point_clouds = rviz_default_plugins::findAllPointClouds(scene_manager_->getRootSceneNode()); ASSERT_THAT(point_clouds.size(), Eq(1u)); EXPECT_THAT(point_clouds[0]->getPoints()[0].position, Vector3Eq(Ogre::Vector3(4, 5, 6))); @@ -129,7 +128,7 @@ TEST_F(PointCloudCommonTestFixture, update_sets_size_and_alpha_on_renderable) { point_cloud_common_->addMessage(cloud); point_cloud_common_->update(0, 0); - auto point_cloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto point_cloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); auto size = point_cloud->getRenderables()[0]->getCustomParameter(RVIZ_RENDERING_SIZE_PARAMETER); auto alpha = point_cloud->getRenderables()[0]->getCustomParameter(RVIZ_RENDERING_ALPHA_PARAMETER); @@ -152,7 +151,7 @@ TEST_F(PointCloudCommonTestFixture, update_adds_nothing_if_transform_fails) { point_cloud_common_->addMessage(cloud); point_cloud_common_->update(0, 0); - auto point_cloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto point_cloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); EXPECT_FALSE(point_cloud); } @@ -176,7 +175,7 @@ TEST_F(PointCloudCommonTestFixture, update_colors_the_points_using_the_selected_ point_cloud_common_->addMessage(cloud); point_cloud_common_->update(0, 0); - auto point_cloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); + auto point_cloud = rviz_default_plugins::findOnePointCloud(scene_manager_->getRootSceneNode()); EXPECT_THAT(point_cloud->getPoints()[0].position, Vector3Eq(Ogre::Vector3(1, 2, 3))); EXPECT_THAT(point_cloud->getPoints()[0].color, ColourValueEq(Ogre::ColourValue(1, 0, 0))); @@ -227,7 +226,7 @@ TEST_F( point_cloud_common_->addMessage(cloud); point_cloud_common_->update(0, 0); - auto point_clouds = rviz_rendering::findAllPointClouds(scene_manager_->getRootSceneNode()); + auto point_clouds = rviz_default_plugins::findAllPointClouds(scene_manager_->getRootSceneNode()); ASSERT_THAT(point_clouds.size(), Eq(0u)); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp index 75f00e1f8..20ac995d6 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp @@ -44,8 +44,7 @@ #include "../../../../src/rviz_default_plugins/displays/pointcloud/point_cloud_common.hpp" #include "../../../../src/rviz_default_plugins/displays/pointcloud/point_cloud2_display.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "../display_test_fixture.hpp" #include "./message_creators.hpp" @@ -138,7 +137,7 @@ TEST_F(PointCloudSelectionHandlerFixture, onSelect_selects_only_points_actually_ rviz_common::interaction::V_AABB aabbs = cloud_info->selection_handler_->getAABBs(picked_object); EXPECT_THAT(aabbs, SizeIs(2)); - auto found_objects = rviz_rendering::findAllOgreObjectByType( + auto found_objects = rviz_default_plugins::findAllOgreObjectByType( scene_manager_->getRootSceneNode(), "SimpleRenderable"); EXPECT_THAT( found_objects, @@ -171,7 +170,7 @@ TEST_F( rviz_common::interaction::V_AABB aabbs = cloud_info->selection_handler_->getAABBs(picked_object); EXPECT_THAT(aabbs, SizeIs(1)); - auto found_objects = rviz_rendering::findAllOgreObjectByType( + auto found_objects = rviz_default_plugins::findAllOgreObjectByType( scene_manager_->getRootSceneNode(), "SimpleRenderable"); EXPECT_THAT( found_objects, diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/xyz_pc_transformer_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/xyz_pc_transformer_test.cpp index fb53a4626..168d33fae 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/xyz_pc_transformer_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/xyz_pc_transformer_test.cpp @@ -34,7 +34,7 @@ #include "../../../pointcloud_messages.hpp" -#include "../../../scene_graph_introspection_helper.hpp" +#include "../../../scene_graph_introspection.hpp" #include "rviz_default_plugins/displays/pointcloud/transformers/xyz_pc_transformer.hpp" diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp index b0ee55c63..1c5e0e8c8 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp @@ -42,9 +42,8 @@ #include "rviz_default_plugins/displays/pose_array/pose_array_display.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../../scene_graph_introspection.hpp" #include "../display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" using namespace ::testing; // NOLINT @@ -169,10 +168,10 @@ TEST_F(PoseArrayDisplayFixture, setTransform_with_invalid_message_returns_early) msg->poses[0].position.x = nan("NaN"); display_->processMessage(msg); - auto arrows_3d = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto arrows_3d = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); auto manual_object = - rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); // the default position and orientation of the scene node are (0, 0, 0) and (1, 0, 0, 0) EXPECT_THAT(display_->getSceneNode()->getPosition(), Vector3Eq(Ogre::Vector3(0, 0, 0))); @@ -189,9 +188,10 @@ TEST_F(PoseArrayDisplayFixture, setTransform_with_invalid_transform_returns_earl auto msg = createMessageWithOnePose(); display_->processMessage(msg); - auto arrows_3d = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto axes = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); - auto manual_object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto arrows_3d = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto axes = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); + auto manual_object = rviz_default_plugins::findOneManualObject( + scene_manager_->getRootSceneNode()); // the default position and orientation of the scene node are (0, 0, 0) and (1, 0, 0, 0) EXPECT_THAT(display_->getSceneNode()->getPosition(), Vector3Eq(Ogre::Vector3(0, 0, 0))); @@ -217,7 +217,8 @@ TEST_F(PoseArrayDisplayFixture, processMessage_sets_manualObject_correctly) { auto msg = createMessageWithOnePose(); display_->processMessage(msg); - auto manual_object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto manual_object = rviz_default_plugins::findOneManualObject( + scene_manager_->getRootSceneNode()); auto manual_objectbounding_radius = 4.17732; EXPECT_THAT(manual_object->getBoundingRadius(), FloatEq(manual_objectbounding_radius)); EXPECT_THAT( @@ -231,7 +232,7 @@ TEST_F(PoseArrayDisplayFixture, processMessage_sets_arrows3d_correctly) { display_->setShape("Arrow (3D)"); display_->processMessage(msg); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); // The orientation is first manipulated by the display and then in setOrientation() in arrow.cpp auto expected_orientation = @@ -253,7 +254,7 @@ TEST_F(PoseArrayDisplayFixture, processMessage_sets_axes_correctly) { display_->setShape("Axes"); display_->processMessage(msg); - auto frames = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto frames = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); auto expected_orientation = Ogre::Quaternion(0, 1, 0, 1); expected_orientation.normalise(); @@ -270,17 +271,18 @@ TEST_F(PoseArrayDisplayFixture, processMessage_updates_the_display_correctly_aft display_->setShape("Arrow (3D)"); display_->processMessage(msg); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto frames = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); - auto manual_object = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto frames = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); + auto manual_object = rviz_default_plugins::findOneManualObject( + scene_manager_->getRootSceneNode()); EXPECT_THAT(arrows, SizeIs(1)); EXPECT_THAT(manual_object->getBoundingRadius(), FloatEq(0)); EXPECT_THAT(frames, SizeIs(0)); display_->setShape("Axes"); display_->processMessage(msg); - auto post_update_arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); - auto post_update_frames = rviz_rendering::findAllAxes(scene_manager_->getRootSceneNode()); + auto post_update_arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); + auto post_update_frames = rviz_default_plugins::findAllAxes(scene_manager_->getRootSceneNode()); EXPECT_THAT(post_update_frames, SizeIs(1)); EXPECT_THAT(manual_object->getBoundingRadius(), FloatEq(0)); EXPECT_THAT(post_update_arrows, SizeIs(0)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/range/range_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/range/range_display_test.cpp index b10ce693e..b94be82f1 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/range/range_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/range/range_display_test.cpp @@ -36,8 +36,7 @@ #include "rviz_default_plugins/displays/range/range_display.hpp" #include "../display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../../scene_graph_introspection.hpp" using namespace ::testing; // NOLINT @@ -69,11 +68,11 @@ sensor_msgs::msg::Range::ConstSharedPtr createRangeMessage(float range = 5) } TEST_F(RangeDisplayFixture, updateBufferLength_creates_right_number_of_cones) { - auto cones = rviz_rendering::findAllCones(scene_manager_->getRootSceneNode()); + auto cones = rviz_default_plugins::findAllCones(scene_manager_->getRootSceneNode()); EXPECT_THAT(cones, SizeIs(1)); display_->findProperty("Buffer Length")->setValue(3); - cones = rviz_rendering::findAllCones(scene_manager_->getRootSceneNode()); + cones = rviz_default_plugins::findAllCones(scene_manager_->getRootSceneNode()); EXPECT_THAT(cones, SizeIs(3)); } @@ -81,7 +80,7 @@ TEST_F(RangeDisplayFixture, processMessage_returns_early_if_transform_is_missing auto message = createRangeMessage(); display_->processMessage(message); - auto cones = rviz_rendering::findAllCones(scene_manager_->getRootSceneNode()); + auto cones = rviz_default_plugins::findAllCones(scene_manager_->getRootSceneNode()); ASSERT_THAT(cones, SizeIs(1)); auto cone_position = cones[0]->getParentSceneNode()->getParentSceneNode()->getPosition(); @@ -97,7 +96,7 @@ TEST_F(RangeDisplayFixture, processMessage_sets_cones_correctly) { auto message = createRangeMessage(); display_->processMessage(message); - auto cones = rviz_rendering::findAllCones(scene_manager_->getRootSceneNode()); + auto cones = rviz_default_plugins::findAllCones(scene_manager_->getRootSceneNode()); ASSERT_THAT(cones, SizeIs(1)); auto cone_position = cones[0]->getParentSceneNode()->getParentSceneNode()->getPosition(); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/tf/frame_info_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/tf/frame_info_test.cpp index c83307a8d..437f19554 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/tf/frame_info_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/tf/frame_info_test.cpp @@ -41,9 +41,8 @@ #include "rviz_default_plugins/displays/tf/frame_info.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../../scene_graph_introspection.hpp" #include "../display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" using namespace ::testing; // NOLINT @@ -66,13 +65,13 @@ TEST_F(FrameInfoTestFixture, updateArrow_makes_arrow_invisible_if_transform_has_ property->setValue(true); frame_info_->enabled_property_ = property.get(); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); EXPECT_THAT(arrows, SizeIs(1)); EXPECT_TRUE(rviz_default_plugins::arrowIsVisible(arrows[0])); frame_info_->updateParentArrow(Ogre::Vector3::ZERO, Ogre::Vector3::ZERO, 1); - auto invisible_arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); + auto invisible_arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); EXPECT_THAT(invisible_arrows, SizeIs(1)); EXPECT_FALSE(rviz_default_plugins::arrowIsVisible(invisible_arrows[0])); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/ogre_testing_environment.cpp b/rviz_default_plugins/test/rviz_default_plugins/ogre_testing_environment.cpp new file mode 100644 index 000000000..776942158 --- /dev/null +++ b/rviz_default_plugins/test/rviz_default_plugins/ogre_testing_environment.cpp @@ -0,0 +1,63 @@ +/* + * Copyright (c) 2017, Bosch Software Innovations GmbH. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "ogre_testing_environment.hpp" + +#include + +#include + +#include "rviz_rendering/render_window.hpp" +#include "rviz_rendering/render_system.hpp" + +namespace rviz_default_plugins +{ + +void OgreTestingEnvironment::setUpOgreTestEnvironment(bool debug) +{ + if (!debug) { + const std::string & name = ""; + auto lm = new Ogre::LogManager(); + lm->createLog(name, false, debug, true); + } + setUpRenderSystem(); +} + +void OgreTestingEnvironment::setUpRenderSystem() +{ + rviz_rendering::RenderSystem::get(); +} + +Ogre::RenderWindow * OgreTestingEnvironment::createOgreRenderWindow() +{ + auto test = new rviz_rendering::RenderWindow(); + return rviz_rendering::RenderSystem::get()->makeRenderWindow(test->winId(), 10, 10, 1.0); +} + +} // end namespace rviz_default_plugins diff --git a/rviz_default_plugins/test/rviz_default_plugins/ogre_testing_environment.hpp b/rviz_default_plugins/test/rviz_default_plugins/ogre_testing_environment.hpp new file mode 100644 index 000000000..145542022 --- /dev/null +++ b/rviz_default_plugins/test/rviz_default_plugins/ogre_testing_environment.hpp @@ -0,0 +1,55 @@ +/* + * Copyright (c) 2017, Bosch Software Innovations GmbH. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef RVIZ_DEFAULT_PLUGINS__OGRE_TESTING_ENVIRONMENT_HPP_ +#define RVIZ_DEFAULT_PLUGINS__OGRE_TESTING_ENVIRONMENT_HPP_ + +#include + +namespace rviz_default_plugins +{ +class OgreTestingEnvironment +{ +public: + /** + * Set up a testing environment to run tests needing Ogre. + * + * @param: bool debug, if true, all logging of Ogre is send to std::out, if false no logging + * occurs. Since the logging pollutes the test output, it defaults to false + */ + void setUpOgreTestEnvironment(bool debug = false); + + void setUpRenderSystem(); + + Ogre::RenderWindow * createOgreRenderWindow(); +}; + +} // namespace rviz_default_plugins + +#endif // RVIZ_DEFAULT_PLUGINS__OGRE_TESTING_ENVIRONMENT_HPP_ diff --git a/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp index d6d54ca3d..55fc90d9c 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp @@ -49,12 +49,12 @@ #include "rviz_default_plugins/robot/robot_joint.hpp" #include "rviz_default_plugins/robot/robot_link.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../ogre_testing_environment.hpp" #include "./mock_link_updater.hpp" #include "../mock_display_context.hpp" #include "../mock_handler_manager.hpp" #include "../mock_selection_manager.hpp" -#include "../scene_graph_introspection_helper.hpp" +#include "../scene_graph_introspection.hpp" using namespace ::testing; // NOLINT using namespace rviz_default_plugins::robot; // NOLINT @@ -66,7 +66,7 @@ class RobotTestFixture : public Test public: static void SetUpTestCase() { - testing_environment_ = std::make_shared(); + testing_environment_ = std::make_shared(); testing_environment_->setUpOgreTestEnvironment(); scene_manager_ = Ogre::Root::getSingletonPtr()->createSceneManager(); @@ -99,7 +99,7 @@ class RobotTestFixture : public Test Ogre::Root::getSingletonPtr()->destroySceneManager(scene_manager_); } - static std::shared_ptr testing_environment_; + static std::shared_ptr testing_environment_; static Ogre::SceneManager * scene_manager_; urdf::Model urdf_model_; @@ -112,7 +112,7 @@ class RobotTestFixture : public Test }; Ogre::SceneManager * RobotTestFixture::scene_manager_ = nullptr; -std::shared_ptr +std::shared_ptr RobotTestFixture::testing_environment_ = nullptr; TEST_F(RobotTestFixture, load_gets_the_correct_link_and_joint_count) { diff --git a/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection.cpp b/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection.cpp new file mode 100644 index 000000000..e6d322b27 --- /dev/null +++ b/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection.cpp @@ -0,0 +1,233 @@ +/* + * Copyright (c) 2018, Bosch Software Innovations GmbH. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted (subject to the limitations in the disclaimer + * below) provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +#include +#include +#include + +#include "rviz_rendering/objects/arrow.hpp" +#include "rviz_rendering/objects/point_cloud.hpp" +#include "rviz_rendering/objects/shape.hpp" + +#include "scene_graph_introspection.hpp" + +namespace rviz_default_plugins +{ + +void assertArrowWithTransform( + Ogre::SceneManager * scene_manager, + Ogre::Vector3 position, + Ogre::Vector3 scale, + Ogre::Quaternion orientation) +{ + auto arrow_scene_node = findOneArrow(scene_manager->getRootSceneNode()); + ASSERT_TRUE(arrow_scene_node); + EXPECT_THAT(arrow_scene_node->getPosition(), Vector3Eq(position)); + // Have to mangle the scale because of the default orientation of the cylinders (see arrow.cpp). + EXPECT_THAT(arrow_scene_node->getScale(), Vector3Eq(Ogre::Vector3(scale.z, scale.x, scale.y))); + EXPECT_THAT(arrow_scene_node->getOrientation(), QuaternionEq(orientation)); +} + +bool axesAreVisible(Ogre::SceneNode * scene_node) +{ + bool axes_are_visible = true; + for (uint16_t i = 0; i < 3; ++i) { + auto child_node = dynamic_cast(scene_node->getChild(i)->getChild(0)); + auto entity = dynamic_cast(child_node->getAttachedObject(0)); + axes_are_visible = entity ? axes_are_visible && entity->isVisible() : false; + } + + return axes_are_visible; +} + +bool arrowIsVisible(Ogre::SceneNode * scene_node) +{ + auto arrow_head = findEntityByMeshName( + scene_node, "rviz_cone.mesh"); + auto arrow_shaft = findEntityByMeshName( + scene_node, "rviz_cylinder.mesh"); + + return arrow_head->isVisible() && arrow_shaft->isVisible(); +} + +std::vector findAllEntitiesByMeshName( + Ogre::SceneNode * scene_node, const Ogre::String & resource_name) +{ + std::vector all_entities = + findAllOgreObjectByType(scene_node, "Entity"); + + std::vector correct_entities; + for (const auto & entity : all_entities) { + if (entity->getMesh() && entity->getMesh()->getName() == resource_name) { + correct_entities.push_back(entity); + } + } + + return correct_entities; +} + +Ogre::Entity * findEntityByMeshName( + Ogre::SceneNode * scene_node, const Ogre::String & resource_name) +{ + auto entities = findAllEntitiesByMeshName(scene_node, resource_name); + return entities.empty() ? nullptr : entities[0]; +} + +std::vector findAllSpheres(Ogre::SceneNode * scene_node) +{ + return findAllEntitiesByMeshName(scene_node, "rviz_sphere.mesh"); +} + +std::vector findAllCones(Ogre::SceneNode * scene_node) +{ + return findAllEntitiesByMeshName(scene_node, "rviz_cone.mesh"); +} + +std::vector findAllCylinders(Ogre::SceneNode * scene_node) +{ + return findAllEntitiesByMeshName(scene_node, "rviz_cylinder.mesh"); +} + +Ogre::BillboardChain * findOneBillboardChain(Ogre::SceneNode * scene_node) +{ + auto objects = findAllOgreObjectByType(scene_node, "BillboardChain"); + return objects.empty() ? nullptr : objects[0]; +} + +rviz_rendering::MovableText * findOneMovableText(Ogre::SceneNode * scene_node) +{ + auto objects = findAllOgreObjectByType(scene_node, "MovableText"); + return objects.empty() ? nullptr : objects[0]; +} + +Ogre::ManualObject * findOneManualObject(Ogre::SceneNode * scene_node) +{ + auto objects = findAllOgreObjectByType(scene_node, "ManualObject"); + return objects.empty() ? nullptr : objects[0]; +} + +rviz_rendering::PointCloud * findOnePointCloud(Ogre::SceneNode * scene_node) +{ + auto point_clouds = findAllPointClouds(scene_node); + return point_clouds.empty() ? nullptr : point_clouds[0]; +} + +std::vector findAllPointClouds(Ogre::SceneNode * scene_node) +{ + return findAllOgreObjectByType(scene_node, "PointCloud"); +} + +std::vector findAllArrows(Ogre::SceneNode * scene_node) +{ + std::vector arrows; + auto head_entities = findAllEntitiesByMeshName(scene_node, "rviz_cone.mesh"); + if (!head_entities.empty()) { + for (auto const & head_entity : head_entities) { + auto arrow_scene_node = head_entity + ->getParentSceneNode() // OffsetNode from head_entity + ->getParentSceneNode() // SceneNode from head_entity + ->getParentSceneNode(); // SceneNode from arrow + if (arrow_scene_node) { + auto shaft_entity = findEntityByMeshName(arrow_scene_node, "rviz_cylinder.mesh"); + if (shaft_entity && + shaft_entity->getParentSceneNode()->getParentSceneNode()->getParentSceneNode() == + arrow_scene_node) + { + arrows.push_back(arrow_scene_node); + } + } + } + } + return arrows; +} + +Ogre::SceneNode * findOneArrow(Ogre::SceneNode * scene_node) +{ + auto arrows = findAllArrows(scene_node); + return arrows.empty() ? nullptr : arrows[0]; +} + +std::vector findAllAxes(Ogre::SceneNode * scene_node) +{ + std::vector axes; + auto cylinder_entities = findAllEntitiesByMeshName(scene_node, "rviz_cylinder.mesh"); + if (!cylinder_entities.empty()) { + for (auto const & cylinder_entity : cylinder_entities) { + auto axes_scene_node = cylinder_entity + ->getParentSceneNode() // OffsetNode from cylinder_entity + ->getParentSceneNode() // SceneNode from cylinder_entity + ->getParentSceneNode(); // SceneNode from axes + if (axes_scene_node) { + auto local_cylinder_entities = findAllEntitiesByMeshName( + axes_scene_node, "rviz_cylinder.mesh"); + if (local_cylinder_entities.size() == 3 && + std::find(axes.begin(), axes.end(), axes_scene_node) == axes.end()) + { + axes.push_back(axes_scene_node); + } + } + } + } + return axes; +} + +Ogre::SceneNode * findOneAxes(Ogre::SceneNode * scene_node) +{ + auto axes = findAllAxes(scene_node); + return axes.empty() ? nullptr : axes[0]; +} + +std::vector getPositionsFromNodes(const std::vector & nodes) +{ + std::vector positions(nodes.size(), Ogre::Vector3::ZERO); + std::transform( + nodes.cbegin(), nodes.cend(), positions.begin(), [](auto node) { + return node->getPosition(); + }); + return positions; +} + +std::vector getOrientationsFromNodes(const std::vector & nodes) +{ + std::vector orientations(nodes.size(), Ogre::Quaternion::IDENTITY); + std::transform( + nodes.cbegin(), nodes.cend(), orientations.begin(), [](auto node) { + return node->getOrientation(); + }); + return orientations; +} + +} // namespace rviz_default_plugins diff --git a/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection_helper.hpp b/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection.hpp similarity index 54% rename from rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection_helper.hpp rename to rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection.hpp index fe71f5fbe..6f7c75b0f 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection_helper.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection.hpp @@ -29,8 +29,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef RVIZ_DEFAULT_PLUGINS__SCENE_GRAPH_INTROSPECTION_HELPER_HPP_ -#define RVIZ_DEFAULT_PLUGINS__SCENE_GRAPH_INTROSPECTION_HELPER_HPP_ +#ifndef RVIZ_DEFAULT_PLUGINS__SCENE_GRAPH_INTROSPECTION_HPP_ +#define RVIZ_DEFAULT_PLUGINS__SCENE_GRAPH_INTROSPECTION_HPP_ #include @@ -69,15 +69,76 @@ MATCHER_P(ColourValueEq, expected, "") { namespace rviz_default_plugins { -bool arrowIsVisible(Ogre::SceneNode * scene_node); - -bool axesAreVisible(Ogre::SceneNode * scene_node); - void assertArrowWithTransform( Ogre::SceneManager * scene_manager, Ogre::Vector3 position, Ogre::Vector3 scale, Ogre::Quaternion orientation); + +bool axesAreVisible(Ogre::SceneNode * scene_node); + +bool arrowIsVisible(Ogre::SceneNode * scene_manager); + +std::vector findAllArrows(Ogre::SceneNode * scene_node); +Ogre::SceneNode * findOneArrow(Ogre::SceneNode * scene_node); + +std::vector findAllAxes(Ogre::SceneNode * scene_node); +Ogre::SceneNode * findOneAxes(Ogre::SceneNode * scene_node); + +std::vector getPositionsFromNodes(const std::vector & nodes); +std::vector +getOrientationsFromNodes(const std::vector & nodes); + +std::vector findAllEntitiesByMeshName( + Ogre::SceneNode * scene_node, const Ogre::String & resource_name); +Ogre::Entity * findEntityByMeshName( + Ogre::SceneNode * scene_node, const Ogre::String & resource_name); + +std::vector findAllSpheres(Ogre::SceneNode * scene_node); +std::vector findAllCones(Ogre::SceneNode * scene_node); +std::vector findAllCylinders(Ogre::SceneNode * scene_node); + +std::vector findAllPointClouds(Ogre::SceneNode * scene_node); +rviz_rendering::PointCloud * findOnePointCloud(Ogre::SceneNode * scene_node); + +Ogre::BillboardChain * findOneBillboardChain(Ogre::SceneNode * scene_node); + +rviz_rendering::MovableText * findOneMovableText(Ogre::SceneNode * scene_node); + +Ogre::ManualObject * findOneManualObject(Ogre::SceneNode * scene_node); + +template +void findAllObjectsAttached( + Ogre::SceneNode * scene_node, const Ogre::String & type, std::vector & objects) +{ + auto attached_objects = scene_node->getAttachedObjects(); + for (const auto & object : attached_objects) { + if (object->getMovableType() == type) { + auto entity = dynamic_cast(object); + if (entity) { + objects.push_back(entity); + } + } + } +} + +template +std::vector findAllOgreObjectByType(Ogre::SceneNode * scene_node, Ogre::String type) +{ + std::vector objects_vector; + findAllObjectsAttached(scene_node, type, objects_vector); + for (auto child_node : scene_node->getChildren()) { + auto child_scene_node = dynamic_cast(child_node); + if (child_scene_node != nullptr) { + auto child_objects_vector = findAllOgreObjectByType(child_scene_node, type); + objects_vector.insert( + objects_vector.cend(), child_objects_vector.begin(), child_objects_vector.end()); + } + } + + return objects_vector; +} + } // namespace rviz_default_plugins -#endif // RVIZ_DEFAULT_PLUGINS__SCENE_GRAPH_INTROSPECTION_HELPER_HPP_ +#endif // RVIZ_DEFAULT_PLUGINS__SCENE_GRAPH_INTROSPECTION_HPP_ diff --git a/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection_helper.cpp b/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection_helper.cpp deleted file mode 100644 index 288ad75f3..000000000 --- a/rviz_default_plugins/test/rviz_default_plugins/scene_graph_introspection_helper.cpp +++ /dev/null @@ -1,87 +0,0 @@ -/* - * Copyright (c) 2018, Bosch Software Innovations GmbH. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted (subject to the limitations in the disclaimer - * below) provided that the following conditions are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of the copyright holder nor the names of its - * contributors may be used to endorse or promote products derived from - * this software without specific prior written permission. - * - * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS - * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, - * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#include - -#include -#include -#include -#include - -#include -#include -#include - -#include "rviz_rendering/objects/arrow.hpp" -#include "rviz_rendering/objects/point_cloud.hpp" -#include "rviz_rendering/objects/shape.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" - -#include "scene_graph_introspection_helper.hpp" - -namespace rviz_default_plugins -{ - -bool arrowIsVisible(Ogre::SceneNode * scene_node) -{ - auto arrow_head = rviz_rendering::findEntityByMeshName(scene_node, "rviz_cone.mesh"); - auto arrow_shaft = rviz_rendering::findEntityByMeshName(scene_node, "rviz_cylinder.mesh"); - - return arrow_head->isVisible() && arrow_shaft->isVisible(); -} - -void assertArrowWithTransform( - Ogre::SceneManager * scene_manager, - Ogre::Vector3 position, - Ogre::Vector3 scale, - Ogre::Quaternion orientation) -{ - auto arrow_scene_node = rviz_rendering::findOneArrow(scene_manager->getRootSceneNode()); - ASSERT_TRUE(arrow_scene_node); - EXPECT_THAT(arrow_scene_node->getPosition(), Vector3Eq(position)); - // Have to mangle the scale because of the default orientation of the cylinders (see arrow.cpp). - EXPECT_THAT(arrow_scene_node->getScale(), Vector3Eq(Ogre::Vector3(scale.z, scale.x, scale.y))); - EXPECT_THAT(arrow_scene_node->getOrientation(), QuaternionEq(orientation)); -} - -bool axesAreVisible(Ogre::SceneNode * scene_node) -{ - bool axes_are_visible = true; - for (uint16_t i = 0; i < 3; ++i) { - auto child_node = dynamic_cast(scene_node->getChild(i)->getChild(0)); - auto entity = dynamic_cast(child_node->getAttachedObject(0)); - axes_are_visible = entity ? axes_are_visible && entity->isVisible() : false; - } - - return axes_are_visible; -} - -} // namespace rviz_default_plugins diff --git a/rviz_default_plugins/test/rviz_default_plugins/tools/measure/measure_tool_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/tools/measure/measure_tool_test.cpp index d1829ca25..48629b52c 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/tools/measure/measure_tool_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/tools/measure/measure_tool_test.cpp @@ -41,8 +41,7 @@ #include "../tool_test_fixture.hpp" #include "../../displays/display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../../scene_graph_introspection.hpp" #include "../../mock_display_context.hpp" #include "../../mock_view_picker.hpp" @@ -85,7 +84,7 @@ TEST_F(MeasureToolTestFixture, choosing_two_objects_shows_a_line_and_the_distanc EXPECT_CALL(*context_, setStatus(_)).WillOnce(SaveArg<0>(&status)); measure_tool_->processMouseEvent(click); - auto line = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto line = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); // Use bounding box to indirectly assert the vertices ASSERT_TRUE(line->isVisible()); EXPECT_THAT(line->getBoundingBox().getMinimum(), Vector3Eq(obj1.position)); @@ -105,7 +104,7 @@ TEST_F(MeasureToolTestFixture, hovering_over_a_second_object_updates_the_line_an EXPECT_CALL(*context_, setStatus(_)).WillOnce(SaveArg<0>(&status)); measure_tool_->processMouseEvent(move); - auto line = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto line = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); // Use bounding box to indirectly assert the vertices ASSERT_TRUE(line->isVisible()); EXPECT_THAT(line->getBoundingBox().getMinimum(), Vector3Eq(obj1.position)); @@ -123,7 +122,7 @@ TEST_F(MeasureToolTestFixture, right_clicking_removes_the_measurement_line) { click = generateMouseLeftClick(obj2.x, obj2.y); measure_tool_->processMouseEvent(click); - auto line = rviz_rendering::findOneManualObject(scene_manager_->getRootSceneNode()); + auto line = rviz_default_plugins::findOneManualObject(scene_manager_->getRootSceneNode()); ASSERT_TRUE(line->isVisible()); click = generateMouseRightClick(5, 5); diff --git a/rviz_default_plugins/test/rviz_default_plugins/tools/pose/pose_tool_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/tools/pose/pose_tool_test.cpp index 5e2abe406..58dff0780 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/tools/pose/pose_tool_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/tools/pose/pose_tool_test.cpp @@ -39,10 +39,9 @@ #include "rviz_default_plugins/tools/pose/pose_tool.hpp" #include "rviz_rendering/viewport_projection_finder.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../../scene_graph_introspection.hpp" #include "../tool_test_fixture.hpp" #include "../../displays/display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" #include "../../mock_display_context.hpp" using namespace ::testing; // NOLINT @@ -91,7 +90,7 @@ class PoseToolTestFixture : public ToolTestFixture, public DisplayTestFixture }; TEST_F(PoseToolTestFixture, onInitialize_sets_arrow_invisible_at_first) { - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); ASSERT_THAT(arrows, SizeIs(1)); EXPECT_FALSE(rviz_default_plugins::arrowIsVisible(arrows[0])); @@ -101,7 +100,7 @@ TEST_F(PoseToolTestFixture, processMouseEvent_sets_arrow_position_below_mouse_cu auto left_click_event = generateMousePressEvent(10, 15); pose_tool_->processMouseEvent(left_click_event); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); ASSERT_THAT(arrows, SizeIs(1)); EXPECT_FALSE(rviz_default_plugins::arrowIsVisible(arrows[0])); EXPECT_THAT(arrows[0]->getPosition(), Vector3Eq(Ogre::Vector3(10, 15, 0))); @@ -115,7 +114,7 @@ TEST_F( pose_tool_->processMouseEvent(left_click_event); pose_tool_->processMouseEvent(move_mouse_event); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); auto expected_orientation = Ogre::Quaternion(-0.270598f, -0.653282f, 0.270598f, -0.653282f); ASSERT_THAT(arrows, SizeIs(1)); EXPECT_TRUE(rviz_default_plugins::arrowIsVisible(arrows[0])); @@ -130,7 +129,7 @@ TEST_F(PoseToolTestFixture, deactivate_makes_arrow_invisible) { pose_tool_->processMouseEvent(move_mouse_event); pose_tool_->deactivate(); - auto arrows = rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()); + auto arrows = rviz_default_plugins::findAllArrows(scene_manager_->getRootSceneNode()); ASSERT_THAT(arrows, SizeIs(1)); EXPECT_FALSE(rviz_default_plugins::arrowIsVisible(arrows[0])); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp index 2ff7ea8a4..4348e9618 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp @@ -46,7 +46,7 @@ #include "rviz_default_plugins/view_controllers/orbit/orbit_view_controller.hpp" #include "../../displays/display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "../view_controller_test_fixture.hpp" using namespace ::testing; // NOLINT diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp index 2c218ce79..ace3a814b 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp @@ -48,7 +48,7 @@ #include "rviz_default_plugins/view_controllers/ortho/fixed_orientation_ortho_view_controller.hpp" #include "../../displays/display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "../view_controller_test_fixture.hpp" using namespace ::testing; // NOLINT diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp index 145b721cd..99fc7e69d 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp @@ -48,7 +48,7 @@ #include "rviz_default_plugins/view_controllers/orbit/orbit_view_controller.hpp" #include "../view_controller_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" using namespace ::testing; // NOLINT diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp index 67be2fd4d..d811202d6 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp @@ -47,7 +47,7 @@ #include "rviz_default_plugins/view_controllers/ortho/fixed_orientation_ortho_view_controller.hpp" #include "../../displays/display_test_fixture.hpp" -#include "../../scene_graph_introspection_helper.hpp" +#include "../../scene_graph_introspection.hpp" #include "../view_controller_test_fixture.hpp" using namespace ::testing; // NOLINT diff --git a/rviz_rendering/CMakeLists.txt b/rviz_rendering/CMakeLists.txt index 4dfe762b7..c3dccd255 100644 --- a/rviz_rendering/CMakeLists.txt +++ b/rviz_rendering/CMakeLists.txt @@ -93,8 +93,6 @@ add_library(rviz_rendering SHARED src/rviz_rendering/objects/point_cloud_renderable.cpp src/rviz_rendering/objects/shape.cpp src/rviz_rendering/objects/wrench_visual.cpp - test/rviz_rendering/ogre_testing_environment.cpp - test/rviz_rendering/scene_graph_introspection.cpp ) target_link_libraries(rviz_rendering @@ -169,6 +167,16 @@ if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) find_package(ament_cmake_gtest REQUIRED) + add_library(rviz_rendering_test_utils + test/rviz_rendering/ogre_testing_environment.cpp + test/rviz_rendering/scene_graph_introspection.cpp + ) + target_link_libraries(rviz_rendering_test_utils + PUBLIC + rviz_ogre_vendor::OgreMain + rviz_rendering + ) + ament_add_gmock(string_helper_test test/rviz_rendering/string_helper_test.cpp) if(TARGET string_helper_test) target_link_libraries(string_helper_test rviz_rendering) @@ -181,6 +189,7 @@ if(BUILD_TESTING) target_link_libraries(point_cloud_test_target rviz_ogre_vendor::OgreMain rviz_rendering + rviz_rendering_test_utils Qt5::Widgets # explicitly do this for include directories (not necessary for external use) ) endif() @@ -192,6 +201,7 @@ if(BUILD_TESTING) target_link_libraries(point_cloud_renderable_test_target rviz_ogre_vendor::OgreMain rviz_rendering + rviz_rendering_test_utils Qt5::Widgets # explicitly do this for include directories (not necessary for external use) ) endif() @@ -203,6 +213,7 @@ if(BUILD_TESTING) target_link_libraries(billboard_line_test_target rviz_ogre_vendor::OgreMain rviz_rendering + rviz_rendering_test_utils Qt5::Widgets # explicitly do this for include directories (not necessary for external use) ) endif() @@ -214,6 +225,7 @@ if(BUILD_TESTING) target_link_libraries(covariance_visual_test_target rviz_ogre_vendor::OgreMain rviz_rendering + rviz_rendering_test_utils Qt5::Widgets # explicitly do this for include directories (not necessary for external use) ) endif() @@ -225,6 +237,7 @@ if(BUILD_TESTING) target_link_libraries(grid_test_target rviz_ogre_vendor::OgreMain rviz_rendering + rviz_rendering_test_utils Qt5::Widgets # explicitly do this for include directories (not necessary for external use) ) endif() @@ -237,6 +250,7 @@ if(BUILD_TESTING) rviz_ogre_vendor::OgreMain rviz_ogre_vendor::OgreOverlay rviz_rendering + rviz_rendering_test_utils Qt5::Widgets ) endif() @@ -248,6 +262,7 @@ if(BUILD_TESTING) target_link_libraries(line_test_target rviz_ogre_vendor::OgreMain rviz_rendering + rviz_rendering_test_utils Qt5::Widgets # explicitly do this for include directories (not necessary for external use) ) endif() @@ -259,6 +274,7 @@ if(BUILD_TESTING) target_link_libraries(wrench_visual_test_target rviz_ogre_vendor::OgreMain rviz_rendering + rviz_rendering_test_utils Qt5::Widgets # explicitly do this for include directories (not necessary for external use) ) endif() diff --git a/rviz_rendering/src/rviz_rendering/render_system.hpp b/rviz_rendering/include/rviz_rendering/render_system.hpp similarity index 99% rename from rviz_rendering/src/rviz_rendering/render_system.hpp rename to rviz_rendering/include/rviz_rendering/render_system.hpp index bec45fcb8..6f457a945 100644 --- a/rviz_rendering/src/rviz_rendering/render_system.hpp +++ b/rviz_rendering/include/rviz_rendering/render_system.hpp @@ -59,6 +59,7 @@ class RenderSystem RenderSystem * get(); + RVIZ_RENDERING_PUBLIC Ogre::RenderWindow * makeRenderWindow( WindowIDType window_id, diff --git a/rviz_rendering/src/rviz_rendering/ogre_render_window_impl.cpp b/rviz_rendering/src/rviz_rendering/ogre_render_window_impl.cpp index bed533347..a80a6bc2b 100644 --- a/rviz_rendering/src/rviz_rendering/ogre_render_window_impl.cpp +++ b/rviz_rendering/src/rviz_rendering/ogre_render_window_impl.cpp @@ -46,7 +46,7 @@ #include #include "rviz_rendering/orthographic.hpp" -#include "./render_system.hpp" +#include "rviz_rendering/render_system.hpp" #include "rviz_rendering/objects/grid.hpp" #include "rviz_rendering/logging.hpp" diff --git a/rviz_rendering/src/rviz_rendering/ogre_render_window_impl.hpp b/rviz_rendering/src/rviz_rendering/ogre_render_window_impl.hpp index 760f5c614..e978841d3 100644 --- a/rviz_rendering/src/rviz_rendering/ogre_render_window_impl.hpp +++ b/rviz_rendering/src/rviz_rendering/ogre_render_window_impl.hpp @@ -42,7 +42,7 @@ #include // NOLINT: cpplint cannot handle include order here #include // NOLINT: cpplint cannot handle include order here -#include "render_system.hpp" +#include "rviz_rendering/render_system.hpp" namespace Ogre { diff --git a/rviz_rendering/src/rviz_rendering/render_system.cpp b/rviz_rendering/src/rviz_rendering/render_system.cpp index 836adb9c6..1765e804e 100644 --- a/rviz_rendering/src/rviz_rendering/render_system.cpp +++ b/rviz_rendering/src/rviz_rendering/render_system.cpp @@ -29,7 +29,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "render_system.hpp" +#include "rviz_rendering/render_system.hpp" #include #include diff --git a/rviz_rendering/test/rviz_rendering/objects/billboard_line_test.cpp b/rviz_rendering/test/rviz_rendering/objects/billboard_line_test.cpp index ed03d253e..d3d00a57a 100644 --- a/rviz_rendering/test/rviz_rendering/objects/billboard_line_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/billboard_line_test.cpp @@ -37,7 +37,7 @@ #include #include -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../ogre_testing_environment.hpp" #include "rviz_rendering/objects/billboard_line.hpp" using namespace ::testing; // NOLINT diff --git a/rviz_rendering/test/rviz_rendering/objects/covariance_visual_test.cpp b/rviz_rendering/test/rviz_rendering/objects/covariance_visual_test.cpp index 26df87f75..0e25592e0 100644 --- a/rviz_rendering/test/rviz_rendering/objects/covariance_visual_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/covariance_visual_test.cpp @@ -39,8 +39,8 @@ #include "rviz_rendering/objects/covariance_visual.hpp" #include "../matcher.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../ogre_testing_environment.hpp" +#include "../scene_graph_introspection.hpp" using namespace ::testing; // NOLINT using rviz_rendering::findAllCones; diff --git a/rviz_rendering/test/rviz_rendering/objects/grid_test.cpp b/rviz_rendering/test/rviz_rendering/objects/grid_test.cpp index 82a128ee4..36707c8d3 100644 --- a/rviz_rendering/test/rviz_rendering/objects/grid_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/grid_test.cpp @@ -38,7 +38,7 @@ #include #include -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../ogre_testing_environment.hpp" #include "rviz_rendering/objects/grid.hpp" #include "rviz_rendering/objects/billboard_line.hpp" diff --git a/rviz_rendering/test/rviz_rendering/objects/line_test.cpp b/rviz_rendering/test/rviz_rendering/objects/line_test.cpp index 9fe60ef72..16c16d6aa 100644 --- a/rviz_rendering/test/rviz_rendering/objects/line_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/line_test.cpp @@ -38,7 +38,7 @@ #include #include "rviz_rendering/objects/line.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../ogre_testing_environment.hpp" #include "../matcher.hpp" diff --git a/rviz_rendering/test/rviz_rendering/objects/movable_text_test.cpp b/rviz_rendering/test/rviz_rendering/objects/movable_text_test.cpp index f1c3a4f16..360d3fe0f 100644 --- a/rviz_rendering/test/rviz_rendering/objects/movable_text_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/movable_text_test.cpp @@ -37,7 +37,7 @@ #include // NOLINT: cpplint cannot handle include order here #include "rviz_rendering/objects/movable_text.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../ogre_testing_environment.hpp" #include "../matcher.hpp" diff --git a/rviz_rendering/test/rviz_rendering/objects/point_cloud_renderable_test.cpp b/rviz_rendering/test/rviz_rendering/objects/point_cloud_renderable_test.cpp index 23210ead4..54badd6e9 100644 --- a/rviz_rendering/test/rviz_rendering/objects/point_cloud_renderable_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/point_cloud_renderable_test.cpp @@ -37,7 +37,7 @@ #include "rviz_rendering/objects/point_cloud.hpp" #include "rviz_rendering/objects/point_cloud_renderable.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../ogre_testing_environment.hpp" using namespace ::testing; // NOLINT diff --git a/rviz_rendering/test/rviz_rendering/objects/point_cloud_test.cpp b/rviz_rendering/test/rviz_rendering/objects/point_cloud_test.cpp index 23c4b45f7..767f3a78d 100644 --- a/rviz_rendering/test/rviz_rendering/objects/point_cloud_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/point_cloud_test.cpp @@ -42,7 +42,7 @@ #include "rviz_rendering/objects/point_cloud.hpp" #include "rviz_rendering/render_window.hpp" #include "rviz_rendering/custom_parameter_indices.hpp" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "../ogre_testing_environment.hpp" #include "../matcher.hpp" diff --git a/rviz_rendering/test/rviz_rendering/objects/wrench_visual_test.cpp b/rviz_rendering/test/rviz_rendering/objects/wrench_visual_test.cpp index c6c199f78..8ef0d7549 100644 --- a/rviz_rendering/test/rviz_rendering/objects/wrench_visual_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/wrench_visual_test.cpp @@ -37,8 +37,8 @@ #include #include -#include "test/rviz_rendering/ogre_testing_environment.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "../ogre_testing_environment.hpp" +#include "../scene_graph_introspection.hpp" #include "rviz_rendering/objects/wrench_visual.hpp" #include "rviz_rendering/objects/billboard_line.hpp" #include "rviz_rendering/objects/arrow.hpp" diff --git a/rviz_rendering/test/rviz_rendering/ogre_testing_environment.cpp b/rviz_rendering/test/rviz_rendering/ogre_testing_environment.cpp index 0da848d65..2cea3fe5a 100644 --- a/rviz_rendering/test/rviz_rendering/ogre_testing_environment.cpp +++ b/rviz_rendering/test/rviz_rendering/ogre_testing_environment.cpp @@ -27,23 +27,30 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "ogre_testing_environment.hpp" -#include "rviz_rendering/render_window.hpp" -#include "../src/rviz_rendering/render_system.hpp" +#include + +#include + +#include "rviz_rendering/render_system.hpp" namespace rviz_rendering { -void OgreTestingEnvironment::setUpRenderSystem() +void OgreTestingEnvironment::setUpOgreTestEnvironment(bool debug) { - RenderSystem::get(); + if (!debug) { + const std::string & name = ""; + auto lm = new Ogre::LogManager(); + lm->createLog(name, false, debug, true); + } + setUpRenderSystem(); } -Ogre::RenderWindow * OgreTestingEnvironment::createOgreRenderWindow() +void OgreTestingEnvironment::setUpRenderSystem() { - auto test = new rviz_rendering::RenderWindow(); - return RenderSystem::get()->makeRenderWindow(test->winId(), 10, 10, 1.0); + RenderSystem::get(); } } // end namespace rviz_rendering diff --git a/rviz_rendering/include/test/rviz_rendering/ogre_testing_environment.hpp b/rviz_rendering/test/rviz_rendering/ogre_testing_environment.hpp similarity index 82% rename from rviz_rendering/include/test/rviz_rendering/ogre_testing_environment.hpp rename to rviz_rendering/test/rviz_rendering/ogre_testing_environment.hpp index 78e920457..c3b74e710 100644 --- a/rviz_rendering/include/test/rviz_rendering/ogre_testing_environment.hpp +++ b/rviz_rendering/test/rviz_rendering/ogre_testing_environment.hpp @@ -30,16 +30,9 @@ #ifndef RVIZ_RENDERING__OGRE_TESTING_ENVIRONMENT_HPP_ #define RVIZ_RENDERING__OGRE_TESTING_ENVIRONMENT_HPP_ -#include - -#include -#include - -#include "rviz_rendering/visibility_control.hpp" - namespace rviz_rendering { -class RVIZ_RENDERING_PUBLIC OgreTestingEnvironment +class OgreTestingEnvironment { public: /** @@ -48,19 +41,9 @@ class RVIZ_RENDERING_PUBLIC OgreTestingEnvironment * @param: bool debug, if true, all logging of Ogre is send to std::out, if false no logging * occurs. Since the logging pollutes the test output, it defaults to false */ - void setUpOgreTestEnvironment(bool debug = false) - { - if (!debug) { - const std::string & name = ""; - auto lm = new Ogre::LogManager(); - lm->createLog(name, false, debug, true); - } - setUpRenderSystem(); - } + void setUpOgreTestEnvironment(bool debug = false); void setUpRenderSystem(); - - Ogre::RenderWindow * createOgreRenderWindow(); }; } // namespace rviz_rendering diff --git a/rviz_rendering/test/rviz_rendering/scene_graph_introspection.cpp b/rviz_rendering/test/rviz_rendering/scene_graph_introspection.cpp index 4b6acaaf0..cf7c13f2c 100644 --- a/rviz_rendering/test/rviz_rendering/scene_graph_introspection.cpp +++ b/rviz_rendering/test/rviz_rendering/scene_graph_introspection.cpp @@ -42,21 +42,11 @@ #include "rviz_rendering/objects/point_cloud.hpp" #include "rviz_rendering/objects/shape.hpp" -#include "test/rviz_rendering/scene_graph_introspection.hpp" +#include "scene_graph_introspection.hpp" namespace rviz_rendering { -bool arrowIsVisible(Ogre::SceneNode * scene_node) -{ - auto arrow_head = findEntityByMeshName( - scene_node, "rviz_cone.mesh"); - auto arrow_shaft = findEntityByMeshName( - scene_node, "rviz_cylinder.mesh"); - - return arrow_head->isVisible() && arrow_shaft->isVisible(); -} - std::vector findAllEntitiesByMeshName( Ogre::SceneNode * scene_node, const Ogre::String & resource_name) { @@ -101,24 +91,6 @@ Ogre::BillboardChain * findOneBillboardChain(Ogre::SceneNode * scene_node) return objects.empty() ? nullptr : objects[0]; } -rviz_rendering::MovableText * findOneMovableText(Ogre::SceneNode * scene_node) -{ - auto objects = findAllOgreObjectByType(scene_node, "MovableText"); - return objects.empty() ? nullptr : objects[0]; -} - -Ogre::ManualObject * findOneManualObject(Ogre::SceneNode * scene_node) -{ - auto objects = findAllOgreObjectByType(scene_node, "ManualObject"); - return objects.empty() ? nullptr : objects[0]; -} - -rviz_rendering::PointCloud * findOnePointCloud(Ogre::SceneNode * scene_node) -{ - auto point_clouds = findAllPointClouds(scene_node); - return point_clouds.empty() ? nullptr : point_clouds[0]; -} - std::vector findAllPointClouds(Ogre::SceneNode * scene_node) { return findAllOgreObjectByType(scene_node, "PointCloud"); @@ -148,12 +120,6 @@ std::vector findAllArrows(Ogre::SceneNode * scene_node) return arrows; } -Ogre::SceneNode * findOneArrow(Ogre::SceneNode * scene_node) -{ - auto arrows = findAllArrows(scene_node); - return arrows.empty() ? nullptr : arrows[0]; -} - std::vector findAllAxes(Ogre::SceneNode * scene_node) { std::vector axes; @@ -178,30 +144,4 @@ std::vector findAllAxes(Ogre::SceneNode * scene_node) return axes; } -Ogre::SceneNode * findOneAxes(Ogre::SceneNode * scene_node) -{ - auto axes = findAllAxes(scene_node); - return axes.empty() ? nullptr : axes[0]; -} - -std::vector getPositionsFromNodes(const std::vector & nodes) -{ - std::vector positions(nodes.size(), Ogre::Vector3::ZERO); - std::transform( - nodes.cbegin(), nodes.cend(), positions.begin(), [](auto node) { - return node->getPosition(); - }); - return positions; -} - -std::vector getOrientationsFromNodes(const std::vector & nodes) -{ - std::vector orientations(nodes.size(), Ogre::Quaternion::IDENTITY); - std::transform( - nodes.cbegin(), nodes.cend(), orientations.begin(), [](auto node) { - return node->getOrientation(); - }); - return orientations; -} - } // namespace rviz_rendering diff --git a/rviz_rendering/include/test/rviz_rendering/scene_graph_introspection.hpp b/rviz_rendering/test/rviz_rendering/scene_graph_introspection.hpp similarity index 80% rename from rviz_rendering/include/test/rviz_rendering/scene_graph_introspection.hpp rename to rviz_rendering/test/rviz_rendering/scene_graph_introspection.hpp index 89225b9a0..ccadeb58b 100644 --- a/rviz_rendering/include/test/rviz_rendering/scene_graph_introspection.hpp +++ b/rviz_rendering/test/rviz_rendering/scene_graph_introspection.hpp @@ -44,57 +44,26 @@ #include "rviz_rendering/objects/point_cloud.hpp" #include "rviz_rendering/objects/movable_text.hpp" -#include "rviz_rendering/visibility_control.hpp" namespace rviz_rendering { -RVIZ_RENDERING_PUBLIC -bool arrowIsVisible(Ogre::SceneManager * scene_manager); - -RVIZ_RENDERING_PUBLIC std::vector findAllArrows(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC -Ogre::SceneNode * findOneArrow(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC std::vector findAllAxes(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC -Ogre::SceneNode * findOneAxes(Ogre::SceneNode * scene_node); - -RVIZ_RENDERING_PUBLIC -std::vector getPositionsFromNodes(const std::vector & nodes); -RVIZ_RENDERING_PUBLIC -std::vector -getOrientationsFromNodes(const std::vector & nodes); -RVIZ_RENDERING_PUBLIC std::vector findAllEntitiesByMeshName( Ogre::SceneNode * scene_node, const Ogre::String & resource_name); -RVIZ_RENDERING_PUBLIC Ogre::Entity * findEntityByMeshName( Ogre::SceneNode * scene_node, const Ogre::String & resource_name); -RVIZ_RENDERING_PUBLIC std::vector findAllSpheres(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC std::vector findAllCones(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC std::vector findAllCylinders(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC std::vector findAllPointClouds(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC -rviz_rendering::PointCloud * findOnePointCloud(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC Ogre::BillboardChain * findOneBillboardChain(Ogre::SceneNode * scene_node); -RVIZ_RENDERING_PUBLIC -rviz_rendering::MovableText * findOneMovableText(Ogre::SceneNode * scene_node); - -RVIZ_RENDERING_PUBLIC -Ogre::ManualObject * findOneManualObject(Ogre::SceneNode * scene_node); - template void findAllObjectsAttached( Ogre::SceneNode * scene_node, const Ogre::String & type, std::vector & objects) diff --git a/rviz_rendering_tests/CMakeLists.txt b/rviz_rendering_tests/CMakeLists.txt index 457d0e442..2cf52d09f 100644 --- a/rviz_rendering_tests/CMakeLists.txt +++ b/rviz_rendering_tests/CMakeLists.txt @@ -63,6 +63,7 @@ if(BUILD_TESTING) ament_add_gmock(mesh_loader_test_target test/mesh_loader_test.cpp + test/ogre_testing_environment.cpp ${SKIP_DISPLAY_TESTS}) if(TARGET mesh_loader_test_target) target_link_libraries(mesh_loader_test_target diff --git a/rviz_rendering_tests/test/mesh_loader_test.cpp b/rviz_rendering_tests/test/mesh_loader_test.cpp index fdfa77f57..52e961bce 100644 --- a/rviz_rendering_tests/test/mesh_loader_test.cpp +++ b/rviz_rendering_tests/test/mesh_loader_test.cpp @@ -39,7 +39,7 @@ #include #include "resource_retriever/retriever.h" -#include "test/rviz_rendering/ogre_testing_environment.hpp" +#include "ogre_testing_environment.hpp" #include "rviz_rendering/mesh_loader.hpp" using namespace ::testing; // NOLINT @@ -49,14 +49,14 @@ class MeshLoaderTestFixture : public ::testing::Test protected: static void SetUpTestCase() { - testing_environment_ = std::make_shared(); + testing_environment_ = std::make_shared(); testing_environment_->setUpOgreTestEnvironment(); } - static std::shared_ptr testing_environment_; + static std::shared_ptr testing_environment_; }; -std::shared_ptr +std::shared_ptr MeshLoaderTestFixture::testing_environment_ = nullptr; void assertVector3Equality(Ogre::Vector3 actual, Ogre::Vector3 expected) diff --git a/rviz_rendering_tests/test/ogre_testing_environment.cpp b/rviz_rendering_tests/test/ogre_testing_environment.cpp new file mode 100644 index 000000000..8c4ca6d0d --- /dev/null +++ b/rviz_rendering_tests/test/ogre_testing_environment.cpp @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2017, Bosch Software Innovations GmbH. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "ogre_testing_environment.hpp" + +#include + +#include + +#include "rviz_rendering/render_system.hpp" + +namespace rviz_rendering_tests +{ + +void OgreTestingEnvironment::setUpOgreTestEnvironment(bool debug) +{ + if (!debug) { + const std::string & name = ""; + auto lm = new Ogre::LogManager(); + lm->createLog(name, false, debug, true); + } + setUpRenderSystem(); +} + +void OgreTestingEnvironment::setUpRenderSystem() +{ + rviz_rendering::RenderSystem::get(); +} + +} // end namespace rviz_rendering_tests diff --git a/rviz_rendering_tests/test/ogre_testing_environment.hpp b/rviz_rendering_tests/test/ogre_testing_environment.hpp new file mode 100644 index 000000000..aa4836246 --- /dev/null +++ b/rviz_rendering_tests/test/ogre_testing_environment.hpp @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2017, Bosch Software Innovations GmbH. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef OGRE_TESTING_ENVIRONMENT_HPP_ +#define OGRE_TESTING_ENVIRONMENT_HPP_ + +namespace rviz_rendering_tests +{ +class OgreTestingEnvironment +{ +public: + /** + * Set up a testing environment to run tests needing Ogre. + * + * @param: bool debug, if true, all logging of Ogre is send to std::out, if false no logging + * occurs. Since the logging pollutes the test output, it defaults to false + */ + void setUpOgreTestEnvironment(bool debug = false); + + void setUpRenderSystem(); +}; + +} // namespace rviz_rendering_tests + +#endif // OGRE_TESTING_ENVIRONMENT_HPP_