mirror of https://github.com/ArduPilot/ardupilot
Rover: arming checks for GPS use requires_position and velocity
This commit is contained in:
parent
a64aee1c17
commit
cf24e6115c
|
@ -61,7 +61,7 @@ bool AP_Arming_Rover::pre_arm_rc_checks(const bool display_failure)
|
|||
// performs pre_arm gps related checks and returns true if passed
|
||||
bool AP_Arming_Rover::gps_checks(bool display_failure)
|
||||
{
|
||||
if (!rover.control_mode->requires_gps()) {
|
||||
if (!rover.control_mode->requires_position() && !rover.control_mode->requires_velocity()) {
|
||||
// we don't care!
|
||||
return true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue