mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_LandingGear: use SERVO_MIN/MAX/REVERSED for landing gear
This commit is contained in:
parent
144e1945c6
commit
ac920633af
@ -10,23 +10,7 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
const AP_Param::GroupInfo AP_LandingGear::var_info[] = {
|
const AP_Param::GroupInfo AP_LandingGear::var_info[] = {
|
||||||
|
|
||||||
// @Param: SERVO_RTRACT
|
// 0 and 1 used by previous retract and deploy pwm, now replaced with SERVOn_MIN/MAX/REVERSED
|
||||||
// @DisplayName: Landing Gear Servo Retracted PWM Value
|
|
||||||
// @Description: Servo PWM value in microseconds when landing gear is retracted
|
|
||||||
// @Range: 1000 2000
|
|
||||||
// @Units: PWM
|
|
||||||
// @Increment: 1
|
|
||||||
// @User: Standard
|
|
||||||
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
|
|
||||||
// @Description: Servo PWM value in microseconds when landing gear is deployed
|
|
||||||
// @Range: 1000 2000
|
|
||||||
// @Units: PWM
|
|
||||||
// @Increment: 1
|
|
||||||
// @User: Standard
|
|
||||||
AP_GROUPINFO("SERVO_DEPLOY", 1, AP_LandingGear, _servo_deploy_pwm, AP_LANDINGGEAR_SERVO_DEPLOY_PWM_DEFAULT),
|
|
||||||
|
|
||||||
// @Param: STARTUP
|
// @Param: STARTUP
|
||||||
// @DisplayName: Landing Gear Startup position
|
// @DisplayName: Landing Gear Startup position
|
||||||
@ -136,7 +120,7 @@ void AP_LandingGear::set_position(LandingGearCommand cmd)
|
|||||||
void AP_LandingGear::deploy()
|
void AP_LandingGear::deploy()
|
||||||
{
|
{
|
||||||
// set servo PWM to deployed position
|
// set servo PWM to deployed position
|
||||||
SRV_Channels::set_output_pwm(SRV_Channel::k_landing_gear_control, _servo_deploy_pwm);
|
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
|
||||||
|
|
||||||
// set deployed flag
|
// set deployed flag
|
||||||
_deployed = true;
|
_deployed = true;
|
||||||
@ -149,7 +133,7 @@ void AP_LandingGear::deploy()
|
|||||||
void AP_LandingGear::retract()
|
void AP_LandingGear::retract()
|
||||||
{
|
{
|
||||||
// set servo PWM to retracted position
|
// set servo PWM to retracted position
|
||||||
SRV_Channels::set_output_pwm(SRV_Channel::k_landing_gear_control, _servo_retract_pwm);
|
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||||
|
|
||||||
// reset deployed flag
|
// reset deployed flag
|
||||||
_deployed = false;
|
_deployed = false;
|
||||||
|
@ -5,9 +5,6 @@
|
|||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
|
|
||||||
#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
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
#define DEFAULT_PIN_WOW 8
|
#define DEFAULT_PIN_WOW 8
|
||||||
#define DEFAULT_PIN_WOW_POL 1
|
#define DEFAULT_PIN_WOW_POL 1
|
||||||
@ -88,8 +85,6 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
// Parameters
|
// 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
|
|
||||||
AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
|
AP_Int8 _startup_behaviour; // start-up behaviour (see LandingGearStartupBehaviour)
|
||||||
|
|
||||||
AP_Int8 _pin_deployed;
|
AP_Int8 _pin_deployed;
|
||||||
|
Loading…
Reference in New Issue
Block a user