mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: fixed plane landing gear to obey LGR_OPTIONS bits
we forced landing gear retract/deploy on takeoff and landing when we should be following the options bits
This commit is contained in:
parent
efb5ad2f1c
commit
156fe0846f
@ -522,8 +522,7 @@ private:
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
// landing gear state
|
||||
struct {
|
||||
int8_t last_auto_cmd;
|
||||
int8_t last_cmd;
|
||||
AP_Vehicle::FixedWing::FlightStage last_flight_stage;
|
||||
} gear;
|
||||
#endif
|
||||
|
||||
@ -933,7 +932,6 @@ 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);
|
||||
|
@ -1128,6 +1128,9 @@ void QuadPlane::init_qland(void)
|
||||
last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
||||
landing_detect.lower_limit_start_ms = 0;
|
||||
landing_detect.land_start_ms = 0;
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
plane.g2.landing_gear.deploy_for_landing();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -2777,6 +2780,9 @@ bool QuadPlane::verify_vtol_land(void)
|
||||
if (poscontrol.state == QPOS_POSITION2 &&
|
||||
plane.auto_state.wp_distance < 2) {
|
||||
poscontrol.state = QPOS_LAND_DESCEND;
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
plane.g2.landing_gear.deploy_for_landing();
|
||||
#endif
|
||||
last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
||||
gcs().send_text(MAV_SEVERITY_INFO,"Land descend started");
|
||||
if (plane.control_mode == &plane.mode_auto) {
|
||||
|
@ -546,47 +546,24 @@ void Plane::set_servos_flaps(void)
|
||||
}
|
||||
|
||||
#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 == &mode_auto && hal.util->get_soft_armed() && is_flying()) {
|
||||
AP_LandingGear::LandingGearCommand cmd = (AP_LandingGear::LandingGearCommand)gear.last_auto_cmd;
|
||||
if (control_mode == &mode_auto && hal.util->get_soft_armed() && is_flying() && gear.last_flight_stage != flight_stage) {
|
||||
switch (flight_stage) {
|
||||
case AP_Vehicle::FixedWing::FLIGHT_LAND:
|
||||
cmd = AP_LandingGear::LandingGear_Deploy;
|
||||
g2.landing_gear.deploy_for_landing();
|
||||
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;
|
||||
}
|
||||
g2.landing_gear.retract_after_takeoff();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if (cmd != gear.last_auto_cmd) {
|
||||
gear.last_auto_cmd = (int8_t)cmd;
|
||||
change_landing_gear(cmd);
|
||||
}
|
||||
}
|
||||
gear.last_flight_stage = flight_stage;
|
||||
}
|
||||
#endif // LANDING_GEAR_ENABLED
|
||||
|
||||
|
@ -112,8 +112,6 @@ void Plane::init_ardupilot()
|
||||
#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
|
||||
|
Loading…
Reference in New Issue
Block a user