Copter: check fence when disarmed
this allows catching fence breaches as part of arming checks
This commit is contained in:
parent
fbe0e5dfb3
commit
290cdcf6fb
@ -13,17 +13,17 @@ void Copter::fence_check()
|
|||||||
uint8_t new_breaches; // the type of fence that has been breached
|
uint8_t new_breaches; // the type of fence that has been breached
|
||||||
uint8_t orig_breaches = fence.get_breaches();
|
uint8_t orig_breaches = fence.get_breaches();
|
||||||
|
|
||||||
// return immediately if motors are not armed
|
|
||||||
if(!motors.armed()) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// give fence library our current distance from home in meters
|
// give fence library our current distance from home in meters
|
||||||
fence.set_home_distance(home_distance*0.01f);
|
fence.set_home_distance(home_distance*0.01f);
|
||||||
|
|
||||||
// check for a breach
|
// check for a breach
|
||||||
new_breaches = fence.check_fence(current_loc.alt/100.0f);
|
new_breaches = fence.check_fence(current_loc.alt/100.0f);
|
||||||
|
|
||||||
|
// return immediately if motors are not armed
|
||||||
|
if(!motors.armed()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// if there is a new breach take action
|
// if there is a new breach take action
|
||||||
if( new_breaches != AC_FENCE_TYPE_NONE ) {
|
if( new_breaches != AC_FENCE_TYPE_NONE ) {
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user