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/ArduPlane/fence.cpp
Views: 1798
1
#include "Plane.h"
2
3
// Code to integrate AC_Fence library with main ArduPlane code
4
5
#if AP_FENCE_ENABLED
6
7
// fence_check - ask fence library to check for breaches and initiate the response
8
void Plane::fence_check()
9
{
10
const uint8_t orig_breaches = fence.get_breaches();
11
const bool armed = arming.is_armed();
12
13
uint16_t mission_id = plane.mission.get_current_nav_cmd().id;
14
bool landing_or_landed = plane.flight_stage == AP_FixedWing::FlightStage::LAND
15
|| !armed
16
#if HAL_QUADPLANE_ENABLED
17
|| control_mode->mode_number() == Mode::Number::QLAND
18
|| quadplane.in_vtol_land_descent()
19
#endif
20
|| (plane.is_land_command(mission_id) && plane.mission.state() == AP_Mission::MISSION_RUNNING);
21
22
// check for new breaches; new_breaches is bitmask of fence types breached
23
const uint8_t new_breaches = fence.check(landing_or_landed);
24
25
/*
26
if we are either disarmed or we are currently not in breach and
27
we are not flying then clear the state associated with the
28
previous mode breach handling. This allows the fence state
29
machine to reset at the end of a fence breach action such as an
30
RTL and autoland
31
*/
32
if (plane.previous_mode_reason == ModeReason::FENCE_BREACHED) {
33
if (!armed || ((new_breaches == 0 && orig_breaches == 0) && !plane.is_flying())) {
34
plane.previous_mode_reason = ModeReason::UNKNOWN;
35
}
36
}
37
38
if (!fence.enabled()) {
39
// Switch back to the chosen control mode if still in
40
// GUIDED to the return point
41
switch(fence.get_action()) {
42
case AC_FENCE_ACTION_GUIDED:
43
case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:
44
case AC_FENCE_ACTION_RTL_AND_LAND:
45
if (plane.control_mode_reason == ModeReason::FENCE_BREACHED &&
46
control_mode->is_guided_mode()) {
47
set_mode(*previous_mode, ModeReason::FENCE_RETURN_PREVIOUS_MODE);
48
}
49
break;
50
default:
51
// No returning to a previous mode, unless our action allows it
52
break;
53
}
54
return;
55
}
56
57
// we still don't do anything when disarmed, but we do check for fence breaches.
58
// fence pre-arm check actually checks if any fence has been breached
59
// that's not ever going to be true if we don't call check on AP_Fence while disarmed
60
if (!armed) {
61
return;
62
}
63
64
// Never trigger a fence breach in the final stage of landing
65
if (landing.is_expecting_impact()) {
66
return;
67
}
68
69
if (in_fence_recovery()) {
70
// we have already triggered, don't trigger again until the
71
// user disables/re-enables using the fence channel switch
72
return;
73
}
74
75
if (new_breaches) {
76
fence.print_fence_message("breached", new_breaches);
77
78
// if the user wants some kind of response and motors are armed
79
const uint8_t fence_act = fence.get_action();
80
switch (fence_act) {
81
case AC_FENCE_ACTION_REPORT_ONLY:
82
break;
83
case AC_FENCE_ACTION_GUIDED:
84
case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:
85
case AC_FENCE_ACTION_RTL_AND_LAND:
86
if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
87
if (control_mode == &mode_auto &&
88
mission.get_in_landing_sequence_flag() &&
89
(g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START ||
90
g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START)) {
91
// already landing
92
return;
93
}
94
set_mode(mode_rtl, ModeReason::FENCE_BREACHED);
95
} else {
96
set_mode(mode_guided, ModeReason::FENCE_BREACHED);
97
}
98
99
Location loc;
100
if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
101
loc = calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm());
102
} else {
103
//return to fence return point, not a rally point
104
if (fence.get_return_altitude() > 0) {
105
// fly to the return point using _retalt
106
loc.alt = home.alt + 100.0f * fence.get_return_altitude();
107
} else if (fence.get_safe_alt_min() >= fence.get_safe_alt_max()) {
108
// invalid min/max, use RTL_altitude
109
loc.alt = home.alt + g.RTL_altitude*100;
110
} else {
111
// fly to the return point, with an altitude half way between
112
// min and max
113
loc.alt = home.alt + 100.0f * (fence.get_safe_alt_min() + fence.get_safe_alt_max()) / 2;
114
}
115
116
Vector2l return_point;
117
if(fence.polyfence().get_return_point(return_point)) {
118
loc.lat = return_point[0];
119
loc.lng = return_point[1];
120
} else {
121
// When no fence return point is found (ie. no inclusion fence uploaded, but exclusion is)
122
// we fail to obtain a valid fence return point. In this case, home is considered a safe
123
// return point.
124
loc.lat = home.lat;
125
loc.lng = home.lng;
126
}
127
}
128
129
if (fence.get_action() != AC_FENCE_ACTION_RTL_AND_LAND) {
130
setup_terrain_target_alt(loc);
131
set_guided_WP(loc);
132
}
133
134
if (fence.get_action() == AC_FENCE_ACTION_GUIDED_THROTTLE_PASS) {
135
guided_throttle_passthru = true;
136
}
137
break;
138
}
139
140
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
141
} else if (orig_breaches && fence.get_breaches() == 0) {
142
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence breach cleared");
143
// record clearing of breach
144
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);
145
}
146
}
147
148
bool Plane::fence_stickmixing(void) const
149
{
150
if (fence.enabled() &&
151
fence.get_breaches() &&
152
in_fence_recovery())
153
{
154
// don't mix in user input
155
return false;
156
}
157
// normal mixing rules
158
return true;
159
}
160
161
bool Plane::in_fence_recovery() const
162
{
163
const bool current_mode_breach = plane.control_mode_reason == ModeReason::FENCE_BREACHED;
164
const bool previous_mode_breach = plane.previous_mode_reason == ModeReason::FENCE_BREACHED;
165
const bool previous_mode_complete = (plane.control_mode_reason == ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL) ||
166
(plane.control_mode_reason == ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND) ||
167
(plane.control_mode_reason == ModeReason::QRTL_INSTEAD_OF_RTL) ||
168
(plane.control_mode_reason == ModeReason::QLAND_INSTEAD_OF_RTL);
169
170
return current_mode_breach || (previous_mode_breach && previous_mode_complete);
171
}
172
173
#endif
174
175