Skip to content

Commit

Permalink
add option to require position for Rover before arming
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Feb 3, 2025
1 parent 3ce8479 commit d534e0b
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 6 deletions.
4 changes: 3 additions & 1 deletion Rover/AP_Arming_Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
6 changes: 3 additions & 3 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -6947,7 +6947,7 @@ def SDPolyFence(self):

self.delay_sim_time(1000)

def REQUIRE_POSITION_FOR_ARMING(self):
def REQUIRE_LOCATION_FOR_ARMING(self):
'''check DriveOption::REQUIRE_POSITION_FOR_ARMING works'''
self.context_push()
self.set_parameters({
Expand All @@ -6966,7 +6966,7 @@ def REQUIRE_POSITION_FOR_ARMING(self):

self.change_mode('MANUAL')
self.set_parameters({
"DRIVE_OPTIONS": 1,
"ARMING_NEED_LOC": 1,
})
self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False)
self.context_pop()
Expand Down Expand Up @@ -7070,7 +7070,7 @@ def tests(self):
self.ClearMission,
self.JammingSimulation,
self.BatteryInvalid,
self.REQUIRE_POSITION_FOR_ARMING,
self.REQUIRE_LOCATION_FOR_ARMING,
])
return ret

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@
// whether the parameter should be shown:
#ifndef AP_ARMING_NEED_LOC_PARAMETER_ENABLED
// determine whether ARMING_NEED_POS is shown:
#if APM_BUILD_COPTER_OR_HELI
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover)
#define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 1
#else
#define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 0
Expand All @@ -98,7 +98,7 @@

// if ARMING_NEED_POS is shown, determine what its default should be:
#if AP_ARMING_NEED_LOC_PARAMETER_ENABLED
#if APM_BUILD_COPTER_OR_HELI
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover)
#define AP_ARMING_NEED_LOC_DEFAULT 0
#else
#error "Unable to find value for AP_ARMING_NEED_LOC_DEFAULT"
Expand Down

0 comments on commit d534e0b

Please sign in to comment.