@@ -219,7 +219,6 @@ void AC_Fence::update()
219
219
// if someone changes the parameter we want to enable or disable everything
220
220
if (_enabled != _last_enabled || _auto_enabled != _last_auto_enabled) {
221
221
// reset the auto mask since we just reconfigured all of fencing
222
- _auto_enable_mask = AC_FENCE_ALL_FENCES;
223
222
_last_enabled = _enabled;
224
223
_last_auto_enabled = _auto_enabled;
225
224
if (_enabled) {
@@ -238,9 +237,9 @@ void AC_Fence::update()
238
237
}
239
238
240
239
// 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
242
241
// 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 )
244
243
{
245
244
uint8_t fences = _configured_fences.get () & fence_types;
246
245
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)
250
249
enabled_fences &= ~fences;
251
250
}
252
251
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 ;
256
255
}
257
256
258
257
uint8_t fences_to_change = _enabled_fences ^ enabled_fences;
259
258
260
259
if (!fences_to_change) {
261
260
return 0 ;
262
261
}
262
+
263
263
#if HAL_LOGGING_ENABLED
264
264
AP::logger ().Write_Event (value ? LogEvent::FENCE_ENABLE : LogEvent::FENCE_DISABLE);
265
265
if (fences_to_change & AC_FENCE_TYPE_ALT_MAX) {
@@ -305,7 +305,11 @@ void AC_Fence::auto_enable_fence_on_arming(void)
305
305
return ;
306
306
}
307
307
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 );
309
313
print_fence_message (" auto-enabled" , fences);
310
314
}
311
315
@@ -318,7 +322,7 @@ void AC_Fence::auto_disable_fence_on_disarming(void)
318
322
return ;
319
323
}
320
324
321
- const uint8_t fences = enable (false , _auto_enable_mask , false );
325
+ const uint8_t fences = enable (false , AC_FENCE_ALL_FENCES , false );
322
326
print_fence_message (" auto-disabled" , fences);
323
327
}
324
328
@@ -332,7 +336,10 @@ void AC_Fence::auto_enable_fence_after_takeoff(void)
332
336
return ;
333
337
}
334
338
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 );
336
343
print_fence_message (" auto-enabled" , fences);
337
344
}
338
345
@@ -342,14 +349,18 @@ uint8_t AC_Fence::get_auto_disable_fences(void) const
342
349
uint8_t auto_disable = 0 ;
343
350
switch (auto_enabled ()) {
344
351
case AC_Fence::AutoEnable::ENABLE_ON_AUTO_TAKEOFF:
345
- auto_disable = _auto_enable_mask ;
352
+ auto_disable = AC_FENCE_ALL_FENCES ;
346
353
break ;
347
354
case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:
348
355
case AC_Fence::AutoEnable::ONLY_WHEN_ARMED:
349
356
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;
351
358
break ;
352
359
}
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
+ }
353
364
return auto_disable;
354
365
}
355
366
@@ -469,8 +480,20 @@ bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) c
469
480
return false ;
470
481
}
471
482
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
+
472
495
// check no limits are currently breached
473
- if (_breached_fences ) {
496
+ if (breached_fences ) {
474
497
char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1 ];
475
498
ExpandingString e (msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1 );
476
499
AC_Fence::get_fence_names (_breached_fences, e);
@@ -511,7 +534,7 @@ bool AC_Fence::check_fence_alt_max()
511
534
512
535
float alt;
513
536
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
515
538
516
539
// check if we are over the altitude fence
517
540
if (_curr_alt >= _alt_max) {
@@ -560,7 +583,7 @@ bool AC_Fence::check_fence_alt_min()
560
583
561
584
float alt;
562
585
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
564
587
565
588
// check if we are under the altitude fence
566
589
if (_curr_alt <= _alt_min) {
@@ -603,7 +626,7 @@ bool AC_Fence::auto_enable_fence_floor()
603
626
// altitude fence check
604
627
if (!(_configured_fences & AC_FENCE_TYPE_ALT_MIN) // not configured
605
628
|| (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
607
630
|| (!_enabled && (auto_enabled () == AC_Fence::AutoEnable::ALWAYS_DISABLED
608
631
|| auto_enabled () == AutoEnable::ENABLE_ON_AUTO_TAKEOFF))) {
609
632
// not enabled
@@ -612,7 +635,7 @@ bool AC_Fence::auto_enable_fence_floor()
612
635
613
636
float alt;
614
637
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
616
639
617
640
// check if we are over the altitude fence
618
641
if (!floor_enabled () && _curr_alt >= _alt_min + _margin) {
@@ -709,11 +732,36 @@ uint8_t AC_Fence::check(bool disable_auto_fences)
709
732
// clear any breach from disabled fences
710
733
clear_breach (fences_to_disable);
711
734
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
+
712
740
// report on any fences that were auto-disabled
713
741
if (fences_to_disable) {
714
742
print_fence_message (" auto-disabled" , fences_to_disable);
715
743
}
716
744
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
+
717
765
// return immediately if disabled
718
766
if ((!enabled () && !_auto_enabled && !(_configured_fences & AC_FENCE_TYPE_ALT_MIN)) || !_configured_fences) {
719
767
return 0 ;
0 commit comments