Skip to content

Commit d37a367

Browse files
authored
Merge pull request #332 from tritonuas/fix/forward-pathing
Forward Pathing Fix
2 parents f7c2abb + 6ef04fa commit d37a367

File tree

4 files changed

+4
-17
lines changed

4 files changed

+4
-17
lines changed

protos

src/pathing/static.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -645,21 +645,20 @@ MissionPath generateInitialPath(std::shared_ptr<MissionState> state) {
645645
MissionPath generateSearchPath(std::shared_ptr<MissionState> state) {
646646
std::vector<GPSCoord> gps_coords;
647647
if (state->config.pathing.coverage.method == AirdropCoverageMethod::Enum::FORWARD) {
648-
LOG_F(FATAL, "Forward search path not fully integrated yet.");
649-
650648
RRTPoint start(state->mission_params.getWaypoints().front(), 0);
651649

652650
// TODO , change the starting point to be something closer to loiter
653651
// region
654-
ForwardCoveragePathing pathing(start, SEARCH_RADIUS,
652+
double scan_radius = state->config.pathing.coverage.camera_vision_m;
653+
ForwardCoveragePathing pathing(start, scan_radius,
655654
state->mission_params.getFlightBoundary(),
656655
state->mission_params.getAirdropBoundary(), state->config);
657656

658657
for (const auto &coord : pathing.run()) {
659658
gps_coords.push_back(state->getCartesianConverter()->toLatLng(coord));
660659
}
661660

662-
return MissionPath(MissionPath::Type::FORWARD, {});
661+
return MissionPath(MissionPath::Type::FORWARD, gps_coords);
663662
} else { // hover
664663
HoverCoveragePathing pathing(state);
665664

tests/integration/util/mission_data_2020.json

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -158,11 +158,5 @@
158158
"Longitude": -76.4282527777778,
159159
"Altitude": 200.0
160160
}
161-
],
162-
163-
"MappingBoundary": [
164-
{ "Latitude": 0.0, "Longitude": 0.0, "Altitude": 0.0},
165-
{ "Latitude": 0.0, "Longitude": 0.0, "Altitude": 0.0},
166-
{ "Latitude": 0.0, "Longitude": 0.0, "Altitude": 0.0}
167161
]
168162
}

tests/integration/util/mission_data_2024.json

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -146,11 +146,5 @@
146146
"Longitude": -76.4282527777778,
147147
"Altitude": 200
148148
}
149-
],
150-
"MappingBoundary": [
151-
{ "Latitude": 38.314669, "Longitude": -76.547987, "Altitude": 0.0},
152-
{ "Latitude": 38.315873, "Longitude": -76.547611, "Altitude": 0.0},
153-
{ "Latitude": 38.315208, "Longitude": -76.54384, "Altitude": 0.0},
154-
{ "Latitude": 38.314008, "Longitude": -76.544237, "Altitude": 0.0}
155149
]
156150
}

0 commit comments

Comments
 (0)