mirror of https://github.com/ArduPilot/ardupilot
Plane: added landing gear support
This commit is contained in:
parent
fa6afe145f
commit
01178a75e9
|
@ -101,6 +101,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||
#if OSD_ENABLED == ENABLED
|
||||
SCHED_TASK(publish_osd_info, 1, 10),
|
||||
#endif
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_LandingGear, &plane.g2.landing_gear, update, 10, 50),
|
||||
#endif
|
||||
};
|
||||
|
||||
constexpr int8_t Plane::_failsafe_priorities[5];
|
||||
|
|
|
@ -1189,6 +1189,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @User: User
|
||||
AP_GROUPINFO("TKOFF_ACCEL_CNT", 15, ParametersG2, takeoff_throttle_accel_count, 1),
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
// @Group: LGR_
|
||||
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
|
||||
AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -551,6 +551,10 @@ public:
|
|||
#endif // ENABLE_SCRIPTING
|
||||
|
||||
AP_Int8 takeoff_throttle_accel_count;
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
AP_LandingGear landing_gear;
|
||||
#endif
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
|
|
@ -96,6 +96,7 @@
|
|||
#include <AP_ICEngine/AP_ICEngine.h>
|
||||
#include <AP_Gripper/AP_Gripper.h>
|
||||
#include <AP_Landing/AP_Landing.h>
|
||||
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
||||
|
||||
#include "GCS_Mavlink.h"
|
||||
#include "GCS_Plane.h"
|
||||
|
@ -536,8 +537,16 @@ private:
|
|||
// throttle commanded from external controller in percent
|
||||
float forced_throttle;
|
||||
uint32_t last_forced_throttle_ms;
|
||||
} guided_state;
|
||||
} guided_state;
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
// landing gear state
|
||||
struct {
|
||||
int8_t last_auto_cmd;
|
||||
int8_t last_cmd;
|
||||
} gear;
|
||||
#endif
|
||||
|
||||
struct {
|
||||
// on hard landings, only check once after directly a landing so you
|
||||
// don't trigger a crash when picking up the aircraft
|
||||
|
@ -963,6 +972,8 @@ private:
|
|||
void set_servos_controlled(void);
|
||||
void set_servos_old_elevons(void);
|
||||
void set_servos_flaps(void);
|
||||
void change_landing_gear(AP_LandingGear::LandingGearCommand cmd);
|
||||
void set_landing_gear(void);
|
||||
void dspoiler_update(void);
|
||||
void servo_output_mixers(void);
|
||||
void servos_output(void);
|
||||
|
|
|
@ -34,6 +34,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
|||
// the following functions do not need to be initialised:
|
||||
case ARMDISARM:
|
||||
case INVERTED:
|
||||
case LANDING_GEAR:
|
||||
break;
|
||||
default:
|
||||
RC_Channel::init_aux_function(ch_option, ch_flag);
|
||||
|
@ -62,6 +63,21 @@ void RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const aux_swi
|
|||
case INVERTED:
|
||||
plane.inverted_flight = (ch_flag == HIGH);
|
||||
break;
|
||||
|
||||
case LANDING_GEAR:
|
||||
switch (ch_flag) {
|
||||
case LOW:
|
||||
plane.g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
|
||||
break;
|
||||
case MIDDLE:
|
||||
// nothing
|
||||
break;
|
||||
case HIGH:
|
||||
plane.g2.landing_gear.set_position(AP_LandingGear::LandingGear_Retract);
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||
break;
|
||||
|
|
|
@ -381,3 +381,7 @@
|
|||
#define SOARING_ENABLED ENABLED
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef LANDING_GEAR_ENABLED
|
||||
#define LANDING_GEAR_ENABLED !HAL_MINIMIZE_FEATURES
|
||||
#endif
|
||||
|
|
|
@ -53,6 +53,7 @@ LIBRARIES += AC_Fence
|
|||
LIBRARIES += AP_Tuning
|
||||
LIBRARIES += AP_Stats
|
||||
LIBRARIES += AP_Landing
|
||||
LIBRARIES += AP_LandingGear
|
||||
LIBRARIES += AP_Beacon
|
||||
LIBRARIES += PID
|
||||
LIBRARIES += AP_Soaring
|
||||
|
|
|
@ -30,6 +30,11 @@ void Plane::parachute_release()
|
|||
|
||||
// release parachute
|
||||
parachute.release();
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
// deploy landing gear
|
||||
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -54,7 +59,11 @@ bool Plane::parachute_manual_release()
|
|||
// if we get this far release parachute
|
||||
parachute_release();
|
||||
|
||||
return true;
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
// deploy landing gear
|
||||
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -467,6 +467,50 @@ void Plane::set_servos_flaps(void)
|
|||
flaperon_update(auto_flap_percent);
|
||||
}
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
/*
|
||||
change and report landing gear
|
||||
*/
|
||||
void Plane::change_landing_gear(AP_LandingGear::LandingGearCommand cmd)
|
||||
{
|
||||
if (cmd != (AP_LandingGear::LandingGearCommand)gear.last_cmd) {
|
||||
if (SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
|
||||
g2.landing_gear.set_position(cmd);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "LandingGear: %s", cmd==AP_LandingGear::LandingGear_Retract?"RETRACT":"DEPLOY");
|
||||
}
|
||||
gear.last_cmd = (int8_t)cmd;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
setup landing gear state
|
||||
*/
|
||||
void Plane::set_landing_gear(void)
|
||||
{
|
||||
if (control_mode == AUTO && hal.util->get_soft_armed() && is_flying()) {
|
||||
AP_LandingGear::LandingGearCommand cmd = (AP_LandingGear::LandingGearCommand)gear.last_auto_cmd;
|
||||
switch (flight_stage) {
|
||||
case AP_Vehicle::FixedWing::FLIGHT_LAND:
|
||||
cmd = AP_LandingGear::LandingGear_Deploy;
|
||||
break;
|
||||
case AP_Vehicle::FixedWing::FLIGHT_NORMAL:
|
||||
cmd = AP_LandingGear::LandingGear_Retract;
|
||||
break;
|
||||
case AP_Vehicle::FixedWing::FLIGHT_VTOL:
|
||||
if (quadplane.is_vtol_land(mission.get_current_nav_cmd().id)) {
|
||||
cmd = AP_LandingGear::LandingGear_Deploy;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if (cmd != gear.last_auto_cmd) {
|
||||
gear.last_auto_cmd = (int8_t)cmd;
|
||||
change_landing_gear(cmd);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // LANDING_GEAR_ENABLED
|
||||
|
||||
/*
|
||||
apply vtail and elevon mixers
|
||||
|
@ -594,6 +638,11 @@ void Plane::set_servos(void)
|
|||
|
||||
// setup flap outputs
|
||||
set_servos_flaps();
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
// setup landing gear output
|
||||
set_landing_gear();
|
||||
#endif
|
||||
|
||||
if (auto_throttle_mode ||
|
||||
quadplane.in_assisted_flight() ||
|
||||
|
|
|
@ -170,6 +170,13 @@ void Plane::init_ardupilot()
|
|||
camera_mount.init(serial_manager);
|
||||
#endif
|
||||
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
// initialise landing gear position
|
||||
g2.landing_gear.init();
|
||||
gear.last_auto_cmd = -1;
|
||||
gear.last_cmd = -1;
|
||||
#endif
|
||||
|
||||
#if FENCE_TRIGGERED_PIN > 0
|
||||
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
|
||||
|
|
|
@ -27,6 +27,7 @@ def build(bld):
|
|||
'AC_Fence',
|
||||
'AP_Stats',
|
||||
'AP_Landing',
|
||||
'AP_LandingGear',
|
||||
'AP_Beacon',
|
||||
'PID',
|
||||
'AP_Soaring',
|
||||
|
|
Loading…
Reference in New Issue