Rover: add option to require position for Rover before arming

This commit is contained in:
Peter Barker 2025-02-03 14:35:48 +11:00 committed by Peter Barker
parent 0fb5a2105c
commit 4959cee694
2 changed files with 4 additions and 2 deletions

View File

@ -34,7 +34,9 @@ bool AP_Arming_Rover::rc_calibration_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_position() && !rover.control_mode->requires_velocity()) {
if (!require_location &&
!rover.control_mode->requires_position() &&
!rover.control_mode->requires_velocity()) {
// we don't care!
return true;
}

View File

@ -191,7 +191,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
// @DisplayName: Require vehicle location
// @Description: Require that the vehicle have an absolute position before it arms. This can help ensure that the vehicle can Return To Launch.
// @User: Advanced
// @Values{Copter}: 0:Do not require location,1:Require Location
// @Values{Copter,Rover}: 0:Do not require location,1:Require Location
AP_GROUPINFO("NEED_LOC", 12, AP_Arming, require_location, float(AP_ARMING_NEED_LOC_DEFAULT)),
#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED