This report covers an input/domain validation issue in the PX4 MAVLink geofence upload path. For polygon fences, PX4 accepts an inflated polygon vertex_count with MAV_MISSION_ACCEPTED, but the resulting custom geofence is not enforced as uploaded.
All examples use the MAVLink mission protocol with mission_type=MAV_MISSION_TYPE_FENCE.
Tested environment:
PX4 SITL: gazebo-classic iris
PX4 version: Release 1.16.1
PX4 git-hash: 94cb2012792b2ae89f0b147cfee53ee31ae550be
A. Geofence polygon metadata validation
For MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION and MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, param1 is the polygon vertex count. PX4 accepts a fence upload where the MAVLink transaction contains only 4 fence items, but each uploaded item declares param1=256.
This creates a mismatch between the transaction count and the polygon metadata:
MISSION_COUNT.count = 4
item 0..3 command = MAV_CMD_NAV_FENCE_POLYGON_VERTEX_*
item 0..3 param1 = 256
A1. Exclusion polygon: an accepted no-fly zone can fail open
Reproduction setup:
- Move Home outside the test no-fly zone using
MAV_CMD_DO_SET_HOME, so a normal exclusion fence is not rejected because of Home position. - Upload a square exclusion polygon around the current SITL vehicle position.
- Use
MISSION_COUNT.count=4,mission_type=MAV_MISSION_TYPE_FENCE. - Send 4
MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSIONitems. - Use the same coordinates in both tests.
- Only change
param1from4to256.
Normal case:
MISSION_ACK: MAV_MISSION_ACCEPTED
navigator status:
Geofence: 0 inclusion, 1 exclusion polygons, 0 inclusion circles, 0 exclusion circles, 4 total vertices
listener geofence_result:
geofence_custom_fence_triggered: True
Malformed case:
MISSION_ACK: MAV_MISSION_ACCEPTED
navigator status:
Geofence: 0 inclusion, 1 exclusion polygons, 0 inclusion circles, 0 exclusion circles, 256 total vertices
listener geofence_result:
geofence_custom_fence_triggered: False
The vehicle is at the same position inside the same square in both tests. With the valid 4-vertex polygon, PX4 reports a custom geofence trigger. With param1=256, the upload is still accepted, but the exclusion polygon no longer triggers.
Expected behavior: PX4 should reject the upload because the declared polygon vertex count is inconsistent with the actual uploaded fence item count.
Actual behavior: PX4 accepts the upload and Navigator installs a polygon with 256 declared vertices even though only 4 vertices were uploaded.
A2. Inclusion polygon: an accepted containment fence can be discarded
With the same 4-point square as an inclusion polygon:
Normal case (param1=4):
MISSION_ACK: MAV_MISSION_ACCEPTED
navigator status:
Geofence: 1 inclusion, 0 exclusion polygons, 0 inclusion circles, 0 exclusion circles, 4 total vertices
listener geofence_result:
geofence_custom_fence_triggered: False
Malformed case (param1=256):
MISSION_ACK: MAV_MISSION_ACCEPTED
PX4 shell:
WARN [navigator] Geofence invalid, doesn't contain Home position
navigator status:
Geofence: 0 inclusion, 0 exclusion polygons, 0 inclusion circles, 0 exclusion circles, 0 total vertices
The upload ACK is still MAV_MISSION_ACCEPTED, but Navigator later discards the malformed inclusion fence during validation. From the uploader’s point of view, the fence upload succeeded; from Navigator’s point of view, there is no active custom fence.
Relevant source in PX4 v1.16.1:
// mavlink_mission.cpp:915-918
if (wpc.count > current_max_item_count()) {
send_mission_ack(..., MAV_MISSION_NO_SPACE);
}
The upload transaction count is checked against capacity, but not against each polygon’s declared vertex_count.
// mavlink_mission.cpp:1514-1517
case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION:
case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION:
mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
mission_item->vertex_count = (uint16_t)(mavlink_mission_item->param1 + 0.5f);
break;
param1 is copied into mission_item->vertex_count.
// mavlink_mission.cpp:1189-1195
if (mission_item.nav_cmd == MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION ||
mission_item.nav_cmd == MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION) {
mission_fence_point.vertex_count = mission_item.vertex_count;
if (mission_item.vertex_count < 3) {
check_failed = true;
}
}
The feasibility check only rejects fewer than 3 vertices. It does not reject a declared vertex count that exceeds the remaining uploaded fence items.
// geofence.cpp:267-277
PolygonInfo &polygon = _polygons[_num_polygons];
polygon.dataman_index = current_seq;
polygon.fence_type = mission_fence_point.nav_cmd;
if (is_circle_area) {
polygon.circle_radius = mission_fence_point.circle_radius;
current_seq += 1;
} else {
polygon.vertex_count = mission_fence_point.vertex_count;
current_seq += mission_fence_point.vertex_count;
}
Navigator trusts the stored vertex_count and advances current_seq by that value.
// geofence.cpp:446-460
for (unsigned i = 0, j = polygon.vertex_count - 1; i < polygon.vertex_count; j = i++) {
bool success = _dataman_cache.loadWait(..., polygon.dataman_index + i, ...);
if (!success) {
break;
}
success = _dataman_cache.loadWait(..., polygon.dataman_index + j, ...);
if (!success) {
break;
}
}
// geofence.cpp:484
return c;
When the declared vertex count is larger than the stored items, the polygon read loop breaks early and returns the default false value. For an exclusion polygon, false means “not inside the exclusion area”, so the no-fly zone can fail open.
Impact:
- A GCS or companion computer can upload a malformed exclusion polygon and receive
MAV_MISSION_ACCEPTED. - The no-fly zone can be present in
navigator statusbut not trigger even when the vehicle is inside the intended polygon. - This requires only MAVLink fence-upload access. It does not require arming or flight.
Suggested fixes
- Reject polygon
vertex_countvalues that are inconsistent withMISSION_COUNT.countand the remaining uploaded fence items. - Reject polygon
vertex_countvalues outside a sane maximum before writing them to dataman. - During Navigator fence loading, treat failed dataman reads for required polygon vertices as an invalid fence, not as a geometric
false. - If Navigator later rejects an uploaded fence set, expose that as an upload-time failure or a clear MAVLink status/error path rather than returning only
MAV_MISSION_ACCEPTED.