Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rover: add require-position-for-arming option #29073

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
10 changes: 0 additions & 10 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -6083,7 +6083,7 @@
raise NotAchievedException("Did not detect a motor peak, found %fHz at %fdB" % (freq, peakdb))
else:
if reverse is not None:
raise NotAchievedException(

Check failure on line 6086 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

vehicle_test_suite.NotAchievedException: Detected motor peak at 131.603031Hz, throttle 36.000000%, 8.125146dB

Check failure on line 6086 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

vehicle_test_suite.NotAchievedException: Detected motor peak at 131.603031Hz, throttle 36.000000%, 8.125146dB

Check failure on line 6086 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

vehicle_test_suite.NotAchievedException: Detected motor peak at 132.557922Hz, throttle 36.000000%, 9.674370dB

Check failure on line 6086 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

vehicle_test_suite.NotAchievedException: Detected motor peak at 132.557922Hz, throttle 36.000000%, 9.674370dB

Check failure on line 6086 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

vehicle_test_suite.NotAchievedException: Detected motor peak at 134.465231Hz, throttle 36.000000%, 7.056362dB
"Detected motor peak at %fHz, throttle %f%%, %fdB" %
(freq, hover_throttle, peakdb))
else:
Expand Down Expand Up @@ -6650,7 +6650,7 @@
self.reboot_sitl()

if ex is not None:
raise ex

Check failure on line 6653 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

File "/__w/ardupilot/ardupilot/Tools/autotest/arducopter.py", line 6630, in test_gyro_fft_harmonic

Check failure on line 6653 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

File "/__w/ardupilot/ardupilot/Tools/autotest/arducopter.py", line 6630, in test_gyro_fft_harmonic

Check failure on line 6653 in Tools/autotest/arducopter.py

View workflow job for this annotation

GitHub Actions / autotest (sitltest-copter-tests2b)

File "/__w/ardupilot/ardupilot/Tools/autotest/arducopter.py", line 6630, in test_gyro_fft_harmonic

def GyroFFTHarmonic(self):
"""Use dynamic harmonic notch to control motor noise with harmonic matching of the first harmonic."""
Expand Down Expand Up @@ -12243,16 +12243,6 @@
self.context_pop()
self.reboot_sitl()

def assert_home_position_not_set(self):
try:
self.poll_home_position()
except NotAchievedException:
return

# if home.lng != 0: etc

raise NotAchievedException("Home is set when it shouldn't be")

def REQUIRE_LOCATION_FOR_ARMING(self):
'''check AP_Arming::Option::REQUIRE_LOCATION_FOR_ARMING works'''
self.context_push()
Expand Down
26 changes: 26 additions & 0 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -6947,6 +6947,31 @@ def SDPolyFence(self):

self.delay_sim_time(1000)

def REQUIRE_LOCATION_FOR_ARMING(self):
'''check DriveOption::REQUIRE_POSITION_FOR_ARMING works'''
self.context_push()
self.set_parameters({
"SIM_GPS1_NUMSATS": 3, # EKF does not like < 6
"AHRS_GPS_USE": 0, # stop DCM supplying home
})
self.reboot_sitl()
self.change_mode('MANUAL')
self.wait_prearm_sys_status_healthy()
self.assert_home_position_not_set()
self.arm_vehicle()
self.disarm_vehicle()

self.change_mode('GUIDED')
self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False)

self.change_mode('MANUAL')
self.set_parameters({
"ARMING_NEED_LOC": 1,
})
self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False)
self.context_pop()
self.reboot_sitl()

def tests(self):
'''return list of all tests'''
ret = super(AutoTestRover, self).tests()
Expand Down Expand Up @@ -7045,6 +7070,7 @@ def tests(self):
self.ClearMission,
self.JammingSimulation,
self.BatteryInvalid,
self.REQUIRE_LOCATION_FOR_ARMING,
])
return ret

Expand Down
14 changes: 12 additions & 2 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -3625,6 +3625,16 @@ def assert_bytes_equal(self, bytes1, bytes2, maxlen=None):
if bytes1[i] != bytes2[i]:
raise NotAchievedException("differ at offset %u" % i)

def assert_home_position_not_set(self):
try:
self.poll_home_position()
except NotAchievedException:
return

# if home.lng != 0: etc

raise NotAchievedException("Home is set when it shouldn't be")

def HIGH_LATENCY2(self):
'''test sending of HIGH_LATENCY2'''

Expand Down Expand Up @@ -8360,8 +8370,8 @@ def assert_prearm_failure(self,
now = self.get_sim_time_cached()
if now - tstart > timeout:
raise NotAchievedException(
"Did not see failure-to-arm messages (statustext=%s command_ack=%s" %
(seen_statustext, seen_command_ack))
f"Did not see failure-to-arm messages ({seen_statustext=} {expected_statustext=} {seen_command_ack=})"
)
if now - arm_last_send > 1:
arm_last_send = now
self.send_mavlink_run_prearms_command()
Expand Down
6 changes: 3 additions & 3 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 Expand Up @@ -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

Expand Down
Loading