Skip to content

Commit

Permalink
AP_DDS: Correct compilation of tests without external odom
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Sep 21, 2024
1 parent 6f867e2 commit ae6a626
Showing 1 changed file with 6 additions and 0 deletions.
6 changes: 6 additions & 0 deletions libraries/AP_DDS/tests/test_ap_dds_external_odom.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,13 @@
#include <AP_gtest.h>

#include <AP_DDS/AP_DDS_config.h>

#include <AP_DDS/AP_DDS_External_Odom.h>
#include "geometry_msgs/msg/TransformStamped.h"
#include <AP_HAL/AP_HAL.h>

#if AP_DDS_VISUALODOM_ENABLED

const AP_HAL::HAL &hal = AP_HAL::get_HAL();

TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success)
Expand Down Expand Up @@ -35,4 +39,6 @@ TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success)
ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg));
}

#endif // AP_DDS_VISUALODOM_ENABLED

AP_GTEST_MAIN()

0 comments on commit ae6a626

Please sign in to comment.