AP_LandingGear: Create LandingGear Library.

This commit is contained in:
Robert Lefebvre 2015-01-05 23:24:05 -05:00 committed by Randy Mackay
parent 1b3c3c754d
commit 9b0a33c453
2 changed files with 172 additions and 0 deletions

View File

@ -0,0 +1,93 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_LandingGear.h>
#include <AP_Relay.h>
#include <AP_Math.h>
#include <RC_Channel.h>
#include <AP_HAL.h>
extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_LandingGear::var_info[] PROGMEM = {
// @Param: CTL_TYPE
// @DisplayName: Landing Gear Control Method(relay or servo)
// @Description: Type of signal used to control the landing gear system
// @Values: 0:First Relay,1:Second Relay,2:Third Relay,3:Fourth Relay,10:Servo
// @User: Standard
AP_GROUPINFO("CTL_TYPE", 0, AP_LandingGear, _control_type, AP_LANDINGGEAR_TRIGGER_TYPE_SERVO),
// @Param: SERVO_RTRACT
// @DisplayName: Landing Gear Servo Retracted PWM Value
// @Description: Servo PWM value when landing gear is retracted
// @Range: 1000 2000
// @Units: pwm
// @Increment: 1
// @User: Standard
AP_GROUPINFO("SERVO_RTRACT", 1, AP_LandingGear, _servo_retract_pwm, AP_LANDINGGEAR_SERVO_RETRACT_PWM_DEFAULT),
// @Param: SERVO_DEPLOY
// @DisplayName: Landing Gear Servo Deployed PWM Value
// @Description: Servo PWM value when landing gear is deployed
// @Range: 1000 2000
// @Units: pwm
// @Increment: 1
// @User: Standard
AP_GROUPINFO("SERVO_DEPLOY", 2, AP_LandingGear, _servo_deploy_pwm, AP_LANDINGGEAR_SERVO_DEPLOY_PWM_DEFAULT),
AP_GROUPEND
};
/// enable - enable or disable land gear retraction
void AP_LandingGear::enable(bool on_off)
{
_retract_enabled = on_off;
}
/// deploy - deploy landing gear
void AP_LandingGear::deploy()
{
if (_control_type == AP_LANDINGGEAR_TRIGGER_TYPE_SERVO) {
// move servo to deployed position
RC_Channel_aux::set_radio(RC_Channel_aux::k_landing_gear_control, _servo_deploy_pwm);
}else if (_control_type <= AP_LANDINGGEAR_TRIGGER_TYPE_RELAY_3) {
// set relay off
_relay.off(_control_type);
}
// set deployed flag
_deployed = true;
}
/// retract - retract landing gear
void AP_LandingGear::retract()
{
if (_control_type == AP_LANDINGGEAR_TRIGGER_TYPE_SERVO) {
// move servo to retracted position
RC_Channel_aux::set_radio(RC_Channel_aux::k_landing_gear_control, _servo_retract_pwm);
}else if (_control_type <= AP_LANDINGGEAR_TRIGGER_TYPE_RELAY_3) {
// set relay on
_relay.on(_control_type);
}
// reset deployed flag
_deployed = false;
}
/// update - should be called at 10hz
void AP_LandingGear::update()
{
if (!_retract_enabled) {
// force deployment if retract is not enabled
deploy();
// retract is disabled until switch is placed into deploy position to prevent accidental retraction on bootup if switch was left in retract position
enable(_command_mode == COMMAND_MODE_DEPLOY);
return;
}
if (_command_mode == COMMAND_MODE_DEPLOY){
deploy();
}
if (_command_mode == COMMAND_MODE_RETRACT){
retract();
}
}

View File

@ -0,0 +1,79 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/// @file AP_LandingGear.h
/// @brief Landing gear control library
#ifndef AP_LANDINGGEAR_H
#define AP_LANDINGGEAR_H
#include <AP_Param.h>
#include <AP_Common.h>
#include <AP_Relay.h>
#define AP_LANDINGGEAR_TRIGGER_TYPE_RELAY_0 0
#define AP_LANDINGGEAR_TRIGGER_TYPE_RELAY_1 1
#define AP_LANDINGGEAR_TRIGGER_TYPE_RELAY_2 2
#define AP_LANDINGGEAR_TRIGGER_TYPE_RELAY_3 3
#define AP_LANDINGGEAR_TRIGGER_TYPE_SERVO 10
#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
#define COMMAND_MODE_DEPLOY 0 // command gear to deploy
#define COMMAND_MODE_AUTO 1 // command gear to actuate automatically
#define COMMAND_MODE_RETRACT 2 // command gear to retract
/// @class AP_LandingGear
/// @brief Class managing the control of landing gear
class AP_LandingGear {
public:
/// Constructor
AP_LandingGear(AP_Relay& relay) :
_relay(relay),
_deployed(false),
_retract_enabled(false)
{
// setup parameter defaults
AP_Param::setup_object_defaults(this, var_info);
}
/// enabled - returns true if landing gear retract is enabled
bool enabled() const { return _retract_enabled; }
/// deployed - returns true if the landing gear is deployed
bool deployed() const { return _deployed; }
/// update - should be called at 10hz
void update();
void set_cmd_mode(int8_t cmd) { _command_mode = cmd; }
static const struct AP_Param::GroupInfo var_info[];
private:
bool _retract_enabled; // true if landing gear retraction is enabled
// Parameters
AP_Int8 _control_type; // 0,1,2,3:Relay 10:Servo
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
// internal variables
AP_Relay &_relay; // pointer to relay object from the base class Relay.
bool _deployed; // true if the landing gear has been deployed, initialized false
int8_t _command_mode; // pilots commanded control mode: Manual Deploy, Auto, or Manual Retract
/// enable - enable landing gear retraction
void enable(bool on_off);
/// retract - retract landing gear
void retract();
/// deploy - deploy the landing gear
void deploy();
};
#endif /* AP_LANDINGGEAR_H */