mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: change AC_FENCE to AP_FENCE_ENABLED
This commit is contained in:
parent
cf1e1b2969
commit
9d4d0c10eb
@ -21,7 +21,7 @@
|
|||||||
|
|
||||||
bool AP_Rally_Rover::is_valid(const Location &rally_point) const
|
bool AP_Rally_Rover::is_valid(const Location &rally_point) const
|
||||||
{
|
{
|
||||||
#if AC_FENCE
|
#if AP_FENCE_ENABLED
|
||||||
if (!rover.fence.check_destination_within_fence(rally_point)) {
|
if (!rover.fence.check_destination_within_fence(rally_point)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -843,7 +843,7 @@ void Rover::load_parameters(void)
|
|||||||
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);
|
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_AIRSPEED_ENABLED | AP_AIS_ENABLED | AC_FENCE
|
#if AP_AIRSPEED_ENABLED | AP_AIS_ENABLED | AP_FENCE_ENABLED
|
||||||
// Find G2's Top Level Key
|
// Find G2's Top Level Key
|
||||||
AP_Param::ConversionInfo info;
|
AP_Param::ConversionInfo info;
|
||||||
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
|
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
|
||||||
@ -864,7 +864,7 @@ void Rover::load_parameters(void)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PARAMETER_CONVERSION - Added: Mar-2022
|
// PARAMETER_CONVERSION - Added: Mar-2022
|
||||||
#if AC_FENCE
|
#if AP_FENCE_ENABLED
|
||||||
AP_Param::convert_class(info.old_key, &fence, fence.var_info, 17, 4049, false);
|
AP_Param::convert_class(info.old_key, &fence, fence.var_info, 17, 4049, false);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
// fence_check - ask fence library to check for breaches and initiate the response
|
// fence_check - ask fence library to check for breaches and initiate the response
|
||||||
void Rover::fence_check()
|
void Rover::fence_check()
|
||||||
{
|
{
|
||||||
#if AC_FENCE
|
#if AP_FENCE_ENABLED
|
||||||
uint8_t new_breaches; // the type of fence that has been breached
|
uint8_t new_breaches; // the type of fence that has been breached
|
||||||
const uint8_t orig_breaches = fence.get_breaches();
|
const uint8_t orig_breaches = fence.get_breaches();
|
||||||
|
|
||||||
@ -57,5 +57,5 @@ void Rover::fence_check()
|
|||||||
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE,
|
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE,
|
||||||
LogErrorCode::ERROR_RESOLVED);
|
LogErrorCode::ERROR_RESOLVED);
|
||||||
}
|
}
|
||||||
#endif // AC_FENCE
|
#endif // AP_FENCE_ENABLED
|
||||||
}
|
}
|
||||||
|
@ -481,7 +481,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_FENCE_ENABLE:
|
case MAV_CMD_DO_FENCE_ENABLE:
|
||||||
#if AC_FENCE
|
#if AP_FENCE_ENABLED
|
||||||
if (cmd.p1 == 0) { //disable
|
if (cmd.p1 == 0) { //disable
|
||||||
rover.fence.enable(false);
|
rover.fence.enable(false);
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled");
|
gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled");
|
||||||
|
@ -220,7 +220,7 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason)
|
|||||||
|
|
||||||
control_mode = &new_mode;
|
control_mode = &new_mode;
|
||||||
|
|
||||||
#if AC_FENCE
|
#if AP_FENCE_ENABLED
|
||||||
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
|
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
|
||||||
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
|
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
|
||||||
// but it should be harmless to disable the fence temporarily in these situations as well
|
// but it should be harmless to disable the fence temporarily in these situations as well
|
||||||
|
Loading…
Reference in New Issue
Block a user