diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 605afbeaa9598d..5593452515904a 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -100,7 +100,7 @@ class Parameters { k_param_sonar_old, // unused k_param_log_bitmask, k_param_BoardConfig, - k_param_mode_autoland, // was rssi_range + k_param_rssi_range, // unused, replaced by rssi_ library parameters k_param_flapin_channel_old, // unused, moved to RC_OPTION k_param_flaperon_output, // unused k_param_gps, @@ -362,6 +362,7 @@ class Parameters { k_param_takeoff_throttle_idle, k_param_pullup = 270, + k_param_mode_autoland, }; AP_Int16 format_version; diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index 4577aa3fc1ec18..19b9d414a9bd4b 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -869,12 +869,6 @@ class ModeAutoLand: public Mode bool _enter() override; AP_Mission::Mission_Command cmd {}; bool land_started; - - -private: - - - }; #if HAL_SOARING_ENABLED diff --git a/ArduPlane/mode_autoland.cpp b/ArduPlane/mode_autoland.cpp index 1d4f88dc50e51c..5b73e09c83c545 100644 --- a/ArduPlane/mode_autoland.cpp +++ b/ArduPlane/mode_autoland.cpp @@ -81,7 +81,6 @@ bool ModeAutoLand::_enter() cmd.content.location = plane.next_WP_loc; plane.start_command(cmd); land_started = false; - gcs().send_text(MAV_SEVERITY_WARNING, "AutoLanding"); return true; } diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index fa4a0949133ff0..f6bd63ec7a6274 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4200,6 +4200,17 @@ def FlyEachFrame(self): self.fly_mission(mission_file, strict=False, quadplane=quadplane, mission_timeout=400.0) self.wait_disarmed() + def AutoLandMode(self): + '''Test AUTOLAND mode''' + self.customise_SITL_commandline(["--home", "-35.362938,149.165085,585,173"]) + self.context_collect('STATUSTEXT') + self.takeoff(alt=80, mode='TAKEOFF') + self.wait_text("Takeoff initial direction", check_context=True) + self.change_mode(26) + self.wait_disarmed(120) + self.progress("Check the landed heading matches takeoff") + self.wait_heading(173, accuracy=5, timeout=1) + def RCDisableAirspeedUse(self): '''Test RC DisableAirspeedUse option''' self.set_parameter("RC9_OPTION", 106) @@ -5847,6 +5858,8 @@ def DO_PARACHUTE(self): def _MAV_CMD_DO_GO_AROUND(self, command): self.load_mission("mission.txt") + self.context_collect('STATUSTEXT') + self.takeoff(mode='TAKEOFF') self.set_parameter("RTL_AUTOLAND", 3) self.change_mode('AUTO') self.wait_ready_to_arm() @@ -6404,6 +6417,7 @@ def tests1b(self): self.MAV_CMD_DO_AUX_FUNCTION, self.SmartBattery, self.FlyEachFrame, + self.AutoLandMode, self.RCDisableAirspeedUse, self.AHRS_ORIENTATION, self.AHRSTrim,