Skip to content

Commit

Permalink
Improve visual testing and add visual tests (#259)
Browse files Browse the repository at this point in the history
* Find property index by name

* Add test for PathDisplay

* Create a publisher in Visual Testing Framework

* Add wait() method to Executor

* Fix QLocale problem

* Add documentation to public classes used by clients of the visual testing framework

* Refactoring of BasePageObjects to allow simpler PageObect writing

* Move test_helpers.hpp to public interface

* Add TF display visual test

* Harmonise logging

* Add visual test for robot model

* Add page object, publisher and test for LaserScanDisplay

* Unify setTopic method

Always wait 1.5 seconds for the first message

* Increase timeout

* Fix Windows error due to duplicate constant

* Change cmake and environment variables to True instead of TRUE

* Write visual tests to rviz_default_plugins

Move page objects + visual tests to rviz_default_plugins
Add more tests for:
- Camera display
- Image display
- Pose display
- Pose array display
- Marker display
- PointCloud(2) display
- Grid display

* Implement better image comparison method

* Remove openCV dependency

* Use size_t instead of int in wait()

* Fix MSBuild warning
  • Loading branch information
Martin-Idel-SI authored and wjwwood committed May 16, 2018
1 parent d49b17d commit d69b6f1
Show file tree
Hide file tree
Showing 103 changed files with 3,755 additions and 613 deletions.
211 changes: 189 additions & 22 deletions rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,13 @@ endif()

option(EnableDisplayTests "EnableDisplayTests")
set(DisplayTests "False" CACHE STRING "DisplayTestsVariable")
option(EnableVisualTests "decides whether or not to enable the tests")

add_definitions(-D_BUILD_DIR_PATH="${CMAKE_CURRENT_BINARY_DIR}")
add_definitions(-D_SRC_DIR_PATH="${CMAKE_CURRENT_SOURCE_DIR}")

file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/test_images)
file(MAKE_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/test/reference_images)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Werror)
Expand All @@ -25,11 +32,12 @@ find_package(resource_retriever REQUIRED)
find_package(rviz_common REQUIRED)
find_package(rviz_rendering REQUIRED)
find_package(rviz_ogre_vendor REQUIRED)
find_package(rviz_visual_testing_framework REQUIRED)
find_package(tinyxml_vendor REQUIRED)
find_package(TinyXML REQUIRED) # provided by tinyxml_vendor
find_package(urdf REQUIRED)

find_package(Qt5 REQUIRED COMPONENTS Widgets)
find_package(Qt5 REQUIRED COMPONENTS Widgets Test)

find_package(geometry_msgs REQUIRED)
find_package(laser_geometry REQUIRED)
Expand Down Expand Up @@ -251,8 +259,8 @@ if(BUILD_TESTING)
)

ament_add_gmock(point_cloud2_display_test
test/rviz_default_plugins/displays/pointcloud/message_creators.hpp
test/rviz_default_plugins/displays/pointcloud/message_creators.cpp
test/rviz_default_plugins/pointcloud_messages.hpp
test/rviz_default_plugins/pointcloud_messages.cpp
test/rviz_default_plugins/displays/pointcloud/point_cloud2_display_test.cpp)
if(TARGET point_cloud2_display_test)
target_include_directories(point_cloud2_display_test PUBLIC
Expand All @@ -262,8 +270,8 @@ if(BUILD_TESTING)
endif()

ament_add_gmock(point_cloud_transformers_test
test/rviz_default_plugins/displays/pointcloud/message_creators.hpp
test/rviz_default_plugins/displays/pointcloud/message_creators.cpp
test/rviz_default_plugins/pointcloud_messages.hpp
test/rviz_default_plugins/pointcloud_messages.cpp
test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/axis_color_pc_transformer_test.cpp
test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/flat_color_pc_transformer_test.cpp
test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/intensity_pc_transformer_test.cpp
Expand Down Expand Up @@ -363,23 +371,182 @@ if(BUILD_TESTING)
${TEST_LINK_LIBRARIES})
endif()

ament_add_gmock(pointcloud_selection_handler_test
test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp
test/rviz_default_plugins/displays/pointcloud/message_creators.cpp
test/rviz_default_plugins/displays/display_test_fixture.cpp
test/rviz_default_plugins/scene_graph_introspection.hpp
APPEND_ENV AMENT_PREFIX_PATH=${CMAKE_INSTALL_PREFIX} PATH=${CMAKE_INSTALL_PREFIX}/bin;${CMAKE_INSTALL_PREFIX}/opt/rviz_assimp_vendor/bin;${CMAKE_INSTALL_PREFIX}/opt/rviz_yaml_cpp_vendor/bin;${CMAKE_INSTALL_PREFIX}/opt/rviz_ogre_vendor/bin)
if(TARGET pointcloud_selection_handler_test)
target_include_directories(pointcloud_selection_handler_test PUBLIC ${TEST_INCLUDE_DIRS})
target_link_libraries(pointcloud_selection_handler_test ${TEST_LINK_LIBRARIES})
endif()

ament_add_gmock(selection_tool_test
test/rviz_default_plugins/tools/select/selection_tool_test.cpp
APPEND_ENV AMENT_PREFIX_PATH=${CMAKE_INSTALL_PREFIX} PATH=${CMAKE_INSTALL_PREFIX}/bin;${CMAKE_INSTALL_PREFIX}/opt/rviz_assimp_vendor/bin;${CMAKE_INSTALL_PREFIX}/opt/rviz_yaml_cpp_vendor/bin;${CMAKE_INSTALL_PREFIX}/opt/rviz_ogre_vendor/bin)
if(TARGET selection_tool_test)
target_include_directories(selection_tool_test PUBLIC ${TEST_INCLUDE_DIRS})
target_link_libraries(selection_tool_test ${TEST_LINK_LIBRARIES})
if(EnableVisualTests STREQUAL "True")
find_package(ament_index_cpp REQUIRED)

ament_add_gtest(camera_display_visual_test
test/rviz_default_plugins/displays/camera/camera_display_visual_test.cpp
test/rviz_default_plugins/publishers/camera_info_publisher.hpp
test/rviz_default_plugins/page_objects/camera_display_page_object.cpp
test/rviz_default_plugins/page_objects/point_cloud_display_page_object.cpp
test/rviz_default_plugins/page_objects/point_cloud_common_page_object.cpp
test/rviz_default_plugins/publishers/image_publisher.hpp
test/rviz_default_plugins/publishers/point_cloud_publisher.hpp
TIMEOUT 180)
if(TARGET camera_display_visual_test)
target_include_directories(camera_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(camera_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(grid_display_visual_test
test/rviz_default_plugins/displays/grid/grid_display_visual_test.cpp
test/rviz_default_plugins/page_objects/grid_display_page_object.cpp
TIMEOUT 180)
if(TARGET grid_display_visual_test)
target_include_directories(grid_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(grid_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(image_display_visual_test
test/rviz_default_plugins/displays/image/image_display_visual_test.cpp
test/rviz_default_plugins/page_objects/image_display_page_object.cpp
test/rviz_default_plugins/publishers/image_publisher.hpp
TIMEOUT 180)
if(TARGET image_display_visual_test)
target_include_directories(image_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(image_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(marker_display_visual_test
test/rviz_default_plugins/displays/marker/marker_display_visual_test.cpp
test/rviz_default_plugins/page_objects/marker_display_page_object.cpp
test/rviz_default_plugins/publishers/marker_publisher.hpp
TIMEOUT 180)
if(TARGET marker_display_visual_test)
target_include_directories(marker_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(marker_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(path_display_visual_test
test/rviz_default_plugins/displays/path/path_display_visual_test.cpp
test/rviz_default_plugins/page_objects/path_display_page_object.cpp
test/rviz_default_plugins/publishers/path_publisher.hpp
TIMEOUT 180)
if(TARGET path_display_visual_test)
target_include_directories(path_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(path_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(point_cloud_display_visual_test
test/rviz_default_plugins/displays/pointcloud/point_cloud_display_visual_test.cpp
test/rviz_default_plugins/page_objects/point_cloud_display_page_object.cpp
test/rviz_default_plugins/page_objects/point_cloud_common_page_object.cpp
test/rviz_default_plugins/publishers/point_cloud_publisher.hpp
TIMEOUT 180)
if(TARGET point_cloud_display_visual_test)
target_include_directories(point_cloud_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(point_cloud_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(point_cloud2_display_visual_test
test/rviz_default_plugins/displays/pointcloud/point_cloud2_display_visual_test.cpp
test/rviz_default_plugins/page_objects/point_cloud2_display_page_object.cpp
test/rviz_default_plugins/publishers/point_cloud2_publisher.hpp
test/rviz_default_plugins/page_objects/point_cloud_common_page_object.cpp
test/rviz_default_plugins/pointcloud_messages.cpp
TIMEOUT 180)
if(TARGET point_cloud2_display_visual_test)
target_include_directories(point_cloud2_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(point_cloud2_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(pose_array_display_visual_test
test/rviz_default_plugins/displays/pose_array/pose_array_display_visual_test.cpp
test/rviz_default_plugins/page_objects/pose_array_display_page_object.cpp
test/rviz_default_plugins/page_objects/pose_display_page_object.cpp
test/rviz_default_plugins/publishers/pose_array_publisher.hpp
TIMEOUT 180)
if(TARGET pose_array_display_visual_test)
target_include_directories(pose_array_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(pose_array_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(pose_display_visual_test
test/rviz_default_plugins/displays/pose/pose_display_visual_test.cpp
test/rviz_default_plugins/page_objects/pose_display_page_object.cpp
test/rviz_default_plugins/publishers/pose_publisher.hpp
TIMEOUT 180)
if(TARGET pose_display_visual_test)
target_include_directories(pose_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(pose_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(robot_model_display_visual_test
test/rviz_default_plugins/displays/robot_model/robot_model_display_visual_test.cpp
test/rviz_default_plugins/page_objects/robot_model_display_page_object.cpp
TIMEOUT 180)
if(TARGET robot_model_display_visual_test)
target_include_directories(robot_model_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(robot_model_display_visual_test
${TEST_LINK_LIBRARIES}
ament_index_cpp::ament_index_cpp
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(tf_display_visual_test
test/rviz_default_plugins/displays/tf/tf_display_visual_test.cpp
test/rviz_default_plugins/page_objects/tf_display_page_object.cpp
TIMEOUT 180)
if(TARGET tf_display_visual_test)
target_include_directories(tf_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(tf_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()

ament_add_gtest(laser_scan_display_visual_test
test/rviz_default_plugins/displays/laser_scan/laser_scan_display_visual_test.cpp
test/rviz_default_plugins/page_objects/point_cloud_common_page_object.cpp
test/rviz_default_plugins/page_objects/laser_scan_display_page_object.cpp
TIMEOUT 180)
if(TARGET laser_scan_display_visual_test)
target_include_directories(laser_scan_display_visual_test PUBLIC
${TEST_INCLUDE_DIRS}
${rviz_visual_testing_framework_INCLUDE_DIRS})
target_link_libraries(laser_scan_display_visual_test
${TEST_LINK_LIBRARIES}
rviz_visual_testing_framework::rviz_visual_testing_framework)
endif()
endif()
endif()
endif()
Expand Down
2 changes: 2 additions & 0 deletions rviz_default_plugins/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,9 @@
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_lint_cmake</test_depend>
<test_depend>ament_cmake_uncrustify</test_depend>
<test_depend>ament_index_cpp</test_depend>
<test_depend>rviz_rendering_tests</test_depend>
<test_depend>rviz_visual_testing_framework</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
/*
* 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 <memory>
#include <string>
#include <vector>

#include "rviz_visual_testing_framework/visual_test_fixture.hpp"
#include "rviz_visual_testing_framework/visual_test_publisher.hpp"

#include "../../page_objects/camera_display_page_object.hpp"
#include "../../publishers/camera_info_publisher.hpp"
#include "../../publishers/image_publisher.hpp"
#include "../../page_objects/point_cloud_display_page_object.hpp"
#include "../../publishers/point_cloud_publisher.hpp"

TEST_F(VisualTestFixture, test_camera_display_with_published_image) {
auto points = {nodes::createPoint(0, 0, 10)};
std::vector<PublisherWithFrame> publishers = {
PublisherWithFrame(std::make_shared<nodes::CameraInfoPublisher>(), "image"),
PublisherWithFrame(std::make_shared<nodes::ImagePublisher>(), "image"),
PublisherWithFrame(std::make_shared<nodes::PointCloudPublisher>(points), "pointcloud_frame")
};
auto cam_publisher = std::make_unique<VisualTestPublisher>(publishers);

setCamPose(Ogre::Vector3(0, 0, 16));
setCamLookAt(Ogre::Vector3(0, 0, 0));

auto camera_display = addDisplay<CameraDisplayPageObject>();
camera_display->setTopic("/image");
camera_display->collapse();

auto pointcloud_display = addDisplay<PointCloudDisplayPageObject>();
pointcloud_display->setStyle("Spheres");
pointcloud_display->setSizeMeters(11);
pointcloud_display->setColor(0, 0, 255);

captureRenderWindow(camera_display);

assertScreenShotsIdentity();
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
/*
* Copyright (c) 2018, 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 copyright holders 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 <memory>
#include <string>

#include "rviz_visual_testing_framework/visual_test_fixture.hpp"

#include "../../page_objects/grid_display_page_object.hpp"

TEST_F(VisualTestFixture, grid_visual_test) {
setCamPose(Ogre::Vector3(10, 0, 0));
setCamLookAt(Ogre::Vector3(0, 0, 0));

auto grid_display = addDisplay<GridDisplayPageObject>();
grid_display->setLineStyle("Billboards");
grid_display->setLineWidth(4.0f);
grid_display->setColor(255, 255, 0);
grid_display->setAlpha(1.0f);
captureMainWindow();

grid_display->setAlpha(0.0f);
captureMainWindow("empty_scene");

assertScreenShotsIdentity();
}
Loading

0 comments on commit d69b6f1

Please sign in to comment.