mirror of https://github.com/ArduPilot/ardupilot
AP_LandingGear: Remove relay control from library.
This commit is contained in:
parent
4935a42054
commit
4177852d89
|
@ -10,13 +10,6 @@ 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
|
||||
|
@ -24,7 +17,7 @@ const AP_Param::GroupInfo AP_LandingGear::var_info[] PROGMEM = {
|
|||
// @Units: pwm
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SERVO_RTRACT", 1, AP_LandingGear, _servo_retract_pwm, AP_LANDINGGEAR_SERVO_RETRACT_PWM_DEFAULT),
|
||||
AP_GROUPINFO("SERVO_RTRACT", 0, AP_LandingGear, _servo_retract_pwm, AP_LANDINGGEAR_SERVO_RETRACT_PWM_DEFAULT),
|
||||
|
||||
// @Param: SERVO_DEPLOY
|
||||
// @DisplayName: Landing Gear Servo Deployed PWM Value
|
||||
|
@ -33,7 +26,7 @@ const AP_Param::GroupInfo AP_LandingGear::var_info[] PROGMEM = {
|
|||
// @Units: pwm
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SERVO_DEPLOY", 2, AP_LandingGear, _servo_deploy_pwm, AP_LANDINGGEAR_SERVO_DEPLOY_PWM_DEFAULT),
|
||||
AP_GROUPINFO("SERVO_DEPLOY", 1, AP_LandingGear, _servo_deploy_pwm, AP_LANDINGGEAR_SERVO_DEPLOY_PWM_DEFAULT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -47,13 +40,9 @@ void AP_LandingGear::enable(bool on_off)
|
|||
/// deploy - deploy landing gear
|
||||
void AP_LandingGear::deploy()
|
||||
{
|
||||
if (_control_type == AP_LANDINGGEAR_TRIGGER_TYPE_SERVO) {
|
||||
// move servo to deployed position
|
||||
// set servo PWM 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;
|
||||
}
|
||||
|
@ -61,13 +50,9 @@ void AP_LandingGear::deploy()
|
|||
/// retract - retract landing gear
|
||||
void AP_LandingGear::retract()
|
||||
{
|
||||
if (_control_type == AP_LANDINGGEAR_TRIGGER_TYPE_SERVO) {
|
||||
// move servo to retracted position
|
||||
// set servo PWM 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;
|
||||
}
|
||||
|
|
|
@ -8,13 +8,6 @@
|
|||
|
||||
#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
|
||||
|
@ -30,8 +23,7 @@ class AP_LandingGear {
|
|||
public:
|
||||
|
||||
/// Constructor
|
||||
AP_LandingGear(AP_Relay& relay) :
|
||||
_relay(relay),
|
||||
AP_LandingGear() :
|
||||
_deployed(false),
|
||||
_retract_enabled(false)
|
||||
{
|
||||
|
@ -57,12 +49,10 @@ 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
|
||||
|
||||
|
|
Loading…
Reference in New Issue