8 #define AP_LANDINGGEAR_SERVO_RETRACT_PWM_DEFAULT 1250 // default PWM value to move servo to when landing gear is up 9 #define AP_LANDINGGEAR_SERVO_DEPLOY_PWM_DEFAULT 1750 // default PWM value to move servo to when landing gear is down AP_Int16 _servo_retract_pwm
void init()
initialise state of landing gear
void retract()
retract - retract landing gear
Class managing the control of landing gear.
A system for managing and storing variables that are of general interest to the system.
AP_LandingGear & operator=(const AP_LandingGear &)=delete
void deploy()
deploy - deploy the landing gear
static const struct AP_Param::GroupInfo var_info[]
AP_Int8 _startup_behaviour
LandingGearStartupBehaviour
Common definitions and utility routines for the ArduPilot libraries.
AP_Int16 _servo_deploy_pwm
void set_position(LandingGearCommand cmd)
set landing gear position to retract, deploy or deploy-and-keep-deployed
bool deployed() const
returns true if the landing gear is deployed
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)