mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 17:34:01 -04:00
GCS_MAVLink: move handling of MAV_CMD_DO_SET_FENCE_ENABLED up
This commit is contained in:
parent
b54f61eccc
commit
8d45a8ff53
@ -407,6 +407,7 @@ protected:
|
|||||||
MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet);
|
||||||
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet);
|
||||||
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
|
||||||
|
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
|
||||||
|
|
||||||
// vehicle-overridable message send function
|
// vehicle-overridable message send function
|
||||||
virtual bool try_send_message(enum ap_message id);
|
virtual bool try_send_message(enum ap_message id);
|
||||||
|
@ -3477,6 +3477,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|||||||
result = handle_command_do_send_banner(packet);
|
result = handle_command_do_send_banner(packet);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_DO_FENCE_ENABLE:
|
||||||
|
result = handle_command_do_fence_enable(packet);
|
||||||
|
break;
|
||||||
|
|
||||||
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||||
result = handle_preflight_reboot(packet);
|
result = handle_preflight_reboot(packet);
|
||||||
break;
|
break;
|
||||||
|
@ -2,6 +2,25 @@
|
|||||||
|
|
||||||
#include <AC_Fence/AC_Fence.h>
|
#include <AC_Fence/AC_Fence.h>
|
||||||
|
|
||||||
|
MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_long_t &packet)
|
||||||
|
{
|
||||||
|
AC_Fence *fence = AP::fence();
|
||||||
|
if (fence == nullptr) {
|
||||||
|
return MAV_RESULT_UNSUPPORTED;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch ((uint16_t)packet.param1) {
|
||||||
|
case 0:
|
||||||
|
fence->enable(false);
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
case 1:
|
||||||
|
fence->enable(true);
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
default:
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// fence_send_mavlink_status - send fence status to ground station
|
// fence_send_mavlink_status - send fence status to ground station
|
||||||
void GCS_MAVLINK::send_fence_status() const
|
void GCS_MAVLINK::send_fence_status() const
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user