Skip to content

Commit 2218afd

Browse files
committed
Allow arming with unhealthy visodom in non-gps modes
1 parent a81c79a commit 2218afd

File tree

4 files changed

+33
-2
lines changed

4 files changed

+33
-2
lines changed

ArduCopter/AP_Arming_Copter.cpp

+25
Original file line numberDiff line numberDiff line change
@@ -399,6 +399,31 @@ 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+
// check if fence requires GPS/position
407+
bool fence_requires_pos = false;
408+
#if AP_FENCE_ENABLED
409+
// if circular or polygon fence is enabled we need GPS/position
410+
fence_requires_pos = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
411+
#endif
412+
413+
// check if flight mode requires GPS/position
414+
bool mode_requires_pos = copter.flightmode->requires_GPS() || fence_requires_pos || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);
415+
416+
// return true if position is not required
417+
if (!mode_requires_pos) {
418+
return true;
419+
} else {
420+
// call parent visodom checks
421+
return AP_Arming::visodom_checks(display_failure);
422+
}
423+
424+
}
425+
#endif
426+
402427
// check ekf attitude is acceptable
403428
bool AP_Arming_Copter::pre_arm_ekf_attitude_check()
404429
{

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
@@ -1930,7 +1930,7 @@ bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channe
19301930

19311931
#if HAL_VISUALODOM_ENABLED
19321932
// check visual odometry is working
1933-
bool AP_Arming::visodom_checks(bool display_failure) const
1933+
bool AP_Arming::visodom_checks(bool display_failure)
19341934
{
19351935
if (!check_enabled(ARMING_CHECK_VISION)) {
19361936
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:
@@ -257,7 +258,9 @@ class AP_Arming {
257258
bool servo_checks(bool report) const;
258259
bool rc_checks_copter_sub(bool display_failure, const class RC_Channel *channels[4]) const;
259260

260-
bool visodom_checks(bool report) const;
261+
#if HAL_VISUALODOM_ENABLED
262+
virtual bool visodom_checks(bool report);
263+
#endif
261264
bool disarm_switch_checks(bool report) const;
262265

263266
// 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)