CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/fence.cpp
Views: 1798
1
#include "Copter.h"
2
3
// Code to integrate AC_Fence library with main ArduCopter code
4
5
#if AP_FENCE_ENABLED
6
7
// fence_check - ask fence library to check for breaches and initiate the response
8
// called at 1hz
9
void Copter::fence_check()
10
{
11
const uint8_t orig_breaches = fence.get_breaches();
12
13
bool is_landing_or_landed = flightmode->is_landing() || ap.land_complete || !motors->armed();
14
15
// check for new breaches; new_breaches is bitmask of fence types breached
16
const uint8_t new_breaches = fence.check(is_landing_or_landed);
17
18
// we still don't do anything when disarmed, but we do check for fence breaches.
19
// fence pre-arm check actually checks if any fence has been breached
20
// that's not ever going to be true if we don't call check on AP_Fence while disarmed.
21
if (!motors->armed()) {
22
return;
23
}
24
25
// if there is a new breach take action
26
if (new_breaches) {
27
28
if (!copter.ap.land_complete) {
29
fence.print_fence_message("breached", new_breaches);
30
}
31
32
// if the user wants some kind of response and motors are armed
33
uint8_t fence_act = fence.get_action();
34
if (fence_act != AC_FENCE_ACTION_REPORT_ONLY ) {
35
36
// disarm immediately if we think we are on the ground or in a manual flight mode with zero throttle
37
// don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down
38
if (ap.land_complete || (flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){
39
arming.disarm(AP_Arming::Method::FENCEBREACH);
40
41
} else {
42
43
// if more than 100m outside the fence just force a land
44
if (fence.get_breach_distance(new_breaches) > AC_FENCE_GIVE_UP_DISTANCE) {
45
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
46
} else {
47
switch (fence_act) {
48
case AC_FENCE_ACTION_RTL_AND_LAND:
49
default:
50
// switch to RTL, if that fails then Land
51
if (!set_mode(Mode::Number::RTL, ModeReason::FENCE_BREACHED)) {
52
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
53
}
54
break;
55
case AC_FENCE_ACTION_ALWAYS_LAND:
56
// if always land option mode is specified, land
57
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
58
break;
59
case AC_FENCE_ACTION_SMART_RTL:
60
// Try SmartRTL, if that fails, RTL, if that fails Land
61
if (!set_mode(Mode::Number::SMART_RTL, ModeReason::FENCE_BREACHED)) {
62
if (!set_mode(Mode::Number::RTL, ModeReason::FENCE_BREACHED)) {
63
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
64
}
65
}
66
break;
67
case AC_FENCE_ACTION_BRAKE:
68
// Try Brake, if that fails Land
69
if (!set_mode(Mode::Number::BRAKE, ModeReason::FENCE_BREACHED)) {
70
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
71
}
72
break;
73
case AC_FENCE_ACTION_SMART_RTL_OR_LAND:
74
// Try SmartRTL, if that fails, Land
75
if (!set_mode(Mode::Number::SMART_RTL, ModeReason::FENCE_BREACHED)) {
76
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
77
}
78
break;
79
}
80
}
81
}
82
}
83
84
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
85
86
} else if (orig_breaches && fence.get_breaches() == 0) {
87
if (!copter.ap.land_complete) {
88
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence breach cleared");
89
}
90
// record clearing of breach
91
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);
92
}
93
}
94
95
#endif
96
97