Skip to content

Commit

Permalink
Command: per-geofences action
Browse files Browse the repository at this point in the history
  • Loading branch information
hamishwillee committed Apr 15, 2021
1 parent 0c7bdea commit 9dd2183
Showing 1 changed file with 26 additions and 4 deletions.
30 changes: 26 additions & 4 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -314,20 +314,30 @@
</enum>
<!-- fenced mode enums -->
<enum name="FENCE_ACTION">
<description>Actions following geofence breach.</description>
<entry value="0" name="FENCE_ACTION_NONE">
<description>Disable fenced mode</description>
<description>Disable fenced mode. If used in a plan this would mean the next fence is disabled.</description>
</entry>
<entry value="1" name="FENCE_ACTION_GUIDED">
<description>Switched to guided mode to return point (fence point 0)</description>
<description>Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions.</description>
</entry>
<entry value="2" name="FENCE_ACTION_REPORT">
<description>Report fence breach, but don't take action</description>
</entry>
<entry value="3" name="FENCE_ACTION_GUIDED_THR_PASS">
<description>Switched to guided mode to return point (fence point 0) with manual throttle control</description>
<description>Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions.</description>
</entry>
<entry value="4" name="FENCE_ACTION_RTL">
<description>Switch to RTL (return to launch) mode and head for the return point.</description>
<description>Return/RTL mode.</description>
</entry>
<entry value="5" name="FENCE_ACTION_HOLD">
<description>Hold at current location.</description>
</entry>
<entry value="6" name="FENCE_ACTION_TERMINATE">
<description>Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions).</description>
</entry>
<entry value="7" name="FENCE_ACTION_LAND">
<description>Land at current location.</description>
</entry>
</enum>
<enum name="FENCE_BREACH">
Expand Down Expand Up @@ -2027,6 +2037,18 @@
<param index="6" label="Longitude">Longitude</param>
<param index="7">Reserved</param>
</entry>
<entry value="5005" name="MAV_CMD_SET_FENCE_BREACH_ACTION" hasLocation="false" isDestination="false">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Sets the action on geofence breach.
If sent using the command protocol this sets the system-default geofence action.
As part of a mission protocol plan it sets the fence action for the next complete geofence definition *after* the command.
Note: A fence action defined in a plan will override the default system setting (even if the system-default is `FENCE_ACTION_NONE`).
Note: Every geofence in a plan can have its own action; if no fence action is defined for a particular fence the system-default will be used.
Note: The flight stack should reject a plan or command that uses a geofence action that it does not support and send a STATUSTEXT with the reason.
</description>
<param index="1" label="Action" enum="FENCE_ACTION">Fence action on breach.</param>
</entry>
<entry value="5100" name="MAV_CMD_NAV_RALLY_POINT" hasLocation="true" isDestination="false">
<description>Rally point. You can have multiple rally points defined.
</description>
Expand Down

0 comments on commit 9dd2183

Please sign in to comment.