Skip to content

Commit

Permalink
Copter: integrate landing gear option and make edge based
Browse files Browse the repository at this point in the history
also guided mode now retracts landing gear after takeoff
previously landing gear deployment was "level based" meaning the pilot could not override the gear's position
  • Loading branch information
rmackay9 committed Feb 25, 2020
1 parent 6297306 commit 8d99f20
Show file tree
Hide file tree
Showing 6 changed files with 17 additions and 37 deletions.
6 changes: 0 additions & 6 deletions ArduCopter/landing_gear.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,6 @@ void Copter::landinggear_update()
// last status (deployed or retracted) used to check for changes, initialised to startup state of landing gear
static bool last_deploy_status = landinggear.deployed();

// if we are doing an automatic landing procedure, force the landing gear to deploy.
// To-Do: should we pause the auto-land procedure to give time for gear to come down?
if (flightmode->landing_gear_should_be_deployed()) {
landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
}

// send event message to datalog if status has changed
if (landinggear.deployed() != last_deploy_status) {
if (landinggear.deployed()) {
Expand Down
4 changes: 0 additions & 4 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,6 @@ class Mode {
virtual bool is_taking_off() const;
static void takeoff_stop() { takeoff.stop(); }

virtual bool landing_gear_should_be_deployed() const { return false; }
virtual bool is_landing() const { return false; }

// mode requires terrain to be present to be functional
Expand Down Expand Up @@ -361,7 +360,6 @@ class ModeAuto : public Mode {
void nav_guided_start();

bool is_landing() const override;
bool landing_gear_should_be_deployed() const override;

bool is_taking_off() const override;

Expand Down Expand Up @@ -870,7 +868,6 @@ class ModeLand : public Mode {
bool is_autopilot() const override { return true; }

bool is_landing() const override { return true; };
bool landing_gear_should_be_deployed() const override { return true; };

void do_not_use_GPS();

Expand Down Expand Up @@ -1043,7 +1040,6 @@ class ModeRTL : public Mode {
bool state_complete() { return _state_complete; }

bool is_landing() const override;
bool landing_gear_should_be_deployed() const override;

void restart_without_terrain();

Expand Down
18 changes: 4 additions & 14 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,6 +234,9 @@ void ModeAuto::land_start(const Vector3f& destination)

// initialise yaw
auto_yaw.set_mode(AUTO_YAW_HOLD);

// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
}

// auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location
Expand Down Expand Up @@ -358,19 +361,6 @@ bool ModeAuto::is_taking_off() const
return ((_mode == Auto_TakeOff) && !wp_nav->reached_wp_destination());
}

bool ModeAuto::landing_gear_should_be_deployed() const
{
switch(_mode) {
case Auto_Land:
return true;
case Auto_RTL:
return copter.mode_rtl.landing_gear_should_be_deployed();
default:
return false;
}
return false;
}

// auto_payload_place_start - initialises controller to implement a placing
void ModeAuto::payload_place_start()
{
Expand Down Expand Up @@ -1493,7 +1483,7 @@ bool ModeAuto::verify_takeoff()

// retract the landing gear
if (reached_wp_dest) {
copter.landinggear.set_position(AP_LandingGear::LandingGear_Retract);
copter.landinggear.retract_after_takeoff();
}

return reached_wp_dest;
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -370,6 +370,10 @@ void ModeGuided::takeoff_run()
{
auto_takeoff_run();
if (wp_nav->reached_wp_destination()) {
// optionally retract landing gear
copter.landinggear.retract_after_takeoff();

// switch to position control mode but maintain current target
const Vector3f& target = wp_nav->get_wp_destination();
set_destination(target);
}
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode_land.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,9 @@ bool ModeLand::init(bool ignore_checks)
// initialise yaw
auto_yaw.set_mode(AUTO_YAW_HOLD);

// optionally deploy landing gear
copter.landinggear.deploy_for_landing();

return true;
}

Expand Down
19 changes: 6 additions & 13 deletions ArduCopter/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,6 +274,9 @@ void ModeRTL::descent_start()

// initialise yaw
auto_yaw.set_mode(AUTO_YAW_HOLD);

// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
}

// rtl_descent_run - implements the final descent to the RTL_ALT
Expand Down Expand Up @@ -357,26 +360,16 @@ void ModeRTL::land_start()

// initialise yaw
auto_yaw.set_mode(AUTO_YAW_HOLD);

// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
}

bool ModeRTL::is_landing() const
{
return _state == RTL_Land;
}

bool ModeRTL::landing_gear_should_be_deployed() const
{
switch(_state) {
case RTL_LoiterAtHome:
case RTL_Land:
case RTL_FinalDescent:
return true;
default:
return false;
}
return false;
}

// rtl_returnhome_run - return home
// called by rtl_run at 100hz or more
void ModeRTL::land_run(bool disarm_on_land)
Expand Down

0 comments on commit 8d99f20

Please sign in to comment.