Skip to content

Commit 804085a

Browse files
Add system test for geofence upload/download round-trip
Self-contained test using GroundStation + Autopilot MAVSDK instances over local UDP with MissionRawServer. No PX4 SITL dependency.
1 parent b40b567 commit 804085a

File tree

3 files changed

+76
-1
lines changed

3 files changed

+76
-1
lines changed

cpp/src/system_tests/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ add_executable(system_tests_runner
1515
param_get_all.cpp
1616
mission_raw_upload.cpp
1717
telemetry_subscription.cpp
18+
geofence_download.cpp
1819
fs_helpers.cpp
1920
ftp_download_file.cpp
2021
ftp_download_file_burst.cpp
Lines changed: 74 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,74 @@
1+
#include "log.h"
2+
#include "mavsdk.h"
3+
#include "plugins/geofence/geofence.h"
4+
#include "plugins/mission_raw_server/mission_raw_server.h"
5+
#include <future>
6+
#include <gtest/gtest.h>
7+
8+
using namespace mavsdk;
9+
10+
TEST(SystemTest, GeofenceUploadDownloadRoundTrip)
11+
{
12+
Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}};
13+
Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}};
14+
15+
ASSERT_EQ(
16+
mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17012"),
17+
ConnectionResult::Success);
18+
ASSERT_EQ(
19+
mavsdk_autopilot.add_any_connection("udpout://127.0.0.1:17012"),
20+
ConnectionResult::Success);
21+
22+
auto mission_raw_server = MissionRawServer{mavsdk_autopilot.server_component()};
23+
24+
auto maybe_system = mavsdk_groundstation.first_autopilot(10.0);
25+
ASSERT_TRUE(maybe_system);
26+
auto system = maybe_system.value();
27+
28+
auto geofence = Geofence{system};
29+
30+
// Build test geofence data: 1 inclusion polygon + 1 exclusion circle
31+
Geofence::GeofenceData upload_data;
32+
33+
Geofence::Polygon polygon;
34+
polygon.fence_type = Geofence::FenceType::Inclusion;
35+
polygon.points.push_back({47.3977, 8.5456});
36+
polygon.points.push_back({47.3980, 8.5460});
37+
polygon.points.push_back({47.3975, 8.5465});
38+
polygon.points.push_back({47.3972, 8.5458});
39+
upload_data.polygons.push_back(polygon);
40+
41+
Geofence::Circle circle;
42+
circle.fence_type = Geofence::FenceType::Exclusion;
43+
circle.point = {47.3978, 8.5459};
44+
circle.radius = 50.0f;
45+
upload_data.circles.push_back(circle);
46+
47+
// Upload
48+
auto upload_result = geofence.upload_geofence(upload_data);
49+
ASSERT_EQ(upload_result, Geofence::Result::Success);
50+
51+
// Download
52+
auto [download_result, download_data] = geofence.download_geofence();
53+
ASSERT_EQ(download_result, Geofence::Result::Success);
54+
55+
// Verify polygon
56+
ASSERT_EQ(download_data.polygons.size(), 1u);
57+
EXPECT_EQ(download_data.polygons[0].fence_type, Geofence::FenceType::Inclusion);
58+
ASSERT_EQ(download_data.polygons[0].points.size(), 4u);
59+
EXPECT_NEAR(download_data.polygons[0].points[0].latitude_deg, 47.3977, 1e-5);
60+
EXPECT_NEAR(download_data.polygons[0].points[0].longitude_deg, 8.5456, 1e-5);
61+
EXPECT_NEAR(download_data.polygons[0].points[3].latitude_deg, 47.3972, 1e-5);
62+
EXPECT_NEAR(download_data.polygons[0].points[3].longitude_deg, 8.5458, 1e-5);
63+
64+
// Verify circle
65+
ASSERT_EQ(download_data.circles.size(), 1u);
66+
EXPECT_EQ(download_data.circles[0].fence_type, Geofence::FenceType::Exclusion);
67+
EXPECT_NEAR(download_data.circles[0].point.latitude_deg, 47.3978, 1e-5);
68+
EXPECT_NEAR(download_data.circles[0].point.longitude_deg, 8.5459, 1e-5);
69+
EXPECT_FLOAT_EQ(download_data.circles[0].radius, 50.0f);
70+
71+
// Clear
72+
auto clear_result = geofence.clear_geofence();
73+
EXPECT_EQ(clear_result, Geofence::Result::Success);
74+
}

0 commit comments

Comments
 (0)