mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
GCS_MAVLink: handld MAV_CMD_DO_FENCE_ENABLE as both long and int
This commit is contained in:
parent
c3c7784c23
commit
25846eb2bc
@ -658,7 +658,7 @@ protected:
|
||||
MAV_RESULT handle_command_do_sprayer(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_set_mode(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_get_home_position(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_debug_trap(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_set_ekf_source_set(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_command_airframe_configuration(const mavlink_command_int_t &packet);
|
||||
|
@ -4727,12 +4727,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
||||
|
||||
switch (packet.command) {
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
case MAV_CMD_DO_FENCE_ENABLE:
|
||||
result = handle_command_do_fence_enable(packet);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if HAL_HIGH_LATENCY2_ENABLED
|
||||
case MAV_CMD_CONTROL_HIGH_LATENCY:
|
||||
result = handle_control_high_latency(packet);
|
||||
@ -5085,6 +5079,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
||||
case MAV_CMD_DO_AUX_FUNCTION:
|
||||
return handle_command_do_aux_function(packet);
|
||||
|
||||
#if AP_FENCE_ENABLED
|
||||
case MAV_CMD_DO_FENCE_ENABLE:
|
||||
return handle_command_do_fence_enable(packet);
|
||||
#endif
|
||||
|
||||
case MAV_CMD_DO_FLIGHTTERMINATION:
|
||||
return handle_flight_termination(packet);
|
||||
|
||||
|
@ -9,7 +9,7 @@
|
||||
#include <AC_Avoidance/AC_Avoid.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_long_t &packet)
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_int_t &packet)
|
||||
{
|
||||
AC_Fence *fence = AP::fence();
|
||||
if (fence == nullptr) {
|
||||
|
Loading…
Reference in New Issue
Block a user