From 1696f10b18887faf4b2b0316d7ef29e65adb251d Mon Sep 17 00:00:00 2001 From: methylDragon Date: Tue, 29 Nov 2022 18:40:28 -0800 Subject: [PATCH] Refine fuse_variables tests Signed-off-by: methylDragon --- fuse_variables/CMakeLists.txt | 9 +-- fuse_variables/package.xml | 4 +- fuse_variables/src/stamped.cpp | 1 - fuse_variables/test/CMakeLists.txt | 8 +-- .../test/launch_tests/test_load_device_id.cpp | 19 +++---- .../test/launch_tests/test_load_device_id.py | 56 ++++++------------- .../test_acceleration_angular_2d_stamped.cpp | 6 -- .../test_acceleration_angular_3d_stamped.cpp | 6 -- .../test_acceleration_linear_2d_stamped.cpp | 6 -- .../test_acceleration_linear_3d_stamped.cpp | 6 -- .../test/test_fixed_size_variable.cpp | 6 -- .../test/test_orientation_2d_stamped.cpp | 6 -- .../test/test_orientation_3d_stamped.cpp | 6 -- .../test/test_point_2d_fixed_landmark.cpp | 6 -- .../test/test_point_2d_landmark.cpp | 6 -- .../test/test_point_3d_fixed_landmark.cpp | 6 -- .../test/test_point_3d_landmark.cpp | 6 -- .../test/test_position_2d_stamped.cpp | 6 -- .../test/test_position_3d_stamped.cpp | 6 -- .../test/test_velocity_angular_2d_stamped.cpp | 6 -- .../test/test_velocity_angular_3d_stamped.cpp | 6 -- .../test/test_velocity_linear_2d_stamped.cpp | 6 -- .../test/test_velocity_linear_3d_stamped.cpp | 6 -- 23 files changed, 34 insertions(+), 165 deletions(-) diff --git a/fuse_variables/CMakeLists.txt b/fuse_variables/CMakeLists.txt index cda6d3f74..3dbf3679a 100644 --- a/fuse_variables/CMakeLists.txt +++ b/fuse_variables/CMakeLists.txt @@ -11,7 +11,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -find_package(ament_cmake REQUIRED) +find_package(ament_cmake_ros REQUIRED) find_package(fuse_core REQUIRED) find_package(pluginlib REQUIRED) @@ -22,7 +22,7 @@ find_package(Ceres REQUIRED) ########### ## fuse_variables library -add_library(${PROJECT_NAME} SHARED +add_library(${PROJECT_NAME} src/acceleration_angular_2d_stamped.cpp src/acceleration_angular_3d_stamped.cpp src/acceleration_linear_2d_stamped.cpp @@ -76,10 +76,7 @@ install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME} ) -install( - FILES fuse_plugins.xml - DESTINATION share/${PROJECT_NAME} -) +pluginlib_export_plugin_description_file(fuse_core fuse_plugins.xml) ament_export_targets(${PROJECT_NAME}-export HAS_LIBRARY_TARGET) ament_export_dependencies( diff --git a/fuse_variables/package.xml b/fuse_variables/package.xml index 940a43cac..446d738b2 100644 --- a/fuse_variables/package.xml +++ b/fuse_variables/package.xml @@ -12,7 +12,7 @@ Tom Moore BSD - ament_cmake + ament_cmake_ros libceres-dev fuse_core @@ -28,10 +28,10 @@ ament_cmake_pytest ament_lint_auto ament_lint_common + launch_pytest ament_cmake - diff --git a/fuse_variables/src/stamped.cpp b/fuse_variables/src/stamped.cpp index 6abcb7870..81b63193b 100644 --- a/fuse_variables/src/stamped.cpp +++ b/fuse_variables/src/stamped.cpp @@ -46,7 +46,6 @@ namespace fuse_variables fuse_core::UUID loadDeviceId( fuse_core::node_interfaces::NodeInterfaces interfaces) { - fuse_core::UUID device_id; std::string device_str; device_str = fuse_core::getParam(interfaces, "device_id", std::string()); diff --git a/fuse_variables/test/CMakeLists.txt b/fuse_variables/test/CMakeLists.txt index 493479be5..57b9df7b7 100644 --- a/fuse_variables/test/CMakeLists.txt +++ b/fuse_variables/test/CMakeLists.txt @@ -32,11 +32,11 @@ ament_add_gtest_executable(test_load_device_id launch_tests/test_load_device_id. target_link_libraries(test_load_device_id ${PROJECT_NAME}) ament_add_pytest_test(test_load_device_id_py "launch_tests/test_load_device_id.py" - PYTHON_EXECUTABLE "${_PYTHON_EXECUTABLE}" WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" ) -install( - DIRECTORY launch_tests - DESTINATION share/${PROJECT_NAME}/test +configure_file( + "launch_tests/test_load_device_id.yaml" + "launch_tests/test_load_device_id.yaml" + COPYONLY ) diff --git a/fuse_variables/test/launch_tests/test_load_device_id.cpp b/fuse_variables/test/launch_tests/test_load_device_id.cpp index ca6ec68b9..58d562318 100644 --- a/fuse_variables/test/launch_tests/test_load_device_id.cpp +++ b/fuse_variables/test/launch_tests/test_load_device_id.cpp @@ -46,30 +46,23 @@ class TestLoadDeviceId : public ::testing::Test public: void SetUp() override { - exec_ = std::make_shared(); - - spinning_ = true; + executor_ = std::make_shared(); spinner_ = std::thread([&](){ - auto context = rclcpp::contexts::get_global_default_context(); - while(context->is_valid() && spinning_) { - exec_->spin_some(); - } + executor_->spin(); }); } void TearDown() override { - spinning_ = false; + executor_->cancel(); if (spinner_.joinable()) { spinner_.join(); } - - exec_.reset(); + executor_.reset(); } std::thread spinner_; //!< Internal thread for spinning the executor - std::atomic spinning_; //!< Flag for spinning the spin thread - rclcpp::executors::SingleThreadedExecutor::SharedPtr exec_; + rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_; }; TEST_F(TestLoadDeviceId, LoadDeviceId) @@ -178,6 +171,8 @@ TEST_F(TestLoadDeviceId, LoadDeviceId) } } + +// NOTE(CH3): This main is required because the test is manually run by a launch test int main(int argc, char** argv) { rclcpp::init(argc, argv); diff --git a/fuse_variables/test/launch_tests/test_load_device_id.py b/fuse_variables/test/launch_tests/test_load_device_id.py index f9c8df620..3d5498c69 100755 --- a/fuse_variables/test/launch_tests/test_load_device_id.py +++ b/fuse_variables/test/launch_tests/test_load_device_id.py @@ -16,53 +16,33 @@ import os -import unittest +from launch import LaunchDescription +from launch.actions import ExecuteProcess -from ament_index_python.packages import get_package_prefix - -from launch import LaunchContext, LaunchDescription, LaunchService -from launch.actions import EmitEvent, ExecuteProcess -from launch.events import Shutdown -from launch_testing.actions import GTest, ReadyToTest - -import launch_testing -import launch_testing.actions -import launch_testing.asserts -import launch_testing.util -import launch_testing.markers -import launch_testing_ros -from launch_ros.substitutions import FindPackageShare +import launch_pytest +from launch_pytest.actions import ReadyToTest +from launch_pytest.tools import process as process_tools import pytest -@pytest.mark.launch_test -@launch_testing.markers.keep_alive -def generate_test_description(): - ls = LaunchContext() - param_path = os.path.join( - FindPackageShare('fuse_variables').perform(ls), - 'test', - 'launch_tests', - 'test_load_device_id.yaml' - ) +@pytest.fixture +def test_proc(): + test_root = '.' - test_path = os.path.join( - get_package_prefix('fuse_variables'), - '..', '..', 'build', 'fuse_variables', 'test', 'test_load_device_id' - ) + param_path = os.path.join(test_root, 'launch_tests', 'test_load_device_id.yaml') + test_path = os.path.join(test_root, 'test_load_device_id') cmd = [test_path, '--ros-args', '--params-file', param_path] - test_load_device_id_process = ExecuteProcess(cmd=cmd, shell=True, output='both') + return ExecuteProcess(cmd=cmd, shell=True, output='screen', cached_output=True) - ld = LaunchDescription([ - test_load_device_id_process, - ReadyToTest() - ]) - return ld, {'test_load_device_id_process': test_load_device_id_process} +@launch_pytest.fixture +def generate_test_description(test_proc): + return LaunchDescription([test_proc, ReadyToTest()]) -class TestNoFailedTests(unittest.TestCase): - def test_no_failed_gtests(self, proc_output): - proc_output.assertWaitFor('[ PASSED ] 1 test.', timeout=10, stream='stdout') +@pytest.mark.launch(fixture=generate_test_description) +async def test_no_failed_gtests(test_proc, launch_context): + await process_tools.wait_for_exit(launch_context, test_proc, timeout=10) + assert test_proc.return_code == 0, "GTests failed" diff --git a/fuse_variables/test/test_acceleration_angular_2d_stamped.cpp b/fuse_variables/test/test_acceleration_angular_2d_stamped.cpp index 8fb877d3c..75ff3febb 100644 --- a/fuse_variables/test/test_acceleration_angular_2d_stamped.cpp +++ b/fuse_variables/test/test_acceleration_angular_2d_stamped.cpp @@ -166,9 +166,3 @@ TEST(AccelerationAngular2DStamped, Serialization) EXPECT_EQ(expected.stamp(), actual.stamp()); EXPECT_EQ(expected.yaw(), actual.yaw()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_acceleration_angular_3d_stamped.cpp b/fuse_variables/test/test_acceleration_angular_3d_stamped.cpp index f20a649a9..a2ca471fc 100644 --- a/fuse_variables/test/test_acceleration_angular_3d_stamped.cpp +++ b/fuse_variables/test/test_acceleration_angular_3d_stamped.cpp @@ -176,9 +176,3 @@ TEST(AccelerationAngular3DStamped, Serialization) EXPECT_EQ(expected.pitch(), actual.pitch()); EXPECT_EQ(expected.yaw(), actual.yaw()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_acceleration_linear_2d_stamped.cpp b/fuse_variables/test/test_acceleration_linear_2d_stamped.cpp index 24a1bae59..d0180b894 100644 --- a/fuse_variables/test/test_acceleration_linear_2d_stamped.cpp +++ b/fuse_variables/test/test_acceleration_linear_2d_stamped.cpp @@ -171,9 +171,3 @@ TEST(AccelerationLinear2DStamped, Serialization) EXPECT_EQ(expected.x(), actual.x()); EXPECT_EQ(expected.y(), actual.y()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_acceleration_linear_3d_stamped.cpp b/fuse_variables/test/test_acceleration_linear_3d_stamped.cpp index a28fcf95c..3eb2e894b 100644 --- a/fuse_variables/test/test_acceleration_linear_3d_stamped.cpp +++ b/fuse_variables/test/test_acceleration_linear_3d_stamped.cpp @@ -176,9 +176,3 @@ TEST(AccelerationLinear3DStamped, Serialization) EXPECT_EQ(expected.y(), actual.y()); EXPECT_EQ(expected.z(), actual.z()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_fixed_size_variable.cpp b/fuse_variables/test/test_fixed_size_variable.cpp index 4eef08003..48d6cab7e 100644 --- a/fuse_variables/test/test_fixed_size_variable.cpp +++ b/fuse_variables/test/test_fixed_size_variable.cpp @@ -107,9 +107,3 @@ TEST(FixedSizeVariable, Array) EXPECT_NO_THROW(success = success && const_variable.array().back() == 4.0); EXPECT_TRUE(success); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_orientation_2d_stamped.cpp b/fuse_variables/test/test_orientation_2d_stamped.cpp index 3228290f0..ae491e78d 100644 --- a/fuse_variables/test/test_orientation_2d_stamped.cpp +++ b/fuse_variables/test/test_orientation_2d_stamped.cpp @@ -292,9 +292,3 @@ TEST(Orientation2DStamped, Serialization) EXPECT_EQ(expected.stamp(), actual.stamp()); EXPECT_EQ(expected.yaw(), actual.yaw()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_orientation_3d_stamped.cpp b/fuse_variables/test/test_orientation_3d_stamped.cpp index 86b4be89c..b00fda694 100644 --- a/fuse_variables/test/test_orientation_3d_stamped.cpp +++ b/fuse_variables/test/test_orientation_3d_stamped.cpp @@ -413,9 +413,3 @@ TEST(Orientation3DStamped, Serialization) EXPECT_EQ(expected.y(), actual.y()); EXPECT_EQ(expected.z(), actual.z()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_point_2d_fixed_landmark.cpp b/fuse_variables/test/test_point_2d_fixed_landmark.cpp index 9fbe72195..4db23701a 100644 --- a/fuse_variables/test/test_point_2d_fixed_landmark.cpp +++ b/fuse_variables/test/test_point_2d_fixed_landmark.cpp @@ -146,9 +146,3 @@ TEST(Point2DFixedLandmark, Serialization) EXPECT_EQ(expected.x(), actual.x()); EXPECT_EQ(expected.y(), actual.y()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_point_2d_landmark.cpp b/fuse_variables/test/test_point_2d_landmark.cpp index 800f9f580..6b137d91e 100644 --- a/fuse_variables/test/test_point_2d_landmark.cpp +++ b/fuse_variables/test/test_point_2d_landmark.cpp @@ -141,9 +141,3 @@ TEST(Point2DLandmark, Serialization) EXPECT_EQ(expected.x(), actual.x()); EXPECT_EQ(expected.y(), actual.y()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_point_3d_fixed_landmark.cpp b/fuse_variables/test/test_point_3d_fixed_landmark.cpp index 75b32c526..3432e13a2 100644 --- a/fuse_variables/test/test_point_3d_fixed_landmark.cpp +++ b/fuse_variables/test/test_point_3d_fixed_landmark.cpp @@ -150,9 +150,3 @@ TEST(Point3DFixedLandmark, Serialization) EXPECT_EQ(expected.y(), actual.y()); EXPECT_EQ(expected.z(), actual.z()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_point_3d_landmark.cpp b/fuse_variables/test/test_point_3d_landmark.cpp index e7a2cb88b..f53753dc4 100644 --- a/fuse_variables/test/test_point_3d_landmark.cpp +++ b/fuse_variables/test/test_point_3d_landmark.cpp @@ -146,9 +146,3 @@ TEST(Point3DLandmark, Serialization) EXPECT_EQ(expected.y(), actual.y()); EXPECT_EQ(expected.z(), actual.z()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_position_2d_stamped.cpp b/fuse_variables/test/test_position_2d_stamped.cpp index 314c5432b..ec597232d 100644 --- a/fuse_variables/test/test_position_2d_stamped.cpp +++ b/fuse_variables/test/test_position_2d_stamped.cpp @@ -171,9 +171,3 @@ TEST(Position2DStamped, Serialization) EXPECT_EQ(expected.x(), actual.x()); EXPECT_EQ(expected.y(), actual.y()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_position_3d_stamped.cpp b/fuse_variables/test/test_position_3d_stamped.cpp index 336526567..fc01c0d4a 100644 --- a/fuse_variables/test/test_position_3d_stamped.cpp +++ b/fuse_variables/test/test_position_3d_stamped.cpp @@ -193,9 +193,3 @@ TEST(Position3DStamped, Serialization) EXPECT_EQ(expected.y(), actual.y()); EXPECT_EQ(expected.z(), actual.z()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_velocity_angular_2d_stamped.cpp b/fuse_variables/test/test_velocity_angular_2d_stamped.cpp index 01b520b98..d65289595 100644 --- a/fuse_variables/test/test_velocity_angular_2d_stamped.cpp +++ b/fuse_variables/test/test_velocity_angular_2d_stamped.cpp @@ -166,9 +166,3 @@ TEST(VelocityAngular2DStamped, Serialization) EXPECT_EQ(expected.stamp(), actual.stamp()); EXPECT_EQ(expected.yaw(), actual.yaw()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_velocity_angular_3d_stamped.cpp b/fuse_variables/test/test_velocity_angular_3d_stamped.cpp index b0f76905f..b34de211d 100644 --- a/fuse_variables/test/test_velocity_angular_3d_stamped.cpp +++ b/fuse_variables/test/test_velocity_angular_3d_stamped.cpp @@ -176,9 +176,3 @@ TEST(VelocityAngular3DStamped, Serialization) EXPECT_EQ(expected.pitch(), actual.pitch()); EXPECT_EQ(expected.yaw(), actual.yaw()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_velocity_linear_2d_stamped.cpp b/fuse_variables/test/test_velocity_linear_2d_stamped.cpp index 3f9aae0e6..6bfbbaed0 100644 --- a/fuse_variables/test/test_velocity_linear_2d_stamped.cpp +++ b/fuse_variables/test/test_velocity_linear_2d_stamped.cpp @@ -171,9 +171,3 @@ TEST(VelocityLinear2DStamped, Serialization) EXPECT_EQ(expected.x(), actual.x()); EXPECT_EQ(expected.y(), actual.y()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/fuse_variables/test/test_velocity_linear_3d_stamped.cpp b/fuse_variables/test/test_velocity_linear_3d_stamped.cpp index 13a19ff21..81f4d32c5 100644 --- a/fuse_variables/test/test_velocity_linear_3d_stamped.cpp +++ b/fuse_variables/test/test_velocity_linear_3d_stamped.cpp @@ -176,9 +176,3 @@ TEST(VelocityLinear3DStamped, Serialization) EXPECT_EQ(expected.y(), actual.y()); EXPECT_EQ(expected.z(), actual.z()); } - -int main(int argc, char **argv) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -}