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

ArduCopter: add Copter flight option for requiring position to arm #27367

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
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -444,7 +444,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif

if (mode_requires_gps) {
if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) {
if (!copter.position_ok()) {
// vehicle level position estimate checks
check_failed(display_failure, "Need Position Estimate");
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -626,6 +626,7 @@ class Copter : public AP_Vehicle {
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8
};
// returns true if option is enabled for this vehicle
bool option_is_enabled(FlightOption option) const {
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1000,7 +1000,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: FLIGHT_OPTIONS
// @DisplayName: Flight mode options
// @Description: Flight mode specific options
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss, 3:Require position for arming
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0),

Expand Down
34 changes: 34 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -11535,6 +11535,39 @@ def GripperReleaseOnThrustLoss(self):
self.do_RTL()
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_POSITION_FOR_ARMING(self):
'''check FlightOption::REQUIRE_POSITION_FOR_ARMING works'''
self.context_push()
self.set_parameters({
"SIM_GPS_NUMSATS": 3, # EKF does not like < 6
})
self.reboot_sitl()
self.change_mode('STABILIZE')
self.wait_prearm_sys_status_healthy()
self.assert_home_position_not_set()
self.arm_vehicle()
self.disarm_vehicle()
self.change_mode('LOITER')
self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False)

self.change_mode('STABILIZE')
self.set_parameters({
"FLIGHT_OPTIONS": 8,
})
self.assert_prearm_failure("Need Position Estimate", other_prearm_failures_fatal=False)
self.context_pop()
self.reboot_sitl()

def tests2b(self): # this block currently around 9.5mins here
'''return list of all tests'''
ret = ([
Expand Down Expand Up @@ -11626,6 +11659,7 @@ def tests2b(self): # this block currently around 9.5mins here
self.GuidedWeatherVane,
self.Clamp,
self.GripperReleaseOnThrustLoss,
self.REQUIRE_POSITION_FOR_ARMING,
])
return ret

Expand Down
Loading