Skip to content

Commit 6d4d3b6

Browse files
authored
Merge branch 'master' into pr-add-vs-code-launch-auto-generation
2 parents 4e98d9c + 6e26353 commit 6d4d3b6

File tree

5 files changed

+134
-35
lines changed

5 files changed

+134
-35
lines changed

Tools/autotest/arducopter.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1719,8 +1719,6 @@ def MinAltFence(self):
17191719
# Also check that the vehicle will not try and ascend too fast when trying to backup from a min alt fence due to avoidance
17201720
def MinAltFenceAvoid(self):
17211721
'''Test Min Alt Fence Avoidance'''
1722-
self.takeoff(30, mode="LOITER")
1723-
"""Hold loiter position."""
17241722

17251723
# enable fence, only min altitude
17261724
# No action, rely on avoidance to prevent the breach
@@ -1730,6 +1728,10 @@ def MinAltFenceAvoid(self):
17301728
"FENCE_ALT_MIN": 20,
17311729
"FENCE_ACTION": 0,
17321730
})
1731+
self.reboot_sitl()
1732+
1733+
self.takeoff(30, mode="LOITER")
1734+
"""Hold loiter position."""
17331735

17341736
# Try and fly past the fence
17351737
self.set_rc(3, 1120)

Tools/autotest/arduplane.py

Lines changed: 58 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -3661,7 +3661,7 @@ def FenceMinAltAutoEnableAbort(self):
36613661
def FenceAutoEnableDisableSwitch(self):
36623662
'''Tests autoenablement of regular fences and manual disablement'''
36633663
self.set_parameters({
3664-
"FENCE_TYPE": 11, # Set fence type to min alt
3664+
"FENCE_TYPE": 9, # Set fence type to min alt, max alt
36653665
"FENCE_ACTION": 1, # Set action to RTL
36663666
"FENCE_ALT_MIN": 50,
36673667
"FENCE_ALT_MAX": 100,
@@ -3672,44 +3672,88 @@ def FenceAutoEnableDisableSwitch(self):
36723672
"FENCE_RET_ALT" : 0,
36733673
"FENCE_RET_RALLY" : 0,
36743674
"FENCE_TOTAL" : 0,
3675+
"RTL_ALTITUDE" : 75,
36753676
"TKOFF_ALT" : 75,
36763677
"RC7_OPTION" : 11, # AC_Fence uses Aux switch functionality
36773678
})
3679+
self.reboot_sitl()
3680+
self.context_collect("STATUSTEXT")
3681+
36783682
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
36793683
# Grab Home Position
36803684
self.mav.recv_match(type='HOME_POSITION', blocking=True)
3681-
self.set_rc_from_map({7: 1000}) # Turn fence off with aux function
3685+
self.set_rc(7, 1000) # Turn fence off with aux function, does not impact later auto-enable
36823686

36833687
self.wait_ready_to_arm()
3688+
3689+
self.progress("Check fence disabled at boot")
3690+
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
3691+
if (m.onboard_control_sensors_enabled & fence_bit):
3692+
raise NotAchievedException("Fence is enabled at boot")
3693+
36843694
cruise_alt = 75
36853695
self.takeoff(cruise_alt, mode='TAKEOFF')
36863696

3687-
self.progress("Fly above ceiling and check there is no breach")
3697+
self.progress("Fly above ceiling and check there is a breach")
3698+
self.change_mode('FBWA')
36883699
self.set_rc(3, 2000)
3689-
self.change_altitude(cruise_alt + 80, relative=True)
3700+
self.set_rc(2, 1000)
3701+
3702+
self.wait_statustext("Max Alt fence breached", timeout=10, check_context=True)
3703+
self.wait_mode('RTL')
3704+
36903705
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
3691-
self.progress("Got (%s)" % str(m))
3692-
if (not (m.onboard_control_sensors_health & fence_bit)):
3693-
raise NotAchievedException("Fence Ceiling breached")
3706+
if (m.onboard_control_sensors_health & fence_bit):
3707+
raise NotAchievedException("Fence ceiling not breached")
3708+
3709+
self.set_rc(3, 1500)
3710+
self.set_rc(2, 1500)
3711+
3712+
self.progress("Wait for RTL alt reached")
3713+
self.wait_altitude(cruise_alt-5, cruise_alt+5, relative=True, timeout=30)
36943714

36953715
self.progress("Return to cruise alt")
36963716
self.set_rc(3, 1500)
36973717
self.change_altitude(cruise_alt, relative=True)
36983718

3699-
self.progress("Fly below floor and check for no breach")
3700-
self.change_altitude(25, relative=True)
3719+
self.progress("Check fence breach cleared")
37013720
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
3702-
self.progress("Got (%s)" % str(m))
37033721
if (not (m.onboard_control_sensors_health & fence_bit)):
3704-
raise NotAchievedException("Fence Ceiling breached")
3722+
raise NotAchievedException("Fence breach not cleared")
3723+
3724+
self.progress("Fly below floor and check for breach")
3725+
self.set_rc(2, 2000)
3726+
self.wait_statustext("Min Alt fence breached", timeout=10, check_context=True)
3727+
self.wait_mode("RTL")
3728+
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
3729+
if (m.onboard_control_sensors_health & fence_bit):
3730+
raise NotAchievedException("Fence floor not breached")
3731+
3732+
self.change_mode("FBWA")
37053733

3706-
self.progress("Fly above floor and check fence is not re-enabled")
3734+
self.progress("Fly above floor and check fence is enabled")
37073735
self.set_rc(3, 2000)
37083736
self.change_altitude(75, relative=True)
37093737
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
3710-
self.progress("Got (%s)" % str(m))
3738+
if (not (m.onboard_control_sensors_enabled & fence_bit)):
3739+
raise NotAchievedException("Fence Floor not enabled")
3740+
3741+
self.progress("Toggle fence enable/disable")
3742+
self.set_rc(7, 2000)
3743+
self.delay_sim_time(2)
3744+
self.set_rc(7, 1000)
3745+
self.delay_sim_time(2)
3746+
3747+
self.progress("Check fence is disabled")
3748+
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
37113749
if (m.onboard_control_sensors_enabled & fence_bit):
3712-
raise NotAchievedException("Fence Ceiling re-enabled")
3750+
raise NotAchievedException("Fence disable with switch failed")
3751+
3752+
self.progress("Fly below floor and check for no breach")
3753+
self.change_altitude(40, relative=True)
3754+
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
3755+
if (not (m.onboard_control_sensors_health & fence_bit)):
3756+
raise NotAchievedException("Fence floor breached")
37133757

37143758
self.progress("Return to cruise alt")
37153759
self.set_rc(3, 1500)

libraries/AC_Fence/AC_Fence.cpp

Lines changed: 64 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -219,7 +219,6 @@ void AC_Fence::update()
219219
// if someone changes the parameter we want to enable or disable everything
220220
if (_enabled != _last_enabled || _auto_enabled != _last_auto_enabled) {
221221
// reset the auto mask since we just reconfigured all of fencing
222-
_auto_enable_mask = AC_FENCE_ALL_FENCES;
223222
_last_enabled = _enabled;
224223
_last_auto_enabled = _auto_enabled;
225224
if (_enabled) {
@@ -238,9 +237,9 @@ void AC_Fence::update()
238237
}
239238

240239
// enable or disable configured fences present in fence_types
241-
// also updates the bitmask of auto enabled fences if update_auto_mask is true
240+
// also updates the _min_alt_state enum if update_auto_enable is true
242241
// returns a bitmask of fences that were changed
243-
uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_mask)
242+
uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable)
244243
{
245244
uint8_t fences = _configured_fences.get() & fence_types;
246245
uint8_t enabled_fences = _enabled_fences;
@@ -250,16 +249,17 @@ uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_mask)
250249
enabled_fences &= ~fences;
251250
}
252251

253-
// fences that were manually changed are no longer eligible for auto-enablement or disablement
254-
if (update_auto_mask) {
255-
_auto_enable_mask &= ~fences;
252+
if (update_auto_enable && (fences & AC_FENCE_TYPE_ALT_MIN) != 0) {
253+
// remember that min-alt fence was manually enabled/disabled
254+
_min_alt_state = value ? MinAltState::MANUALLY_ENABLED : MinAltState::MANUALLY_DISABLED;
256255
}
257256

258257
uint8_t fences_to_change = _enabled_fences ^ enabled_fences;
259258

260259
if (!fences_to_change) {
261260
return 0;
262261
}
262+
263263
#if HAL_LOGGING_ENABLED
264264
AP::logger().Write_Event(value ? LogEvent::FENCE_ENABLE : LogEvent::FENCE_DISABLE);
265265
if (fences_to_change & AC_FENCE_TYPE_ALT_MAX) {
@@ -305,7 +305,11 @@ void AC_Fence::auto_enable_fence_on_arming(void)
305305
return;
306306
}
307307

308-
const uint8_t fences = enable(true, _auto_enable_mask & ~AC_FENCE_TYPE_ALT_MIN, false);
308+
// reset min alt state, after an auto-enable the min alt fence can be auto-enabled on
309+
// reaching altitude
310+
_min_alt_state = MinAltState::DEFAULT;
311+
312+
const uint8_t fences = enable(true, AC_FENCE_ARMING_FENCES, false);
309313
print_fence_message("auto-enabled", fences);
310314
}
311315

@@ -318,7 +322,7 @@ void AC_Fence::auto_disable_fence_on_disarming(void)
318322
return;
319323
}
320324

321-
const uint8_t fences = enable(false, _auto_enable_mask, false);
325+
const uint8_t fences = enable(false, AC_FENCE_ALL_FENCES, false);
322326
print_fence_message("auto-disabled", fences);
323327
}
324328

@@ -332,7 +336,10 @@ void AC_Fence::auto_enable_fence_after_takeoff(void)
332336
return;
333337
}
334338

335-
const uint8_t fences = enable(true, _auto_enable_mask, false);
339+
// reset min-alt state
340+
_min_alt_state = MinAltState::DEFAULT;
341+
342+
const uint8_t fences = enable(true, AC_FENCE_ALL_FENCES, false);
336343
print_fence_message("auto-enabled", fences);
337344
}
338345

@@ -342,14 +349,18 @@ uint8_t AC_Fence::get_auto_disable_fences(void) const
342349
uint8_t auto_disable = 0;
343350
switch (auto_enabled()) {
344351
case AC_Fence::AutoEnable::ENABLE_ON_AUTO_TAKEOFF:
345-
auto_disable = _auto_enable_mask;
352+
auto_disable = AC_FENCE_ALL_FENCES;
346353
break;
347354
case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:
348355
case AC_Fence::AutoEnable::ONLY_WHEN_ARMED:
349356
default: // when auto disable is not set we still need to disable the altmin fence on landing
350-
auto_disable = _auto_enable_mask & AC_FENCE_TYPE_ALT_MIN;
357+
auto_disable = AC_FENCE_TYPE_ALT_MIN;
351358
break;
352359
}
360+
if (_min_alt_state == MinAltState::MANUALLY_ENABLED) {
361+
// don't auto-disable min alt fence if manually enabled
362+
auto_disable &= ~AC_FENCE_TYPE_ALT_MIN;
363+
}
353364
return auto_disable;
354365
}
355366

@@ -469,8 +480,20 @@ bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) c
469480
return false;
470481
}
471482

483+
auto breached_fences = _breached_fences;
484+
if (auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
485+
Location loc;
486+
if (!AP::ahrs().get_location(loc)) {
487+
hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position");
488+
return false;
489+
}
490+
if (_poly_loader.breached(loc)) {
491+
breached_fences |= AC_FENCE_TYPE_POLYGON;
492+
}
493+
}
494+
472495
// check no limits are currently breached
473-
if (_breached_fences) {
496+
if (breached_fences) {
474497
char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
475498
ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
476499
AC_Fence::get_fence_names(_breached_fences, e);
@@ -511,7 +534,7 @@ bool AC_Fence::check_fence_alt_max()
511534

512535
float alt;
513536
AP::ahrs().get_relative_position_D_home(alt);
514-
_curr_alt = -alt; // translate Down to Up
537+
const float _curr_alt = -alt; // translate Down to Up
515538

516539
// check if we are over the altitude fence
517540
if (_curr_alt >= _alt_max) {
@@ -560,7 +583,7 @@ bool AC_Fence::check_fence_alt_min()
560583

561584
float alt;
562585
AP::ahrs().get_relative_position_D_home(alt);
563-
_curr_alt = -alt; // translate Down to Up
586+
const float _curr_alt = -alt; // translate Down to Up
564587

565588
// check if we are under the altitude fence
566589
if (_curr_alt <= _alt_min) {
@@ -603,7 +626,7 @@ bool AC_Fence::auto_enable_fence_floor()
603626
// altitude fence check
604627
if (!(_configured_fences & AC_FENCE_TYPE_ALT_MIN) // not configured
605628
|| (get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) // already enabled
606-
|| !(_auto_enable_mask & AC_FENCE_TYPE_ALT_MIN) // has been manually disabled
629+
|| _min_alt_state == MinAltState::MANUALLY_DISABLED // user has manually disabled the fence
607630
|| (!_enabled && (auto_enabled() == AC_Fence::AutoEnable::ALWAYS_DISABLED
608631
|| auto_enabled() == AutoEnable::ENABLE_ON_AUTO_TAKEOFF))) {
609632
// not enabled
@@ -612,7 +635,7 @@ bool AC_Fence::auto_enable_fence_floor()
612635

613636
float alt;
614637
AP::ahrs().get_relative_position_D_home(alt);
615-
_curr_alt = -alt; // translate Down to Up
638+
const float _curr_alt = -alt; // translate Down to Up
616639

617640
// check if we are over the altitude fence
618641
if (!floor_enabled() && _curr_alt >= _alt_min + _margin) {
@@ -709,11 +732,36 @@ uint8_t AC_Fence::check(bool disable_auto_fences)
709732
// clear any breach from disabled fences
710733
clear_breach(fences_to_disable);
711734

735+
if (_min_alt_state == MinAltState::MANUALLY_ENABLED) {
736+
// if user has manually enabled the min-alt fence then don't auto-disable
737+
fences_to_disable &= ~AC_FENCE_TYPE_ALT_MIN;
738+
}
739+
712740
// report on any fences that were auto-disabled
713741
if (fences_to_disable) {
714742
print_fence_message("auto-disabled", fences_to_disable);
715743
}
716744

745+
#if 0
746+
/*
747+
this debug log message is very useful both when developing tests
748+
and doing manual SITL fence testing
749+
*/
750+
{
751+
float alt;
752+
AP::ahrs().get_relative_position_D_home(alt);
753+
754+
AP::logger().WriteStreaming("FENC", "TimeUS,EN,AE,CF,EF,DF,Alt", "QIIIIIf",
755+
AP_HAL::micros64(),
756+
enabled(),
757+
_auto_enabled,
758+
_configured_fences,
759+
get_enabled_fences(),
760+
disabled_fences,
761+
alt*-1);
762+
}
763+
#endif
764+
717765
// return immediately if disabled
718766
if ((!enabled() && !_auto_enabled && !(_configured_fences & AC_FENCE_TYPE_ALT_MIN)) || !_configured_fences) {
719767
return 0;

libraries/AC_Fence/AC_Fence.h

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -249,10 +249,7 @@ class AC_Fence
249249
float _circle_breach_distance; // distance beyond the circular fence
250250

251251
// other internal variables
252-
uint8_t _auto_enable_mask = AC_FENCE_ALL_FENCES; // fences that can be auto-enabled or auto-disabled
253252
float _home_distance; // distance from home in meters (provided by main code)
254-
float _curr_alt;
255-
256253

257254
// breach information
258255
uint8_t _breached_fences; // bitmask holding the fence type that was breached (i.e. AC_FENCE_TYPE_ALT_MIN, AC_FENCE_TYPE_CIRCLE)
@@ -262,6 +259,13 @@ class AC_Fence
262259

263260
uint32_t _manual_recovery_start_ms; // system time in milliseconds that pilot re-took manual control
264261

262+
enum class MinAltState
263+
{
264+
DEFAULT = 0,
265+
MANUALLY_ENABLED,
266+
MANUALLY_DISABLED
267+
} _min_alt_state;
268+
265269

266270
AC_PolyFence_loader _poly_loader{_total, _options}; // polygon fence
267271
};

libraries/RC_Channel/RC_Channel.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -242,6 +242,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
242242
// @Values{Copter}: 178:FlightMode Pause/Resume
243243
// @Values{Plane}: 179:ICEngine start / stop
244244
// @Values{Copter, Plane}: 180:Test autotuned gains after tune is complete
245+
// @Values{Plane}: 181: QuickTune
245246
// @Values{Rover}: 201:Roll
246247
// @Values{Rover}: 202:Pitch
247248
// @Values{Rover}: 207:MainSail

0 commit comments

Comments
 (0)