Skip to content

Commit

Permalink
ArduPlane: add AutoLand fixed-wing mode
Browse files Browse the repository at this point in the history
  • Loading branch information
Hwurzburg committed Nov 29, 2024
1 parent 3d8a8d1 commit 21cd87f
Show file tree
Hide file tree
Showing 12 changed files with 176 additions and 3 deletions.
4 changes: 3 additions & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -681,11 +681,13 @@ void Plane::update_flight_stage(void)
}
#endif
set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
} else if (control_mode != &mode_takeoff) {
} else if ((control_mode != &mode_takeoff) && (control_mode != &mode_autoland)) {
// If not in AUTO then assume normal operation for normal TECS operation.
// 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);
}
return;
}
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ MAV_MODE GCS_MAVLINK_Plane::base_mode() const
case Mode::Number::GUIDED:
case Mode::Number::CIRCLE:
case Mode::Number::TAKEOFF:
case Mode::Number::AUTOLAND:
#if HAL_QUADPLANE_ENABLED
case Mode::Number::QRTL:
case Mode::Number::LOITER_ALT_QLAND:
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/GCS_Plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void)
case Mode::Number::GUIDED:
case Mode::Number::CIRCLE:
case Mode::Number::TAKEOFF:
case Mode::Number::AUTOLAND:
#if HAL_QUADPLANE_ENABLED
case Mode::Number::QRTL:
case Mode::Number::LOITER_ALT_QLAND:
Expand Down
4 changes: 4 additions & 0 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1027,6 +1027,10 @@ const AP_Param::Info Plane::var_info[] = {
// @Group: TKOFF_
// @Path: mode_takeoff.cpp
GOBJECT(mode_takeoff, "TKOFF_", ModeTakeoff),

// @Group: AUTOLAND_
// @Path: mode_autoland.cpp
GOBJECT(mode_autoland, "AUTOLAND_", ModeAutoLand),

#if AP_PLANE_GLIDER_PULLUP_ENABLED
// @Group: PUP_
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ class Parameters {
k_param_sonar_old, // unused
k_param_log_bitmask,
k_param_BoardConfig,
k_param_rssi_range, // unused, replaced by rssi_ library parameters
k_param_mode_autoland, // was rssi_range
k_param_flapin_channel_old, // unused, moved to RC_OPTION
k_param_flaperon_output, // unused
k_param_gps,
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -172,6 +172,7 @@ class Plane : public AP_Vehicle {
friend class ModeTakeoff;
friend class ModeThermal;
friend class ModeLoiterAltQLand;
friend class ModeAutoLand;

#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Plane;
Expand Down Expand Up @@ -326,6 +327,7 @@ class Plane : public AP_Vehicle {
#endif // QAUTOTUNE_ENABLED
#endif // HAL_QUADPLANE_ENABLED
ModeTakeoff mode_takeoff;
ModeAutoLand mode_autoland;
#if HAL_SOARING_ENABLED
ModeThermal mode_thermal;
#endif
Expand Down Expand Up @@ -450,6 +452,7 @@ class Plane : public AP_Vehicle {
float throttle_lim_min;
uint32_t throttle_max_timer_ms;
// Good candidate for keeping the initial time for TKOFF_THR_MAX_T.
int32_t takeoff_initial_direction; //deg
} takeoff_state;

// ground steering controller state
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -380,6 +380,7 @@ 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;
takeoff_state.takeoff_initial_direction = -1;
auto_state.baro_takeoff_alt = barometer.get_altitude();
}

Expand Down Expand Up @@ -554,6 +555,8 @@ 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();
takeoff_state.takeoff_initial_direction = gps.ground_course();
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff initial direction= %u",int(takeoff_state.takeoff_initial_direction));
}
if (auto_state.takeoff_speed_time_ms != 0 &&
millis() - auto_state.takeoff_speed_time_ms >= 2000) {
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/control_modes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,9 @@ Mode *Plane::mode_from_mode_num(const enum Mode::Number num)
case Mode::Number::TAKEOFF:
ret = &mode_takeoff;
break;
case Mode::Number::AUTOLAND:
ret = &mode_autoland;
break;
case Mode::Number::THERMAL:
#if HAL_SOARING_ENABLED
ret = &mode_thermal;
Expand Down
4 changes: 3 additions & 1 deletion ArduPlane/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,8 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
break;
#endif // HAL_QUADPLANE_ENABLED

case Mode::Number::AUTO: {
case Mode::Number::AUTO:
case Mode::Number::AUTOLAND: {
if (failsafe_in_landing_sequence()) {
// don't failsafe in a landing sequence
break;
Expand Down Expand Up @@ -169,6 +170,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
#endif // HAL_QUADPLANE_ENABLED

case Mode::Number::AUTO:
case Mode::Number::AUTOLAND:
if (failsafe_in_landing_sequence()) {
// don't failsafe in a landing sequence
break;
Expand Down
40 changes: 40 additions & 0 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ class Mode
#if HAL_QUADPLANE_ENABLED
LOITER_ALT_QLAND = 25,
#endif
AUTOLAND = 26,
};

// Constructor
Expand Down Expand Up @@ -835,6 +836,45 @@ class ModeTakeoff: public Mode
// flag that we have already called autoenable fences once in MODE TAKEOFF
bool have_autoenabled_fences;

};

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

Number mode_number() const override { return Number::AUTOLAND; }
const char *name() const override { return "AUTOLAND"; }
const char *name4() const override { return "AUTOLAND"; }

// methods that affect movement of the vehicle in this mode
void update() override;

void navigate() override;

bool allows_throttle_nudging() const override { return true; }

bool does_auto_navigation() const override { return true; }

bool does_auto_throttle() const override { return true; }


// var_info for holding parameter information
static const struct AP_Param::GroupInfo var_info[];

AP_Int16 final_wp_alt;
AP_Int16 final_wp_dist;

protected:
bool _enter() override;
AP_Mission::Mission_Command cmd {};
bool land_started;


private:



};

#if HAL_SOARING_ENABLED
Expand Down
104 changes: 104 additions & 0 deletions ArduPlane/mode_autoland.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
#include "mode.h"
#include "Plane.h"
#include <GCS_MAVLink/GCS.h>

/*
mode AutoLand parameters
*/
const AP_Param::GroupInfo ModeAutoLand::var_info[] = {
// @Param: WP_ALT
// @DisplayName: Final approach WP altitude
// @Description: This is the target altitude for final approach waypoint
// @Range: 0 200
// @Increment: 1
// @Units: m
// @User: Standard
AP_GROUPINFO("WP_ALT", 1, ModeAutoLand, final_wp_alt, 55),

// @Param: DIST
// @DisplayName: Final approach WP distance
// @Description: This is the distance from Home that the final approach waypoint is set. The waypoint point will be in the opposite direction of takeoff (the direction the plane is facing when the plane sets its takeoff heading)
// @Range: 0 700
// @Increment: 1
// @Units: m
// @User: Standard
AP_GROUPINFO("WP_DIST", 2, ModeAutoLand, final_wp_dist, 400),

AP_GROUPEND
};

ModeAutoLand::ModeAutoLand() :
Mode()
{
AP_Param::setup_object_defaults(this, var_info);
}

bool ModeAutoLand::_enter()
{
//must be flying to enter
if (!plane.is_flying()) {
return false;
}

//if do_land_start exists, jump to it
if( (plane.mission.contains_item(MAV_CMD_DO_LAND_START)) && (plane.arming.is_armed())) {
if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) {
// switch to AUTO
plane.mission.set_force_resume(true);
if (plane.set_mode(plane.mode_auto, ModeReason::FIXED_WING_AUTOLAND)) {
return true;
}
}
}

//setup final approach waypoint
plane.prev_WP_loc = plane.current_loc;
const Location &home = ahrs.get_home();
plane.set_target_altitude_current();
plane.next_WP_loc = home;
uint16_t bearing_cd = wrap_360((plane.takeoff_state.takeoff_initial_direction + 180));
plane.next_WP_loc.offset_bearing(bearing_cd, final_wp_dist);
plane.next_WP_loc.alt = home.alt + final_wp_alt*100;

// create a command to fly to final approach waypoint and start it
cmd.id = MAV_CMD_NAV_WAYPOINT;
cmd.content.location = plane.next_WP_loc;
plane.start_command(cmd);
land_started = false;

return true;
}

void ModeAutoLand::update()
{
plane.calc_nav_roll();
plane.calc_nav_pitch();
plane.set_offset_altitude_location(plane.prev_WP_loc, plane.next_WP_loc);
if (plane.landing.is_throttle_suppressed()) {
// if landing is considered complete throttle is never allowed, regardless of landing type
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
} else {
plane.calc_throttle();
}
}

void ModeAutoLand::navigate()
{
// check to see if if we have reached final approach waypoint, switch to NAV_LAND command and start it once if so
if (!land_started){
if (plane.verify_nav_wp(cmd)){
const Location &home_loc = ahrs.get_home();
cmd.id = MAV_CMD_NAV_LAND;
cmd.content.location = home_loc;
land_started = true;
plane.prev_WP_loc = plane.current_loc;
plane.next_WP_loc = home_loc;
plane.set_offset_altitude_location(plane.prev_WP_loc, plane.next_WP_loc);
plane.start_command(cmd);
}
return;
//otherwise keep flying the current command
} else {
plane.verify_command(cmd);
}
}
10 changes: 10 additions & 0 deletions ArduPlane/mode_takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,7 @@ 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.
plane.takeoff_state.takeoff_initial_direction = -1; //so we can capture takeoff direction
}
}
}
Expand All @@ -130,6 +131,15 @@ void ModeTakeoff::update()
plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
takeoff_mode_setup = false;
}

// set takeoff_initial_direction
const float min_gps_speed = 5;
if ((plane.takeoff_state.takeoff_initial_direction == -1) && (plane.gps.ground_speed() > min_gps_speed)) {
plane.takeoff_state.takeoff_initial_direction = plane.gps.ground_course();
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff initial direction= %u",int(plane.takeoff_state.takeoff_initial_direction));
}



// 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
Expand Down

0 comments on commit 21cd87f

Please sign in to comment.