Skip to content

Commit

Permalink
use Qplane option to allow autoland and fix auto-flaps
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Dec 21, 2024
1 parent f1fe400 commit f387876
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 6 deletions.
4 changes: 2 additions & 2 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -689,8 +689,8 @@ void Plane::update_flight_stage(void)
// This prevents TECS from being stuck in the wrong stage if you switch from
// AUTO to, say, FBWB during a landing, an aborted landing or takeoff.
set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
} else if (control_mode == &mode_autoland) {
set_flight_stage(AP_FixedWing::FlightStage::LAND);
// } else if (control_mode == &mode_autoland) {
// set_flight_stage(AP_FixedWing::FlightStage::LAND);
}
return;
}
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -861,6 +861,7 @@ class ModeTakeoff: public Mode

class ModeAutoLand: public Mode
{
friend class QuadPlane;
public:
ModeAutoLand();

Expand Down
9 changes: 5 additions & 4 deletions ArduPlane/mode_autoland.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,17 +43,17 @@ ModeAutoLand::ModeAutoLand() :
}

bool ModeAutoLand::_enter()
{
{
//must be flying to enter
if (!plane.is_flying()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Must already be flying!");
return false;
}

//takeoff direction must be set and must not be a quadplane, otherwise since flying switch to RTL so this can be used as FS action
#if HAL_QUADPLANE_ENABLED
if (quadplane.available()) {
gcs().send_text(MAV_SEVERITY_WARNING, "AutoLand is fixed wing only mode");
if HAL_QUADPLANE_ENABLED
if (quadplane.available() && !quadplane.option_is_set(QuadPlane::OPTION::ALLOW_FW_LAND)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Option not set to allow fixed wing autoland");
return false;
}
#endif
Expand Down Expand Up @@ -105,6 +105,7 @@ void ModeAutoLand::navigate()
plane.prev_WP_loc = plane.current_loc;
plane.next_WP_loc = home_loc;
plane.start_command(cmd);
plane.set_flight_stage(AP_FixedWing::FlightStage::LAND);
}
return;
//otherwise keep flying the current command
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -696,6 +696,7 @@ void Plane::set_servos_flaps(void)
better than speed based flaps as it leads to less
possibility of oscillation
*/

switch (flight_stage) {
case AP_FixedWing::FlightStage::TAKEOFF:
case AP_FixedWing::FlightStage::ABORT_LANDING:
Expand All @@ -710,8 +711,10 @@ void Plane::set_servos_flaps(void)
}
break;
case AP_FixedWing::FlightStage::LAND:

if (landing.get_flap_percent() != 0) {
auto_flap_percent = landing.get_flap_percent();
//GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"Gothere, %u",auto_flap_percent);
}
break;
default:
Expand Down

0 comments on commit f387876

Please sign in to comment.