Skip to content

Commit

Permalink
Plane: added glider pullup support
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Sep 10, 2024
1 parent c0b89ec commit 2f19dfe
Show file tree
Hide file tree
Showing 11 changed files with 407 additions and 8 deletions.
23 changes: 23 additions & 0 deletions ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,6 +216,13 @@ void Plane::update_speed_height(void)
should_run_tecs = false;
}
#endif

#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (mode_auto.in_pullup()) {
should_run_tecs = false;
}
#endif

if (should_run_tecs) {
// Call TECS 50Hz update. Note that we call this regardless of
// throttle suppressed, as this needs to be running for
Expand Down Expand Up @@ -512,6 +519,12 @@ void Plane::update_fly_forward(void)
}
#endif

if (auto_state.idle_mode) {
// don't fuse airspeed when in balloon lift
ahrs.set_fly_forward(false);
return;
}

if (flight_stage == AP_FixedWing::FlightStage::LAND) {
ahrs.set_fly_forward(landing.is_flying_forward());
return;
Expand Down Expand Up @@ -578,6 +591,16 @@ void Plane::update_alt()
should_run_tecs = false;
}
#endif

if (auto_state.idle_mode) {
should_run_tecs = false;
}

#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (mode_auto.in_pullup()) {
should_run_tecs = false;
}
#endif

if (should_run_tecs && !throttle_suppressed) {

Expand Down
6 changes: 6 additions & 0 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1019,6 +1019,12 @@ const AP_Param::Info Plane::var_info[] = {
// @Path: mode_takeoff.cpp
GOBJECT(mode_takeoff, "TKOFF_", ModeTakeoff),

#if AP_PLANE_GLIDER_PULLUP_ENABLED
// @Group: PUP_
// @Path: pullup.cpp
GOBJECTN(mode_auto.pullup, pullup, "PUP_", GliderPullup),
#endif

// @Group:
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
PARAM_VEHICLE_INFO,
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -359,6 +359,8 @@ class Parameters {
k_param_autotune_options,
k_param_takeoff_throttle_min,
k_param_takeoff_options,

k_param_pullup = 270,
};

AP_Int16 format_version;
Expand Down
10 changes: 10 additions & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,7 @@
#include "avoidance_adsb.h"
#endif
#include "AP_Arming.h"
#include "pullup.h"

/*
main APM:Plane class
Expand Down Expand Up @@ -175,6 +176,9 @@ class Plane : public AP_Vehicle {
#if AP_EXTERNAL_CONTROL_ENABLED
friend class AP_ExternalControl_Plane;
#endif
#if AP_PLANE_GLIDER_PULLUP_ENABLED
friend class GliderPullup;
#endif

Plane(void);

Expand Down Expand Up @@ -515,6 +519,11 @@ class Plane : public AP_Vehicle {
// have we checked for an auto-land?
bool checked_for_autoland;

// Altitude threshold to complete a takeoff command in autonomous modes. Centimeters
// are we in idle mode? used for balloon launch to stop servo
// movement until altitude is reached
bool idle_mode;

// are we in VTOL mode in AUTO?
bool vtol_mode;

Expand Down Expand Up @@ -959,6 +968,7 @@ class Plane : public AP_Vehicle {
void do_loiter_turns(const AP_Mission::Mission_Command& cmd);
void do_loiter_time(const AP_Mission::Mission_Command& cmd);
void do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd);
void do_altitude_wait(const AP_Mission::Mission_Command& cmd);
void do_loiter_to_alt(const AP_Mission::Mission_Command& cmd);
void do_vtol_takeoff(const AP_Mission::Mission_Command& cmd);
void do_vtol_land(const AP_Mission::Mission_Command& cmd);
Expand Down
57 changes: 50 additions & 7 deletions ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,9 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)

nav_controller->set_data_is_stale();

// start non-idle
auto_state.idle_mode = false;

// reset loiter start time. New command is a new loiter
loiter.start_time_ms = 0;

Expand Down Expand Up @@ -92,6 +95,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
break;

case MAV_CMD_NAV_ALTITUDE_WAIT:
do_altitude_wait(cmd);
break;

#if HAL_QUADPLANE_ENABLED
Expand Down Expand Up @@ -501,6 +505,15 @@ void Plane::do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd)
reset_offset_altitude();
}

void Plane::do_altitude_wait(const AP_Mission::Mission_Command& cmd)
{
// set all servos to trim until we reach altitude or descent speed
auto_state.idle_mode = true;
#if AP_PLANE_GLIDER_PULLUP_ENABLED
mode_auto.pullup.reset();
#endif
}

void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd)
{
//set target alt
Expand Down Expand Up @@ -831,17 +844,46 @@ bool Plane::verify_continue_and_change_alt()
*/
bool ModeAuto::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
{
if (plane.current_loc.alt > cmd.content.altitude_wait.altitude*100.0f) {
gcs().send_text(MAV_SEVERITY_INFO,"Reached altitude");
return true;
#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (pullup.in_pullup()) {
return pullup.verify_pullup();
}
if (plane.auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {
#endif

/*
the target altitude in param1 is always AMSL
*/
const float alt_diff = plane.current_loc.alt*0.01 - cmd.content.altitude_wait.altitude;
bool completed = false;
if (alt_diff > 0) {
gcs().send_text(MAV_SEVERITY_INFO,"Reached altitude");
completed = true;
} else if (cmd.content.altitude_wait.descent_rate > 0 &&
plane.auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {
gcs().send_text(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)plane.auto_state.sink_rate);
return true;
completed = true;
}

// if requested, wiggle servos
if (cmd.content.altitude_wait.wiggle_time != 0) {
if (completed) {
#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (pullup.pullup_start()) {
// we are doing a pullup, ALTITUDE_WAIT not complete until pullup is done
return false;
}
#endif
return true;
}

const float time_to_alt = alt_diff / MIN(plane.auto_state.sink_rate, -0.01);

/*
if requested, wiggle servos
we don't start a wiggle if we expect to release soon as we don't
want the servos to be off trim at the time of release
*/
if (cmd.content.altitude_wait.wiggle_time != 0 &&
(plane.auto_state.sink_rate > 0 || time_to_alt > cmd.content.altitude_wait.wiggle_time*5)) {
if (wiggle.stage == 0 &&
AP_HAL::millis() - wiggle.last_ms > cmd.content.altitude_wait.wiggle_time*1000) {
wiggle.stage = 1;
Expand Down Expand Up @@ -1291,3 +1333,4 @@ bool Plane::in_auto_mission_id(uint16_t command) const
{
return control_mode == &mode_auto && mission.get_current_nav_id() == command;
}

3 changes: 3 additions & 0 deletions ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,9 @@ bool Mode::enter()
plane.target_altitude.terrain_following_pending = false;
#endif

// disable auto mode servo idle during altitude wait command
plane.auto_state.idle_mode = false;

bool enter_result = _enter();

if (enter_result) {
Expand Down
10 changes: 10 additions & 0 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include "quadplane.h"
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Mission/AP_Mission.h>
#include "pullup.h"

class AC_PosControl;
class AC_AttitudeControl_Multi;
Expand Down Expand Up @@ -208,6 +209,7 @@ friend class ModeQAcro;
class ModeAuto : public Mode
{
public:
friend class Plane;

Number mode_number() const override { return Number::AUTO; }
const char *name() const override { return "AUTO"; }
Expand Down Expand Up @@ -237,6 +239,10 @@ class ModeAuto : public Mode

void run() override;

#if AP_PLANE_GLIDER_PULLUP_ENABLED
bool in_pullup() const { return pullup.in_pullup(); }
#endif

protected:

bool _enter() override;
Expand All @@ -257,6 +263,10 @@ class ModeAuto : public Mode
uint8_t stage;
uint32_t last_ms;
} wiggle;

#if AP_PLANE_GLIDER_PULLUP_ENABLED
GliderPullup pullup;
#endif // AP_PLANE_GLIDER_PULLUP_ENABLED
};


Expand Down
13 changes: 13 additions & 0 deletions ArduPlane/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,12 @@ void ModeAuto::update()
}
#endif

#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (pullup.in_pullup()) {
return;
}
#endif

if (nav_cmd_id == MAV_CMD_NAV_TAKEOFF ||
(nav_cmd_id == MAV_CMD_NAV_LAND && plane.flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING)) {
plane.takeoff_calc_roll();
Expand Down Expand Up @@ -166,6 +172,13 @@ bool ModeAuto::is_landing() const

void ModeAuto::run()
{
#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (pullup.in_pullup()) {
pullup.stabilize_pullup();
return;
}
#endif

if (plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_ALTITUDE_WAIT) {

wiggle_servos();
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/navigation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -321,7 +321,7 @@ void Plane::update_loiter_update_nav(uint16_t radius)
if ((loiter.start_time_ms == 0 &&
(control_mode == &mode_auto || control_mode == &mode_guided) &&
auto_state.crosstrack &&
current_loc.get_distance(next_WP_loc) > radius*3) ||
current_loc.get_distance(next_WP_loc) > 3 * nav_controller->loiter_radius(radius)) ||
quadplane_qrtl_switch) {
/*
if never reached loiter point and using crosstrack and somewhat far away from loiter point
Expand Down
Loading

0 comments on commit 2f19dfe

Please sign in to comment.