Skip to content

Commit

Permalink
Refine fuse_variables tests
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Dec 7, 2022
1 parent 5d42a50 commit 1696f10
Show file tree
Hide file tree
Showing 23 changed files with 34 additions and 165 deletions.
9 changes: 3 additions & 6 deletions fuse_variables/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand All @@ -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
Expand Down Expand Up @@ -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(
Expand Down
4 changes: 2 additions & 2 deletions fuse_variables/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
<author email="tmoore@locusrobotics.com">Tom Moore</author>
<license>BSD</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_ros</buildtool_depend>

<build_depend>libceres-dev</build_depend>
<build_depend>fuse_core</build_depend>
Expand All @@ -28,10 +28,10 @@
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>launch_pytest</test_depend>

<export>
<build_type>ament_cmake</build_type>
<fuse_core plugin="${prefix}/fuse_plugins.xml" />
<rosdoc config="rosdoc.yaml" />
</export>
</package>
1 change: 0 additions & 1 deletion fuse_variables/src/stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ namespace fuse_variables
fuse_core::UUID loadDeviceId(
fuse_core::node_interfaces::NodeInterfaces<fuse_core::node_interfaces::Parameters> interfaces)
{
fuse_core::UUID device_id;
std::string device_str;

device_str = fuse_core::getParam(interfaces, "device_id", std::string());
Expand Down
8 changes: 4 additions & 4 deletions fuse_variables/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
)
19 changes: 7 additions & 12 deletions fuse_variables/test/launch_tests/test_load_device_id.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,30 +46,23 @@ class TestLoadDeviceId : public ::testing::Test
public:
void SetUp() override
{
exec_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

spinning_ = true;
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
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<bool> spinning_; //!< Flag for spinning the spin thread
rclcpp::executors::SingleThreadedExecutor::SharedPtr exec_;
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
};

TEST_F(TestLoadDeviceId, LoadDeviceId)
Expand Down Expand Up @@ -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);
Expand Down
56 changes: 18 additions & 38 deletions fuse_variables/test/launch_tests/test_load_device_id.py
Original file line number Diff line number Diff line change
Expand Up @@ -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"
6 changes: 0 additions & 6 deletions fuse_variables/test/test_acceleration_angular_2d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_acceleration_angular_3d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_acceleration_linear_2d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_acceleration_linear_3d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_fixed_size_variable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_orientation_2d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_orientation_3d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_point_2d_fixed_landmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_point_2d_landmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_point_3d_fixed_landmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_point_3d_landmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_position_2d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_position_3d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_velocity_angular_2d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_velocity_angular_3d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_velocity_linear_2d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
6 changes: 0 additions & 6 deletions fuse_variables/test/test_velocity_linear_3d_stamped.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

0 comments on commit 1696f10

Please sign in to comment.