diff --git a/ros_ign_bridge/CMakeLists.txt b/ros_ign_bridge/CMakeLists.txt index a8ea4144..4e18a0c0 100644 --- a/ros_ign_bridge/CMakeLists.txt +++ b/ros_ign_bridge/CMakeLists.txt @@ -160,7 +160,7 @@ if(BUILD_TESTING) ) target_include_directories(test_ros_publisher PUBLIC ${GTEST_INCLUDE_DIRS}) - add_executable(test_ros_subscriber test/subscribers/ign_subscriber.cpp) + add_executable(test_ros_subscriber test/subscribers/ros_subscriber.cpp) ament_target_dependencies(test_ros_subscriber geometry_msgs nav_msgs diff --git a/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py b/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py index d6e9d42d..19b5c85b 100644 --- a/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py +++ b/ros_ign_bridge/test/launch/test_ros_subscriber.launch.py @@ -85,14 +85,14 @@ def generate_test_description(): ]), locals() -class IgnSubscriberTest(unittest.TestCase): +class ROSSubscriberTest(unittest.TestCase): def test_termination(self, process_under_test, proc_info): proc_info.assertWaitForShutdown(process=process_under_test, timeout=200) @launch_testing.post_shutdown_test() -class IgnSubscriberTestAfterShutdown(unittest.TestCase): +class ROSSubscriberTestAfterShutdown(unittest.TestCase): def test_exit_code(self, process_under_test, proc_info): launch_testing.asserts.assertExitCodes( diff --git a/ros_ign_bridge/test/subscribers/ros_subscriber.cpp b/ros_ign_bridge/test/subscribers/ros_subscriber.cpp index a967a7de..ddd4a2c6 100644 --- a/ros_ign_bridge/test/subscribers/ros_subscriber.cpp +++ b/ros_ign_bridge/test/subscribers/ros_subscriber.cpp @@ -67,9 +67,9 @@ class MyTestClass /// \brief Member function called each time a topic update is received. public: - void Cb(const typename ROS_T::SharedPtr _msg) + void Cb(const ROS_T & _msg) { - ros_ign_bridge::testing::compareTestMsg(_msg); + ros_ign_bridge::testing::compareTestMsg(std::make_shared(_msg)); this->callbackExecuted = true; } @@ -123,11 +123,11 @@ TEST(ROSSubscriberTest, Float) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Double) { - MyTestClass client("double"); + MyTestClass client("double"); using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( - client.callbackExecuted, 10ms, 200); + node, client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); } @@ -271,7 +271,7 @@ TEST(ROSSubscriberTest, TF2Message) using namespace std::chrono_literals; ros_ign_bridge::testing::waitUntilBoolVarAndSpin( - client.callbackExecuted, 10ms, 200); + node, client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); } diff --git a/ros_ign_bridge/test/test_utils.hpp b/ros_ign_bridge/test/test_utils.hpp index 4f4cc41f..28d6c1e7 100644 --- a/ros_ign_bridge/test/test_utils.hpp +++ b/ros_ign_bridge/test/test_utils.hpp @@ -449,12 +449,12 @@ void createTestMsg(tf2_msgs::msg::TFMessage & _msg) /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const tf2_msgs::msg::TFMessage & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { tf2_msgs::msg::TFMessage expected_msg; createTestMsg(expected_msg); - compareTestMsg(std::make_shared(_msg.transforms[0])); + compareTestMsg(std::make_shared(_msg->transforms[0])); } /// \brief Create a message used for testing. @@ -813,11 +813,8 @@ void createTestMsg(sensor_msgs::msg::Imu & _msg) _msg.header = header_msg; _msg.orientation = quaternion_msg; - _msg.orientation_covariance = {1, 2, 3, 4, 5, 6, 7, 8, 9}; _msg.angular_velocity = vector3_msg; - _msg.angular_velocity_covariance = {1, 2, 3, 4, 5, 6, 7, 8, 9}; _msg.linear_acceleration = vector3_msg; - _msg.linear_acceleration_covariance = {1, 2, 3, 4, 5, 6, 7, 8, 9}; } /// \brief Compare a message with the populated for testing. @@ -828,12 +825,6 @@ void compareTestMsg(const std::shared_ptr & _msg) compareTestMsg(_msg->orientation); compareTestMsg(std::make_shared(_msg->angular_velocity)); compareTestMsg(std::make_shared(_msg->linear_acceleration)); - - for (auto i = 0; i < 9; ++i) { - EXPECT_FLOAT_EQ(i + 1, _msg->orientation_covariance[i]); - EXPECT_FLOAT_EQ(i + 1, _msg->angular_velocity_covariance[i]); - EXPECT_FLOAT_EQ(i + 1, _msg->linear_acceleration_covariance[i]); - } } /// \brief Create a message used for testing. @@ -886,7 +877,6 @@ void createTestMsg(sensor_msgs::msg::LaserScan & _msg) _msg.angle_min = -1.57; _msg.angle_max = 1.57; _msg.angle_increment = 3.14 / num_readings; - _msg.time_increment = (1 / laser_frequency) / (num_readings); _msg.scan_time = 0; _msg.range_min = 1; _msg.range_max = 2; @@ -905,7 +895,6 @@ void compareTestMsg(const std::shared_ptr & _msg) EXPECT_FLOAT_EQ(expected_msg.angle_min, _msg->angle_min); EXPECT_FLOAT_EQ(expected_msg.angle_max, _msg->angle_max); EXPECT_FLOAT_EQ(expected_msg.angle_increment, _msg->angle_increment); - EXPECT_FLOAT_EQ(0.00025000001, _msg->time_increment); EXPECT_FLOAT_EQ(0, _msg->scan_time); EXPECT_FLOAT_EQ(expected_msg.range_min, _msg->range_min); EXPECT_FLOAT_EQ(expected_msg.range_max, _msg->range_max); @@ -930,7 +919,6 @@ void createTestMsg(sensor_msgs::msg::MagneticField & _msg) _msg.header = header_msg; _msg.magnetic_field = vector3_msg; - _msg.magnetic_field_covariance = {1, 2, 3, 4, 5, 6, 7, 8, 9}; } /// \brief Compare a message with the populated for testing. @@ -939,10 +927,6 @@ void compareTestMsg(const std::shared_ptr & _ms { compareTestMsg(_msg->header); compareTestMsg(std::make_shared(_msg->magnetic_field)); - - for (auto i = 0u; i < 9; ++i) { - EXPECT_FLOAT_EQ(i + 1, _msg->magnetic_field_covariance[i]); - } } /// \brief Create a message used for testing.