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..ab49236b3 100644 --- a/fuse_variables/package.xml +++ b/fuse_variables/package.xml @@ -31,7 +31,6 @@ ament_cmake - diff --git a/fuse_variables/src/stamped.cpp b/fuse_variables/src/stamped.cpp index 6173acc26..fd2334e50 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 a596f36f3..835d99e49 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,24 @@ class TestLoadDeviceId : public ::testing::Test public: void SetUp() override { - exec_ = std::make_shared(); + executor_ = std::make_shared(); - spinning_ = true; 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; 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 +172,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..8004822b1 100755 --- a/fuse_variables/test/launch_tests/test_load_device_id.py +++ b/fuse_variables/test/launch_tests/test_load_device_id.py @@ -23,46 +23,37 @@ 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 +import launch_pytest +from launch_pytest.actions import ReadyToTest +from launch_pytest.tools import process as process_tools + from launch_ros.substitutions import FindPackageShare 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 = os.path.join( + get_package_prefix('fuse_variables'), '..', '..', 'build', 'fuse_variables', 'test' ) - 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') - ld = LaunchDescription([ - test_load_device_id_process, - ReadyToTest() - ]) + return ExecuteProcess(cmd=cmd, shell=True, output='both', cached_output=True) - 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()]) +@pytest.mark.launch(fixture=generate_test_description) +def test_no_failed_gtests(test_proc, launch_context): + def validate_output(output): + assert '[ PASSED ] 1 test.' in output.splitlines(), ( + 'process never printed required passes') -class TestNoFailedTests(unittest.TestCase): - def test_no_failed_gtests(self, proc_output): - proc_output.assertWaitFor('[ PASSED ] 1 test.', timeout=10, stream='stdout') + process_tools.assert_output_sync( + launch_context, test_proc, validate_output, timeout=10) diff --git a/fuse_variables/test/test_acceleration_angular_2d_stamped.cpp b/fuse_variables/test/test_acceleration_angular_2d_stamped.cpp index 9642912b5..ff8d27885 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 d988802c6..92dbf02e0 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 fc08cbccc..45178d0c0 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 d783addbe..66b7f7b82 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 62806d3d9..a137d3fda 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 8401df473..e2717b807 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 29043d272..d740a5232 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 8149ad098..fa57eea83 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 d178181a0..d52da7358 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 971391a0c..73e64a8b9 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 2323aaefd..a217c1b2c 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 1978cc7fc..2682c5b5d 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 2597281d4..16a364cb7 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 5916012c9..9111eb6c0 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 09fc6ec1f..752144d24 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 d4b00ac14..73e1d9715 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 beea7f6c9..7b4e96985 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(); -}