Skip to content

Commit

Permalink
Improve the compilation time of rviz_default_plugins (#1007)
Browse files Browse the repository at this point in the history
* Cleanup rviz_visual_testing_framework CMakeLists.txt

The main motivation here is to remove an exported absolute
path from this package.  To do this, mark everything in
the CMakeLists.txt private that we can.

This ended up exposing a bunch of missing dependencies
in rviz_default_plugins, so fix those here as well.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Jul 10, 2023
1 parent 439c683 commit 5af8896
Show file tree
Hide file tree
Showing 20 changed files with 441 additions and 391 deletions.
716 changes: 364 additions & 352 deletions rviz_default_plugins/CMakeLists.txt

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@

#include <OgreSceneNode.h>

#include "rclcpp/clock.hpp"

void DisplayTestFixture::SetUpTestCase()
{
testing_environment_ = std::make_shared<rviz_default_plugins::OgreTestingEnvironment>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@

#include <gtest/gtest.h>

#include <QString>

#include \
"rviz_default_plugins/displays/interactive_markers/interactive_marker_namespace_property.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,11 @@

#include <OgreVector.h>

#include "geometry_msgs/msg/point.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/color_rgba.hpp"
#include "std_msgs/msg/header.hpp"
#include "visualization_msgs/msg/marker.hpp"

namespace testing
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@
#ifndef RVIZ_DEFAULT_PLUGINS__DISPLAYS__MARKER__MARKER_MESSAGES_HPP_
#define RVIZ_DEFAULT_PLUGINS__DISPLAYS__MARKER__MARKER_MESSAGES_HPP_

#include "geometry_msgs/msg/point.hpp"
#include "std_msgs/msg/color_rgba.hpp"
#include "visualization_msgs/msg/marker.hpp"

namespace testing
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <QString>

#include "map_display_page_object.hpp"

MapDisplayPageObject::MapDisplayPageObject()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <QString>

#include "marker_display_page_object.hpp"

MarkerDisplayPageObject::MarkerDisplayPageObject()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
#ifndef RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__MARKER_DISPLAY_PAGE_OBJECT_HPP_
#define RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__MARKER_DISPLAY_PAGE_OBJECT_HPP_

#include <QString>

#include "rviz_visual_testing_framework/page_objects/base_page_object.hpp"

class MarkerDisplayPageObject : public BasePageObject
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
#ifndef RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__POINT_CLOUD_COMMON_PAGE_OBJECT_HPP_
#define RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__POINT_CLOUD_COMMON_PAGE_OBJECT_HPP_

#include <QString>

#include "rviz_visual_testing_framework/page_objects/base_page_object.hpp"

class PointCloudCommonPageObject : public BasePageObject
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@

#include "pose_display_page_object.hpp"

#include <QString>

#include <memory>
#include <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
#ifndef RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__POSE_DISPLAY_PAGE_OBJECT_HPP_
#define RVIZ_DEFAULT_PLUGINS__PAGE_OBJECTS__POSE_DISPLAY_PAGE_OBJECT_HPP_

#include <QString>

#include "rviz_visual_testing_framework/page_objects/base_page_object.hpp"

class PoseDisplayPageObject : public BasePageObject
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <QString>

#include "pose_with_covariance_display_page_object.hpp"

PoseWithCovarianceDisplayPageObject::PoseWithCovarianceDisplayPageObject()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <QString>

#include "range_display_page_object.hpp"

RangeDisplayPageObject::RangeDisplayPageObject()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <QString>

#include "robot_model_display_page_object.hpp"

RobotModelDisplayPageObject::RobotModelDisplayPageObject()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@

#include "tf_display_page_object.hpp"

#include <QString>

#include <memory>
#include <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@

#include "wrench_display_page_object.hpp"

#include <QString>

#include <memory>
#include <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,11 @@
#include <memory>
#include <vector>

#include "geometry_msgs/msg/point32.hpp"
#include "rclcpp/clock.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "sensor_msgs/msg/point_field.hpp"
#include "std_msgs/msg/header.hpp"

namespace rviz_default_plugins
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/clock.hpp"
#include "std_msgs/msg/header.hpp"
#include "geometry_msgs/msg/pose.hpp"
#include "geometry_msgs/msg/pose_array.hpp"

using namespace std::chrono_literals; // NOLINT
Expand Down
72 changes: 33 additions & 39 deletions rviz_visual_testing_framework/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,47 +24,20 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)

find_package(geometry_msgs REQUIRED)
find_package(Qt5 REQUIRED COMPONENTS Widgets Test)
find_package(rclcpp REQUIRED)
find_package(rcutils REQUIRED)

find_package(rviz_common REQUIRED)

find_package(rviz_ogre_vendor REQUIRED)

find_package(Qt5 REQUIRED COMPONENTS Widgets Test)
find_package(rviz_rendering REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)

find_package(ament_cmake_gtest REQUIRED)
ament_find_gtest()

set(visual_test_framework_source_files
include/rviz_visual_testing_framework/page_objects/base_page_object.hpp
src/page_objects/base_page_object.cpp
include/rviz_visual_testing_framework/page_objects/page_object_with_window.hpp
src/page_objects/page_object_with_window.cpp
src/internal/rviz_scene_test.cpp
include/rviz_visual_testing_framework/internal/rviz_scene_test.hpp
include/rviz_visual_testing_framework/internal/display_handler.hpp
src/internal/display_handler.cpp
src/internal/image_tester.cpp
include/rviz_visual_testing_framework/internal/image_tester.hpp
include/rviz_visual_testing_framework/test_helpers.hpp
src/test_helpers.cpp
include/rviz_visual_testing_framework/internal/executor.hpp
src/internal/executor.cpp
include/rviz_visual_testing_framework/internal/transform_message_creator.hpp
src/internal/transform_message_creator.cpp
include/rviz_visual_testing_framework/internal/visual_test.hpp
src/internal/visual_test.cpp
include/rviz_visual_testing_framework/visual_test_fixture.hpp
src/visual_test_fixture.cpp
include/rviz_visual_testing_framework/visual_test_publisher.hpp
)

set(visual_tests_target_libaries
rviz_common::rviz_common
Qt5::Widgets
Qt5::Test)

# TODO(wjwwood): this block is to setup the windeployqt tool, could be removed later.
if(Qt5_FOUND AND WIN32 AND TARGET Qt5::qmake AND NOT TARGET Qt5::windeployqt)
get_target_property(_qt5_qmake_location Qt5::qmake IMPORTED_LOCATION)
Expand All @@ -77,20 +50,41 @@ if(Qt5_FOUND AND WIN32 AND TARGET Qt5::qmake AND NOT TARGET Qt5::windeployqt)
)
endif()

add_library(rviz_visual_testing_framework STATIC ${visual_test_framework_source_files})
add_library(rviz_visual_testing_framework STATIC
src/page_objects/base_page_object.cpp
src/page_objects/page_object_with_window.cpp
src/internal/rviz_scene_test.cpp
src/internal/display_handler.cpp
src/internal/image_tester.cpp
src/test_helpers.cpp
src/internal/executor.cpp
src/internal/transform_message_creator.cpp
src/internal/visual_test.cpp
src/visual_test_fixture.cpp
)

target_include_directories(rviz_visual_testing_framework
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>
${GTEST_INCLUDE_DIRS})

target_link_libraries(rviz_visual_testing_framework
${visual_tests_target_libaries})
target_link_libraries(rviz_visual_testing_framework PUBLIC
${geometry_msgs_TARGETS}
Qt5::Test
Qt5::Widgets
rclcpp::rclcpp
rcutils::rcutils
rviz_common::rviz_common
rviz_ogre_vendor::OgreMain
rviz_rendering::rviz_rendering
${std_msgs_TARGETS}
tf2::tf2
tf2_ros::tf2_ros
)

# export information to downstream packages
ament_export_dependencies(Qt5)
ament_export_dependencies(rviz_common)
ament_export_dependencies(geometry_msgs Qt5 rclcpp rcutils rviz_common rviz_ogre_vendor rviz_rendering std_msgs tf2 tf2_ros)

# Export old-style CMake variables
ament_export_include_directories("include/${PROJECT_NAME}")
Expand Down
7 changes: 7 additions & 0 deletions rviz_visual_testing_framework/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,15 @@

<build_depend>qtbase5-dev</build_depend>

<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>rcutils</depend>
<depend>rviz_common</depend>
<depend>rviz_ogre_vendor</depend>
<depend>rviz_rendering</depend>
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>ament_cmake_gtest</depend>

<!-- TODO(jacobperron): Replace with ament_lint_common when ament_copyright is working -->
Expand Down

0 comments on commit 5af8896

Please sign in to comment.