mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: make and use AP_LANDINGGEAR_ENABLED
This commit is contained in:
parent
c32a11f37a
commit
0cf56ea320
@ -133,7 +133,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||||||
#if AP_GRIPPER_ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75, 156),
|
SCHED_TASK_CLASS(AP_Gripper, &plane.g2.gripper, update, 10, 75, 156),
|
||||||
#endif
|
#endif
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
SCHED_TASK(landing_gear_update, 5, 50, 159),
|
SCHED_TASK(landing_gear_update, 5, 50, 159),
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
@ -1096,7 +1096,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("TKOFF_ACCEL_CNT", 15, ParametersG2, takeoff_throttle_accel_count, 1),
|
AP_GROUPINFO("TKOFF_ACCEL_CNT", 15, ParametersG2, takeoff_throttle_accel_count, 1),
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
// @Group: LGR_
|
// @Group: LGR_
|
||||||
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
|
// @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
|
||||||
AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear),
|
AP_SUBGROUPINFO(landing_gear, "LGR_", 16, ParametersG2, AP_LandingGear),
|
||||||
|
@ -528,7 +528,7 @@ public:
|
|||||||
AP_Int8 takeoff_throttle_accel_count;
|
AP_Int8 takeoff_throttle_accel_count;
|
||||||
AP_Int8 takeoff_timeout;
|
AP_Int8 takeoff_timeout;
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
AP_LandingGear landing_gear;
|
AP_LandingGear landing_gear;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -558,7 +558,7 @@ private:
|
|||||||
#endif // OFFBOARD_GUIDED == ENABLED
|
#endif // OFFBOARD_GUIDED == ENABLED
|
||||||
} guided_state;
|
} guided_state;
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
// landing gear state
|
// landing gear state
|
||||||
struct {
|
struct {
|
||||||
AP_FixedWing::FlightStage last_flight_stage;
|
AP_FixedWing::FlightStage last_flight_stage;
|
||||||
|
@ -250,10 +250,6 @@
|
|||||||
#define OFFBOARD_GUIDED !HAL_MINIMIZE_FEATURES
|
#define OFFBOARD_GUIDED !HAL_MINIMIZE_FEATURES
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef LANDING_GEAR_ENABLED
|
|
||||||
#define LANDING_GEAR_ENABLED !HAL_MINIMIZE_FEATURES
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// EKF Failsafe
|
// EKF Failsafe
|
||||||
#ifndef FS_EKF_THRESHOLD_DEFAULT
|
#ifndef FS_EKF_THRESHOLD_DEFAULT
|
||||||
|
@ -13,7 +13,7 @@ bool ModeQLand::_enter()
|
|||||||
quadplane.last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
quadplane.last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
||||||
quadplane.landing_detect.lower_limit_start_ms = 0;
|
quadplane.landing_detect.lower_limit_start_ms = 0;
|
||||||
quadplane.landing_detect.land_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();
|
plane.g2.landing_gear.deploy_for_landing();
|
||||||
#endif
|
#endif
|
||||||
#if AP_FENCE_ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
|
@ -31,7 +31,7 @@ void Plane::parachute_release()
|
|||||||
// release parachute
|
// release parachute
|
||||||
parachute.release();
|
parachute.release();
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
// deploy landing gear
|
// deploy landing gear
|
||||||
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
|
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
|
||||||
#endif
|
#endif
|
||||||
@ -59,7 +59,7 @@ bool Plane::parachute_manual_release()
|
|||||||
// if we get this far release parachute
|
// if we get this far release parachute
|
||||||
parachute_release();
|
parachute_release();
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
// deploy landing gear
|
// deploy landing gear
|
||||||
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
|
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
|
||||||
#endif
|
#endif
|
||||||
|
@ -3325,7 +3325,7 @@ bool QuadPlane::verify_vtol_land(void)
|
|||||||
#if AP_FENCE_ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
plane.fence.auto_disable_fence_for_landing();
|
plane.fence.auto_disable_fence_for_landing();
|
||||||
#endif
|
#endif
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
plane.g2.landing_gear.deploy_for_landing();
|
plane.g2.landing_gear.deploy_for_landing();
|
||||||
#endif
|
#endif
|
||||||
last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
||||||
|
@ -691,7 +691,7 @@ void Plane::set_servos_flaps(void)
|
|||||||
flaperon_update();
|
flaperon_update();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
/*
|
/*
|
||||||
setup landing gear state
|
setup landing gear state
|
||||||
*/
|
*/
|
||||||
@ -711,7 +711,7 @@ void Plane::set_landing_gear(void)
|
|||||||
}
|
}
|
||||||
gear.last_flight_stage = flight_stage;
|
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
|
// setup flap outputs
|
||||||
set_servos_flaps();
|
set_servos_flaps();
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
// setup landing gear output
|
// setup landing gear output
|
||||||
set_landing_gear();
|
set_landing_gear();
|
||||||
#endif
|
#endif
|
||||||
|
@ -101,7 +101,7 @@ void Plane::init_ardupilot()
|
|||||||
camera_mount.init();
|
camera_mount.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
// initialise landing gear position
|
// initialise landing gear position
|
||||||
g2.landing_gear.init();
|
g2.landing_gear.init();
|
||||||
#endif
|
#endif
|
||||||
|
@ -274,7 +274,7 @@ return_zero:
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if LANDING_GEAR_ENABLED == ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
/*
|
/*
|
||||||
update landing gear
|
update landing gear
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user