Skip to content

Commit

Permalink
ArduPlane:add AUTOLAND build option
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Dec 22, 2024
1 parent ca0b2af commit dab9079
Show file tree
Hide file tree
Showing 13 changed files with 48 additions and 9 deletions.
2 changes: 2 additions & 0 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,9 @@ MAV_MODE GCS_MAVLINK_Plane::base_mode() const
case Mode::Number::GUIDED:
case Mode::Number::CIRCLE:
case Mode::Number::TAKEOFF:
#if MODE_AUTOLAND_ENABLED
case Mode::Number::AUTOLAND:
#endif
#if HAL_QUADPLANE_ENABLED
case Mode::Number::QRTL:
case Mode::Number::LOITER_ALT_QLAND:
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/GCS_Plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,9 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
case Mode::Number::GUIDED:
case Mode::Number::CIRCLE:
case Mode::Number::TAKEOFF:
#if MODE_AUTOLAND_ENABLED
case Mode::Number::AUTOLAND:
#endif
#if HAL_QUADPLANE_ENABLED
case Mode::Number::QRTL:
case Mode::Number::LOITER_ALT_QLAND:
Expand Down
4 changes: 3 additions & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1027,10 +1027,12 @@ const AP_Param::Info Plane::var_info[] = {
// @Group: TKOFF_
// @Path: mode_takeoff.cpp
GOBJECT(mode_takeoff, "TKOFF_", ModeTakeoff),


#if MODE_AUTOLAND_ENABLED
// @Group: AUTOLAND_
// @Path: mode_autoland.cpp
GOBJECT(mode_autoland, "AUTOLAND_", ModeAutoLand),
#endif

#if AP_PLANE_GLIDER_PULLUP_ENABLED
// @Group: PUP_
Expand Down
5 changes: 4 additions & 1 deletion ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -172,8 +172,9 @@ class Plane : public AP_Vehicle {
friend class ModeTakeoff;
friend class ModeThermal;
friend class ModeLoiterAltQLand;
#if MODE_AUTOLAND_ENABLED
friend class ModeAutoLand;

#endif
#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Plane;
#endif
Expand Down Expand Up @@ -457,8 +458,10 @@ class Plane : public AP_Vehicle {
uint32_t throttle_max_timer_ms;
uint32_t level_off_start_time_ms;
// Good candidate for keeping the initial time for TKOFF_THR_MAX_T.
#if MODE_AUTOLAND_ENABLED
int32_t takeoff_initial_direction; //deg
bool takeoff_direction_initialized;
#endif
} takeoff_state;

// ground steering controller state
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -382,7 +382,9 @@ void Plane::do_takeoff(const AP_Mission::Mission_Command& cmd)
// zero locked course
steer_state.locked_course_err = 0;
steer_state.hold_course_cd = -1;
#if MODE_AUTOLAND_ENABLED
takeoff_state.takeoff_direction_initialized = false;
#endif
auto_state.baro_takeoff_alt = barometer.get_altitude();
}

Expand Down Expand Up @@ -557,9 +559,11 @@ bool Plane::verify_takeoff()
gps.ground_speed() > min_gps_speed &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
auto_state.takeoff_speed_time_ms = millis();
#if MODE_AUTOLAND_ENABLED
plane.takeoff_state.takeoff_initial_direction = wrap_360(plane.gps.ground_course() + plane.mode_autoland.landing_dir_off);
takeoff_state.takeoff_direction_initialized = true;
gcs().send_text(MAV_SEVERITY_INFO, "Autoland direction= %u",int(takeoff_state.takeoff_initial_direction));
#endif
}
if (auto_state.takeoff_speed_time_ms != 0 &&
millis() - auto_state.takeoff_speed_time_ms >= 2000) {
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/control_modes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,11 @@ Mode *Plane::mode_from_mode_num(const enum Mode::Number num)
case Mode::Number::TAKEOFF:
ret = &mode_takeoff;
break;
#if MODE_AUTOLAND_ENABLED
case Mode::Number::AUTOLAND:
ret = &mode_autoland;
break;
#endif //MODE_AUTOLAND_ENABLED
case Mode::Number::THERMAL:
#if HAL_SOARING_ENABLED
ret = &mode_thermal;
Expand Down
14 changes: 12 additions & 2 deletions ArduPlane/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,10 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
#endif // HAL_QUADPLANE_ENABLED

case Mode::Number::AUTO:
case Mode::Number::AUTOLAND: {
#if MODE_AUTOLAND_ENABLED
case Mode::Number::AUTOLAND:
#endif
{
if (failsafe_in_landing_sequence()) {
// don't failsafe in a landing sequence
break;
Expand Down Expand Up @@ -146,10 +149,12 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
set_mode(mode_fbwa, reason);
} else if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
set_mode(mode_auto, reason);
#if MODE_AUTOLAND_ENABLED
} else if (g.fs_action_long == FS_ACTION_LONG_AUTOLAND) {
if(!set_mode(mode_autoland, reason)) {
set_mode(mode_rtl, reason);
}
#endif
} else {
set_mode(mode_rtl, reason);
}
Expand Down Expand Up @@ -199,20 +204,23 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
set_mode(mode_fbwa, reason);
} else if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
set_mode(mode_auto, reason);
#if MODE_AUTOLAND_ENABLED
} else if (g.fs_action_long == FS_ACTION_LONG_AUTOLAND) {
if(!set_mode(mode_autoland, reason)) {
set_mode(mode_rtl, reason);
}
} else if (g.fs_action_long == FS_ACTION_LONG_RTL) {
set_mode(mode_rtl, reason);
#endif
}
break;

case Mode::Number::RTL:
if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
set_mode(mode_auto, reason);
#if MODE_AUTOLAND_ENABLED
} else if (g.fs_action_long == FS_ACTION_LONG_AUTOLAND) {
set_mode(mode_autoland, reason);
#endif
}
break;
#if HAL_QUADPLANE_ENABLED
Expand All @@ -221,7 +229,9 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
case Mode::Number::LOITER_ALT_QLAND:
#endif
case Mode::Number::INITIALISING:
#if MODE_AUTOLAND_ENABLED
case Mode::Number::AUTOLAND:
#endif
break;
}
gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe On: %s", (reason == ModeReason:: GCS_FAILSAFE) ? "GCS" : "RC Long", control_mode->name());
Expand Down
8 changes: 6 additions & 2 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@
#define AP_QUICKTUNE_ENABLED HAL_QUADPLANE_ENABLED
#endif

#ifndef MODE_AUTOLAND_ENABLED
#define MODE_AUTOLAND_ENABLED 1
#endif

#include <AP_Quicktune/AP_Quicktune.h>

class AC_PosControl;
Expand Down Expand Up @@ -858,7 +862,7 @@ class ModeTakeoff: public Mode
bool have_autoenabled_fences;

};

#if MODE_AUTOLAND_ENABLED
class ModeAutoLand: public Mode
{
public:
Expand Down Expand Up @@ -892,7 +896,7 @@ class ModeAutoLand: public Mode
AP_Mission::Mission_Command cmd;
bool land_started;
};

#endif
#if HAL_SOARING_ENABLED

class ModeThermal: public Mode
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/mode_autoland.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
#include "Plane.h"
#include <GCS_MAVLink/GCS.h>

#if MODE_AUTOLAND_ENABLED

/*
mode AutoLand parameters
*/
Expand Down Expand Up @@ -113,3 +115,4 @@ void ModeAutoLand::navigate()
plane.verify_command(cmd);
}
}
#endif
6 changes: 4 additions & 2 deletions ArduPlane/mode_takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,9 @@ void ModeTakeoff::update()
plane.takeoff_state.throttle_max_timer_ms = millis();
takeoff_mode_setup = true;
plane.steer_state.hold_course_cd = wrap_360_cd(direction*100); // Necessary to allow Plane::takeoff_calc_roll() to function.
#if MODE_AUTOLAND_ENABLED
plane.takeoff_state.takeoff_direction_initialized = false;
#endif
}
}
}
Expand All @@ -143,7 +145,7 @@ void ModeTakeoff::update()
plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
takeoff_mode_setup = false;
}
#if MODE_AUTOLAND_ENABLED
// set takeoff_initial_direction
const float min_gps_speed = GPS_GND_CRS_MIN_SPD;
if (!(plane.takeoff_state.takeoff_direction_initialized) && (plane.gps.ground_speed() > min_gps_speed)
Expand All @@ -152,7 +154,7 @@ void ModeTakeoff::update()
plane.takeoff_state.takeoff_direction_initialized = true;
gcs().send_text(MAV_SEVERITY_INFO, "Autoland direction= %u",int(plane.takeoff_state.takeoff_initial_direction));
}

#endif
// We update the waypoint to follow once we're past TKOFF_LVL_ALT or we
// pass the target location. The check for target location prevents us
// flying towards a wrong location if we can't climb.
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class QuadPlane
friend class ModeQAcro;
friend class ModeLoiterAltQLand;
friend class ModeAutoLand;

QuadPlane(AP_AHRS &_ahrs);

static QuadPlane *get_singleton() {
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,14 @@ bool Plane::auto_takeoff_check(void)
}

// Reset states if process has been interrupted, except takeoff_direction_initialized if set
#if MODE_AUTOLAND_ENABLED
bool takeoff_dir_initialized = takeoff_state.takeoff_direction_initialized;
#endif
if (takeoff_state.last_check_ms && (now - takeoff_state.last_check_ms) > 200) {
memset(&takeoff_state, 0, sizeof(takeoff_state));
#if MODE_AUTOLAND_ENABLED
takeoff_state.takeoff_direction_initialized = takeoff_dir_initialized; //restore dir init state
#endif
return false;
}
takeoff_state.last_check_ms = now;
Expand Down
1 change: 1 addition & 0 deletions Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -226,6 +226,7 @@ def config_option(self):
Feature('Plane', 'PLANE_GUIDED_SLEW', 'AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED', 'Enable Offboard-guided slew commands', 0, None), # noqa:401
Feature('Plane', 'PLANE_GLIDER_PULLUP', 'AP_PLANE_GLIDER_PULLUP_ENABLED', 'Enable Glider pullup support', 0, None),
Feature('Plane', 'QUICKTUNE', 'AP_QUICKTUNE_ENABLED', 'Enable VTOL quicktune', 0, None),
Feature('Plane', 'AUTOLAND_MODE', 'MODE_AUTOLAND_ENABLED', 'Enable Fixed Wing Autolanding mode', 0, None),

Feature('RC', 'RC_Protocol', 'AP_RCPROTOCOL_ENABLED', "Enable Serial RC Protocols", 0, None), # NOQA: E501
Feature('RC', 'RC_CRSF', 'AP_RCPROTOCOL_CRSF_ENABLED', "Enable CRSF", 0, "RC_Protocol"), # NOQA: E501
Expand Down

0 comments on commit dab9079

Please sign in to comment.