mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: Allowed to arm in Manual mode without GPS
This commit is contained in:
parent
b6bfc8947f
commit
e18b3cac6b
@ -42,6 +42,11 @@ bool AP_Arming_Rover::pre_arm_rc_checks(const bool display_failure)
|
|||||||
// performs pre_arm gps related checks and returns true if passed
|
// performs pre_arm gps related checks and returns true if passed
|
||||||
bool AP_Arming_Rover::gps_checks(bool display_failure)
|
bool AP_Arming_Rover::gps_checks(bool display_failure)
|
||||||
{
|
{
|
||||||
|
if (!rover.control_mode->requires_position() && !rover.control_mode->requires_velocity()) {
|
||||||
|
// we don't care!
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
const AP_AHRS &ahrs = AP::ahrs();
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
|
||||||
// always check if inertial nav has started and is ready
|
// always check if inertial nav has started and is ready
|
||||||
@ -54,11 +59,6 @@ bool AP_Arming_Rover::gps_checks(bool display_failure)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!rover.control_mode->requires_position() && !rover.control_mode->requires_velocity()) {
|
|
||||||
// we don't care!
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
// check for ekf failsafe
|
// check for ekf failsafe
|
||||||
if (rover.failsafe.ekf) {
|
if (rover.failsafe.ekf) {
|
||||||
check_failed(ARMING_CHECK_NONE, display_failure, "EKF failsafe");
|
check_failed(ARMING_CHECK_NONE, display_failure, "EKF failsafe");
|
||||||
|
Loading…
Reference in New Issue
Block a user