-
-
Notifications
You must be signed in to change notification settings - Fork 484
/
geofence_inclusion.cpp
56 lines (43 loc) · 1.71 KB
/
geofence_inclusion.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
#include <iostream>
#include <memory>
#include "integration_test_helper.h"
#include "mavsdk.h"
#include "plugins/telemetry/telemetry.h"
#include "plugins/geofence/geofence.h"
using namespace mavsdk;
static Geofence::Point add_point(double latitude_deg, double longitude_deg);
TEST_F(SitlTest, GeofenceInclusion)
{
Mavsdk mavsdk;
ConnectionResult ret = mavsdk.add_udp_connection();
ASSERT_EQ(ret, ConnectionResult::Success);
// Wait for system to connect via heartbeat.
std::this_thread::sleep_for(std::chrono::seconds(2));
auto system = mavsdk.systems().at(0);
ASSERT_TRUE(system->has_autopilot());
auto telemetry = std::make_shared<Telemetry>(system);
auto geofence = std::make_shared<Geofence>(system);
while (!telemetry->health_all_ok()) {
LogInfo() << "waiting for system to be ready";
std::this_thread::sleep_for(std::chrono::seconds(1));
}
LogInfo() << "System ready, let's start";
std::vector<Geofence::Point> points;
points.push_back(add_point(47.39929240, 8.54296524));
points.push_back(add_point(47.39696482, 8.54161340));
points.push_back(add_point(47.39626761, 8.54527193));
points.push_back(add_point(47.39980072, 8.54736050));
std::vector<Geofence::Polygon> polygons;
Geofence::Polygon new_polygon{};
new_polygon.fence_type = Geofence::Polygon::FenceType::Inclusion;
new_polygon.points = points;
polygons.push_back(new_polygon);
EXPECT_EQ(Geofence::Result::Success, geofence->upload_geofence(polygons));
}
Geofence::Point add_point(double latitude_deg, double longitude_deg)
{
Geofence::Point new_point;
new_point.latitude_deg = latitude_deg;
new_point.longitude_deg = longitude_deg;
return new_point;
}