mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 14:38:44 -04:00
GCS_MAVLink: change AC_FENCE to AP_FENCE_ENABLED
This commit is contained in:
parent
a9310c3d18
commit
31bc6d9ec4
@ -38,7 +38,7 @@ void GCS::get_sensor_status_flags(uint32_t &present,
|
||||
|
||||
MissionItemProtocol_Waypoints *GCS::_missionitemprotocol_waypoints;
|
||||
MissionItemProtocol_Rally *GCS::_missionitemprotocol_rally;
|
||||
#if AC_FENCE
|
||||
#if AP_FENCE_ENABLED
|
||||
MissionItemProtocol_Fence *GCS::_missionitemprotocol_fence;
|
||||
#endif
|
||||
|
||||
@ -269,7 +269,7 @@ void GCS::update_sensor_status_flags()
|
||||
}
|
||||
#endif
|
||||
|
||||
#if !defined(HAL_BUILD_AP_PERIPH) && AC_FENCE
|
||||
#if !defined(HAL_BUILD_AP_PERIPH) && AP_FENCE_ENABLED
|
||||
const AC_Fence *fence = AP::fence();
|
||||
if (fence != nullptr) {
|
||||
if (fence->sys_status_enabled()) {
|
||||
|
@ -1064,7 +1064,7 @@ public:
|
||||
|
||||
static class MissionItemProtocol_Waypoints *_missionitemprotocol_waypoints;
|
||||
static class MissionItemProtocol_Rally *_missionitemprotocol_rally;
|
||||
#if AC_FENCE
|
||||
#if AP_FENCE_ENABLED
|
||||
static class MissionItemProtocol_Fence *_missionitemprotocol_fence;
|
||||
#endif
|
||||
class MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const;
|
||||
|
@ -561,7 +561,7 @@ MissionItemProtocol *GCS::get_prot_for_mission_type(const MAV_MISSION_TYPE missi
|
||||
return _missionitemprotocol_waypoints;
|
||||
case MAV_MISSION_TYPE_RALLY:
|
||||
return _missionitemprotocol_rally;
|
||||
#if AC_FENCE
|
||||
#if AP_FENCE_ENABLED
|
||||
case MAV_MISSION_TYPE_FENCE:
|
||||
return _missionitemprotocol_fence;
|
||||
#endif
|
||||
@ -2196,7 +2196,7 @@ void GCS::send_message(enum ap_message id)
|
||||
void GCS::update_send()
|
||||
{
|
||||
update_send_has_been_called = true;
|
||||
#if !defined(HAL_BUILD_AP_PERIPH) && AC_FENCE
|
||||
#if !defined(HAL_BUILD_AP_PERIPH) && AP_FENCE_ENABLED
|
||||
if (!initialised_missionitemprotocol_objects) {
|
||||
initialised_missionitemprotocol_objects = true;
|
||||
// once-only initialisation of MissionItemProtocol objects:
|
||||
@ -6164,7 +6164,7 @@ uint64_t GCS_MAVLINK::capabilities() const
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AC_FENCE
|
||||
#if AP_FENCE_ENABLED
|
||||
if (AP::fence()) {
|
||||
ret |= MAV_PROTOCOL_CAPABILITY_MISSION_FENCE;
|
||||
}
|
||||
|
@ -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
|
||||
}
|
||||
#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)
|
||||
#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
|
||||
mavlink_breach_type,
|
||||
fence->get_breach_time(),
|
||||
breach_mitigation);
|
||||
#endif // AC_FENCE
|
||||
#endif // AP_FENCE_ENABLED
|
||||
}
|
||||
|
@ -4,7 +4,7 @@
|
||||
#include <AP_InternalError/AP_InternalError.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#if AC_FENCE
|
||||
#if AP_FENCE_ENABLED
|
||||
|
||||
/*
|
||||
public function to format mission item as mavlink_mission_item_int_t
|
||||
@ -244,4 +244,4 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_update_resources()
|
||||
return MAV_MISSION_ACCEPTED;
|
||||
}
|
||||
|
||||
#endif // AC_FENCE
|
||||
#endif // AP_FENCE_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user