mirror of https://github.com/ArduPilot/ardupilot
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
a552861d8f
commit
62ff0a5d4f
|
@ -537,8 +537,7 @@ private:
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if LANDING_GEAR_ENABLED == ENABLED
|
||||||
// landing gear state
|
// landing gear state
|
||||||
struct {
|
struct {
|
||||||
int8_t last_auto_cmd;
|
AP_Vehicle::FixedWing::FlightStage last_flight_stage;
|
||||||
int8_t last_cmd;
|
|
||||||
} gear;
|
} gear;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -946,7 +945,6 @@ private:
|
||||||
void set_servos_controlled(void);
|
void set_servos_controlled(void);
|
||||||
void set_servos_old_elevons(void);
|
void set_servos_old_elevons(void);
|
||||||
void set_servos_flaps(void);
|
void set_servos_flaps(void);
|
||||||
void change_landing_gear(AP_LandingGear::LandingGearCommand cmd);
|
|
||||||
void set_landing_gear(void);
|
void set_landing_gear(void);
|
||||||
void dspoiler_update(void);
|
void dspoiler_update(void);
|
||||||
void servo_output_mixers(void);
|
void servo_output_mixers(void);
|
||||||
|
|
|
@ -1090,6 +1090,9 @@ void QuadPlane::init_qland(void)
|
||||||
poscontrol.state = QPOS_LAND_DESCEND;
|
poscontrol.state = QPOS_LAND_DESCEND;
|
||||||
landing_detect.lower_limit_start_ms = 0;
|
landing_detect.lower_limit_start_ms = 0;
|
||||||
landing_detect.land_start_ms = 0;
|
landing_detect.land_start_ms = 0;
|
||||||
|
#if LANDING_GEAR_ENABLED == ENABLED
|
||||||
|
plane.g2.landing_gear.deploy_for_landing();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -2716,6 +2719,9 @@ bool QuadPlane::verify_vtol_land(void)
|
||||||
if (poscontrol.state == QPOS_POSITION2 &&
|
if (poscontrol.state == QPOS_POSITION2 &&
|
||||||
plane.auto_state.wp_distance < 2) {
|
plane.auto_state.wp_distance < 2) {
|
||||||
poscontrol.state = QPOS_LAND_DESCEND;
|
poscontrol.state = QPOS_LAND_DESCEND;
|
||||||
|
#if LANDING_GEAR_ENABLED == ENABLED
|
||||||
|
plane.g2.landing_gear.deploy_for_landing();
|
||||||
|
#endif
|
||||||
gcs().send_text(MAV_SEVERITY_INFO,"Land descend started");
|
gcs().send_text(MAV_SEVERITY_INFO,"Land descend started");
|
||||||
if (plane.control_mode == &plane.mode_auto) {
|
if (plane.control_mode == &plane.mode_auto) {
|
||||||
// set height to mission height, so we can use the mission
|
// set height to mission height, so we can use the mission
|
||||||
|
|
|
@ -544,47 +544,24 @@ void Plane::set_servos_flaps(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#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
|
setup landing gear state
|
||||||
*/
|
*/
|
||||||
void Plane::set_landing_gear(void)
|
void Plane::set_landing_gear(void)
|
||||||
{
|
{
|
||||||
if (control_mode == &mode_auto && hal.util->get_soft_armed() && is_flying()) {
|
if (control_mode == &mode_auto && hal.util->get_soft_armed() && is_flying() && gear.last_flight_stage != flight_stage) {
|
||||||
AP_LandingGear::LandingGearCommand cmd = (AP_LandingGear::LandingGearCommand)gear.last_auto_cmd;
|
|
||||||
switch (flight_stage) {
|
switch (flight_stage) {
|
||||||
case AP_Vehicle::FixedWing::FLIGHT_LAND:
|
case AP_Vehicle::FixedWing::FLIGHT_LAND:
|
||||||
cmd = AP_LandingGear::LandingGear_Deploy;
|
g2.landing_gear.deploy_for_landing();
|
||||||
break;
|
break;
|
||||||
case AP_Vehicle::FixedWing::FLIGHT_NORMAL:
|
case AP_Vehicle::FixedWing::FLIGHT_NORMAL:
|
||||||
cmd = AP_LandingGear::LandingGear_Retract;
|
g2.landing_gear.retract_after_takeoff();
|
||||||
break;
|
|
||||||
case AP_Vehicle::FixedWing::FLIGHT_VTOL:
|
|
||||||
if (quadplane.is_vtol_land(mission.get_current_nav_cmd().id)) {
|
|
||||||
cmd = AP_LandingGear::LandingGear_Deploy;
|
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
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
|
#endif // LANDING_GEAR_ENABLED
|
||||||
|
|
||||||
|
|
|
@ -135,8 +135,6 @@ void Plane::init_ardupilot()
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if LANDING_GEAR_ENABLED == ENABLED
|
||||||
// initialise landing gear position
|
// initialise landing gear position
|
||||||
g2.landing_gear.init();
|
g2.landing_gear.init();
|
||||||
gear.last_auto_cmd = -1;
|
|
||||||
gear.last_cmd = -1;
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if FENCE_TRIGGERED_PIN > 0
|
#if FENCE_TRIGGERED_PIN > 0
|
||||||
|
|
Loading…
Reference in New Issue