ArduPlane: make and use AP_LANDINGGEAR_ENABLED

This commit is contained in:
Peter Barker 2022-10-01 20:21:38 +10:00 committed by Andrew Tridgell
parent c32a11f37a
commit 0cf56ea320
11 changed files with 14 additions and 18 deletions

View File

@ -133,7 +133,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#if AP_GRIPPER_ENABLED
SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75, 156),
#endif
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
SCHED_TASK(landing_gear_update, 5, 50, 159),
#endif
};

View File

@ -1096,7 +1096,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard
AP_GROUPINFO("TKOFF_ACCEL_CNT", 15, ParametersG2, takeoff_throttle_accel_count, 1),
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
// @Group: LGR_
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear),

View File

@ -528,7 +528,7 @@ public:
AP_Int8 takeoff_throttle_accel_count;
AP_Int8 takeoff_timeout;
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
AP_LandingGear landing_gear;
#endif

View File

@ -558,7 +558,7 @@ private:
#endif // OFFBOARD_GUIDED == ENABLED
} guided_state;
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
// landing gear state
struct {
AP_FixedWing::FlightStage last_flight_stage;

View File

@ -250,10 +250,6 @@
#define OFFBOARD_GUIDED !HAL_MINIMIZE_FEATURES
#endif
#ifndef LANDING_GEAR_ENABLED
#define LANDING_GEAR_ENABLED !HAL_MINIMIZE_FEATURES
#endif
//////////////////////////////////////////////////////////////////////////////
// EKF Failsafe
#ifndef FS_EKF_THRESHOLD_DEFAULT

View File

@ -13,7 +13,7 @@ bool ModeQLand::_enter()
quadplane.last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
quadplane.landing_detect.lower_limit_start_ms = 0;
quadplane.landing_detect.land_start_ms = 0;
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
plane.g2.landing_gear.deploy_for_landing();
#endif
#if AP_FENCE_ENABLED

View File

@ -31,7 +31,7 @@ void Plane::parachute_release()
// release parachute
parachute.release();
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
// deploy landing gear
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
#endif
@ -59,10 +59,10 @@ bool Plane::parachute_manual_release()
// if we get this far release parachute
parachute_release();
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
// deploy landing gear
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
#endif
return true;
}
#endif
#endif

View File

@ -3325,7 +3325,7 @@ bool QuadPlane::verify_vtol_land(void)
#if AP_FENCE_ENABLED
plane.fence.auto_disable_fence_for_landing();
#endif
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
plane.g2.landing_gear.deploy_for_landing();
#endif
last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);

View File

@ -691,7 +691,7 @@ void Plane::set_servos_flaps(void)
flaperon_update();
}
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
/*
setup landing gear state
*/
@ -711,7 +711,7 @@ void Plane::set_landing_gear(void)
}
gear.last_flight_stage = flight_stage;
}
#endif // LANDING_GEAR_ENABLED
#endif // AP_LANDINGGEAR_ENABLED
/*
@ -879,7 +879,7 @@ void Plane::set_servos(void)
// setup flap outputs
set_servos_flaps();
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
// setup landing gear output
set_landing_gear();
#endif

View File

@ -101,7 +101,7 @@ void Plane::init_ardupilot()
camera_mount.init();
#endif
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
// initialise landing gear position
g2.landing_gear.init();
#endif

View File

@ -274,7 +274,7 @@ return_zero:
return 0;
}
#if LANDING_GEAR_ENABLED == ENABLED
#if AP_LANDINGGEAR_ENABLED
/*
update landing gear
*/