|
|
|
@ -6,7 +6,7 @@
@@ -6,7 +6,7 @@
|
|
|
|
|
|
|
|
|
|
MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_long_t &packet) |
|
|
|
|
{ |
|
|
|
|
#if AC_FENCE |
|
|
|
|
#if AP_FENCE_ENABLED |
|
|
|
|
AC_Fence *fence = AP::fence(); |
|
|
|
|
if (fence == nullptr) { |
|
|
|
|
return MAV_RESULT_UNSUPPORTED; |
|
|
|
@ -32,12 +32,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_lon
@@ -32,12 +32,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_lon
|
|
|
|
|
} |
|
|
|
|
#else |
|
|
|
|
return MAV_RESULT_UNSUPPORTED; |
|
|
|
|
#endif // AC_FENCE
|
|
|
|
|
#endif // AP_FENCE_ENABLED
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void GCS_MAVLINK::handle_fence_message(const mavlink_message_t &msg) |
|
|
|
|
{ |
|
|
|
|
#if AC_FENCE |
|
|
|
|
#if AP_FENCE_ENABLED |
|
|
|
|
AC_Fence *fence = AP::fence(); |
|
|
|
|
if (fence == nullptr) { |
|
|
|
|
return; |
|
|
|
@ -54,13 +54,13 @@ void GCS_MAVLINK::handle_fence_message(const mavlink_message_t &msg)
@@ -54,13 +54,13 @@ void GCS_MAVLINK::handle_fence_message(const mavlink_message_t &msg)
|
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
#endif // AC_FENCE
|
|
|
|
|
#endif // AP_FENCE_ENABLED
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// fence_send_mavlink_status - send fence status to ground station
|
|
|
|
|
void GCS_MAVLINK::send_fence_status() const |
|
|
|
|
{ |
|
|
|
|
#if AC_FENCE |
|
|
|
|
#if AP_FENCE_ENABLED |
|
|
|
|
const AC_Fence *fence = AP::fence(); |
|
|
|
|
if (fence == nullptr) { |
|
|
|
|
return; |
|
|
|
@ -102,5 +102,5 @@ void GCS_MAVLINK::send_fence_status() const
@@ -102,5 +102,5 @@ void GCS_MAVLINK::send_fence_status() const
|
|
|
|
|
mavlink_breach_type, |
|
|
|
|
fence->get_breach_time(), |
|
|
|
|
breach_mitigation); |
|
|
|
|
#endif // AC_FENCE
|
|
|
|
|
#endif // AP_FENCE_ENABLED
|
|
|
|
|
} |
|
|
|
|