Skip to content

Commit 8307a57

Browse files
committed
Allow arming with unhealthy visodom in non-gps modes
1 parent 17299bd commit 8307a57

File tree

4 files changed

+31
-2
lines changed

4 files changed

+31
-2
lines changed

ArduCopter/AP_Arming_Copter.cpp

+23
Original file line numberDiff line numberDiff line change
@@ -399,6 +399,29 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
399399
return true;
400400
}
401401

402+
#if HAL_VISUALODOM_ENABLED
403+
// performs pre_arm visodom related checks and returns true if passed
404+
bool AP_Arming_Copter::visodom_checks(bool display_failure)
405+
{
406+
bool location_required = require_location == RequireLocation::YES;
407+
#if AP_FENCE_ENABLED
408+
// check if fence requires GPS/position
409+
location_required |= (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
410+
#endif
411+
412+
// check if flight mode requires GPS/position
413+
location_required |= copter.flightmode->requires_GPS() || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);
414+
415+
// return true if position is not required
416+
if (!location_required) {
417+
return true;
418+
}
419+
// call parent visodom checks
420+
return AP_Arming::visodom_checks(display_failure);
421+
422+
}
423+
#endif
424+
402425
// check ekf attitude is acceptable
403426
bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
404427
{

ArduCopter/AP_Arming_Copter.h

+3
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,9 @@ class AP_Arming_Copter : public AP_Arming
4040
bool gps_checks(bool display_failure) override;
4141
bool barometer_checks(bool display_failure) override;
4242
bool board_voltage_checks(bool display_failure) override;
43+
#if HAL_VISUALODOM_ENABLED
44+
bool visodom_checks(bool display_failure) override;
45+
#endif
4346

4447
// NOTE! the following check functions *DO NOT* call into AP_Arming!
4548
bool parameter_checks(bool display_failure);

libraries/AP_Arming/AP_Arming.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1957,7 +1957,7 @@ bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channe
19571957

19581958
#if HAL_VISUALODOM_ENABLED
19591959
// check visual odometry is working
1960-
bool AP_Arming::visodom_checks(bool display_failure) const
1960+
bool AP_Arming::visodom_checks(bool display_failure)
19611961
{
19621962
if (!check_enabled(ARMING_CHECK_VISION)) {
19631963
return true;

libraries/AP_Arming/AP_Arming.h

+4-1
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
#include "AP_Arming_config.h"
1010
#include "AP_InertialSensor/AP_InertialSensor_config.h"
1111
#include "AP_Proximity/AP_Proximity_config.h"
12+
#include "AP_VisualOdom/AP_VisualOdom_config.h"
1213

1314
class AP_Arming {
1415
public:
@@ -261,7 +262,9 @@ class AP_Arming {
261262
bool servo_checks(bool report) const;
262263
bool rc_checks_copter_sub(bool display_failure, const class RC_Channel *channels[4]) const;
263264

264-
bool visodom_checks(bool report) const;
265+
#if HAL_VISUALODOM_ENABLED
266+
virtual bool visodom_checks(bool report);
267+
#endif
265268
bool disarm_switch_checks(bool report) const;
266269

267270
// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced

0 commit comments

Comments
 (0)