Skip to content

Commit bfe1c77

Browse files
committed
common.xml: add polygon fence variants with altitude
1 parent f5eeecf commit bfe1c77

File tree

1 file changed

+46
-0
lines changed

1 file changed

+46
-0
lines changed

message_definitions/v1.0/common.xml

Lines changed: 46 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1937,6 +1937,52 @@
19371937
<param index="6" label="Longitude">Longitude</param>
19381938
<param index="7">Reserved</param>
19391939
</entry>
1940+
1941+
<entry value="5005" name="MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION_WITH_ALTITUDES" hasLocation="true" isDestination="false">
1942+
<description>Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. Altitudes supplied.
1943+
</description>
1944+
<param index="1" label="Vertex Count" minValue="3" increment="1">Polygon vertex count</param>
1945+
<param index="2" label="Inclusion Group" minValue="0" increment="1">Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group, must be the same for all points in each polygon</param>
1946+
<param index="3" label="Minimum Altitude"></param>
1947+
<param index="4" label="Maximum Altitude"></param>
1948+
<param index="5" label="Latitude">Latitude</param>
1949+
<param index="6" label="Longitude">Longitude</param>
1950+
<param index="7" label="Altitude Frames"></param> <!-- (param7&0b11111) bits give frame for mimimum altitude, ((param7>>5)&0b11111) gives frame for maximum altitude -->
1951+
</entry>
1952+
<entry value="5006" name="MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION_WITH_ALTITUDES" hasLocation="true" isDestination="false">
1953+
<description>Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required.
1954+
</description>
1955+
<param index="1" label="Vertex Count" minValue="3" increment="1">Polygon vertex count</param>
1956+
<param index="2">Reserved</param>
1957+
<param index="3" label="Minimum Altitude"></param>
1958+
<param index="4" label="Maximum Altitude"></param>
1959+
<param index="5" label="Latitude">Latitude</param>
1960+
<param index="6" label="Longitude">Longitude</param>
1961+
<param index="7" label="Altitude Frames"></param> <!-- (param7&0b11111) bits give frame for mimimum altitude, ((param7>>5)&0b11111) gives frame for maximum altitude -->
1962+
</entry>
1963+
<entry value="5007" name="MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION_WITH_ALTITUDES" hasLocation="true" isDestination="false">
1964+
<description>Circular fence area. The vehicle must stay inside this area.
1965+
</description>
1966+
<param index="1" label="Radius" units="m">Radius.</param>
1967+
<param index="2" label="Inclusion Group" minValue="0" increment="1">Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group</param>
1968+
<param index="3" label="Minimum Altitude"></param>
1969+
<param index="4" label="Maximum Altitude"></param>
1970+
<param index="5" label="Latitude">Latitude</param>
1971+
<param index="6" label="Longitude">Longitude</param>
1972+
<param index="7" label="Altitude Frames"></param> <!-- (param7&0b11111) bits give frame for mimimum altitude, ((param7>>5)&0b11111) gives frame for maximum altitude -->
1973+
</entry>
1974+
<entry value="5008" name="MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION_WITH_ALTITUDES" hasLocation="true" isDestination="false">
1975+
<description>Circular fence area. The vehicle must stay outside this area.
1976+
</description>
1977+
<param index="1" label="Radius" units="m">Radius.</param>
1978+
<param index="2">Reserved</param>
1979+
<param index="3" label="Minimum Altitude"></param>
1980+
<param index="4" label="Maximum Altitude"></param>
1981+
<param index="5" label="Latitude">Latitude</param>
1982+
<param index="6" label="Longitude">Longitude</param>
1983+
<param index="7" label="Altitude Frames"></param> <!-- (param7&0b11111) bits give frame for mimimum altitude, ((param7>>5)&0b11111) gives frame for maximum altitude -->
1984+
</entry>
1985+
19401986
<entry value="5100" name="MAV_CMD_NAV_RALLY_POINT" hasLocation="true" isDestination="false">
19411987
<description>Rally point. You can have multiple rally points defined.
19421988
</description>

0 commit comments

Comments
 (0)