APM:Libraries
AP_LandingGear.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Param/AP_Param.h>
6 #include <AP_Common/AP_Common.h>
7 
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
10 
14 public:
16  // setup parameter defaults
18  }
19 
20  /* Do not allow copies */
21  AP_LandingGear(const AP_LandingGear &other) = delete;
22  AP_LandingGear &operator=(const AP_LandingGear&) = delete;
23 
24  // Gear command modes
29  };
30 
31  // Gear command modes
36  };
37 
39  void init();
40 
42  bool deployed() const { return _deployed; }
43 
46 
47  static const struct AP_Param::GroupInfo var_info[];
48 
49 private:
50  // Parameters
51  AP_Int16 _servo_retract_pwm; // PWM value to move servo to when gear is retracted
52  AP_Int16 _servo_deploy_pwm; // PWM value to move servo to when gear is deployed
53  AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
54 
55  // internal variables
56  bool _deployed; // true if the landing gear has been deployed, initialized false
57  bool _deploy_lock; // used to force landing gear to remain deployed until another regular Deploy command is received to reduce accidental retraction
58 
60  void retract();
61 
63  void deploy();
64 };
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
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)
Definition: AP_Param.cpp:1214