2015-01-06 00:24:05 -04:00
|
|
|
/// @file AP_LandingGear.h
|
|
|
|
/// @brief Landing gear control library
|
2016-02-17 21:25:32 -04:00
|
|
|
#pragma once
|
2015-01-06 00:24:05 -04:00
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
2015-01-06 00:24:05 -04:00
|
|
|
|
|
|
|
#define AP_LANDINGGEAR_SERVO_RETRACT_PWM_DEFAULT 1250 // default PWM value to move servo to when landing gear is up
|
|
|
|
#define AP_LANDINGGEAR_SERVO_DEPLOY_PWM_DEFAULT 1750 // default PWM value to move servo to when landing gear is down
|
|
|
|
|
|
|
|
/// @class AP_LandingGear
|
|
|
|
/// @brief Class managing the control of landing gear
|
|
|
|
class AP_LandingGear {
|
|
|
|
public:
|
2017-12-12 21:06:12 -04:00
|
|
|
AP_LandingGear() {
|
|
|
|
// setup parameter defaults
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
2017-08-29 20:57:36 -03:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
|
|
|
AP_LandingGear(const AP_LandingGear &other) = delete;
|
|
|
|
AP_LandingGear &operator=(const AP_LandingGear&) = delete;
|
2015-01-06 00:24:05 -04:00
|
|
|
|
2017-06-10 01:07:38 -03:00
|
|
|
// Gear command modes
|
|
|
|
enum LandingGearCommand {
|
|
|
|
LandingGear_Retract,
|
|
|
|
LandingGear_Deploy,
|
|
|
|
};
|
|
|
|
|
2017-08-04 03:28:33 -03:00
|
|
|
// Gear command modes
|
|
|
|
enum LandingGearStartupBehaviour {
|
|
|
|
LandingGear_Startup_WaitForPilotInput = 0,
|
|
|
|
LandingGear_Startup_Retract = 1,
|
|
|
|
LandingGear_Startup_Deploy = 2,
|
|
|
|
};
|
|
|
|
|
|
|
|
/// initialise state of landing gear
|
|
|
|
void init();
|
|
|
|
|
2017-06-10 01:07:38 -03:00
|
|
|
/// returns true if the landing gear is deployed
|
2015-01-06 00:24:05 -04:00
|
|
|
bool deployed() const { return _deployed; }
|
|
|
|
|
2017-06-10 01:07:38 -03:00
|
|
|
/// set landing gear position to retract, deploy or deploy-and-keep-deployed
|
|
|
|
void set_position(LandingGearCommand cmd);
|
2015-01-06 00:24:05 -04:00
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
private:
|
|
|
|
// Parameters
|
|
|
|
AP_Int16 _servo_retract_pwm; // PWM value to move servo to when gear is retracted
|
|
|
|
AP_Int16 _servo_deploy_pwm; // PWM value to move servo to when gear is deployed
|
2017-08-04 03:28:33 -03:00
|
|
|
AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
|
2015-01-06 00:24:05 -04:00
|
|
|
|
|
|
|
// internal variables
|
|
|
|
bool _deployed; // true if the landing gear has been deployed, initialized false
|
|
|
|
|
|
|
|
/// retract - retract landing gear
|
|
|
|
void retract();
|
|
|
|
|
|
|
|
/// deploy - deploy the landing gear
|
|
|
|
void deploy();
|
|
|
|
};
|