AP_DDS: Correct compilation of tests without external odom

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
Ryan Friedman 2024-09-17 22:34:24 -06:00 committed by Peter Barker
parent c0d14ec397
commit aecb3268c7

View File

@ -1,9 +1,13 @@
#include <AP_gtest.h> #include <AP_gtest.h>
#include <AP_DDS/AP_DDS_config.h>
#include <AP_DDS/AP_DDS_External_Odom.h> #include <AP_DDS/AP_DDS_External_Odom.h>
#include "geometry_msgs/msg/TransformStamped.h" #include "geometry_msgs/msg/TransformStamped.h"
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#if AP_DDS_VISUALODOM_ENABLED
const AP_HAL::HAL &hal = AP_HAL::get_HAL(); const AP_HAL::HAL &hal = AP_HAL::get_HAL();
TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success) TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success)
@ -35,4 +39,6 @@ TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success)
ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg)); ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg));
} }
#endif // AP_DDS_VISUALODOM_ENABLED
AP_GTEST_MAIN() AP_GTEST_MAIN()