APM:Libraries
AP_LandingGear.cpp
Go to the documentation of this file.
1 #include "AP_LandingGear.h"
2 #include <AP_Relay/AP_Relay.h>
3 #include <AP_Math/AP_Math.h>
5 #include <AP_HAL/AP_HAL.h>
6 
7 extern const AP_HAL::HAL& hal;
8 
10 
11  // @Param: SERVO_RTRACT
12  // @DisplayName: Landing Gear Servo Retracted PWM Value
13  // @Description: Servo PWM value in microseconds when landing gear is retracted
14  // @Range: 1000 2000
15  // @Units: PWM
16  // @Increment: 1
17  // @User: Standard
18  AP_GROUPINFO("SERVO_RTRACT", 0, AP_LandingGear, _servo_retract_pwm, AP_LANDINGGEAR_SERVO_RETRACT_PWM_DEFAULT),
19 
20  // @Param: SERVO_DEPLOY
21  // @DisplayName: Landing Gear Servo Deployed PWM Value
22  // @Description: Servo PWM value in microseconds when landing gear is deployed
23  // @Range: 1000 2000
24  // @Units: PWM
25  // @Increment: 1
26  // @User: Standard
27  AP_GROUPINFO("SERVO_DEPLOY", 1, AP_LandingGear, _servo_deploy_pwm, AP_LANDINGGEAR_SERVO_DEPLOY_PWM_DEFAULT),
28 
29  // @Param: STARTUP
30  // @DisplayName: Landing Gear Startup position
31  // @Description: Landing Gear Startup behaviour control
32  // @Values: 0:WaitForPilotInput, 1:Retract, 2:Deploy
33  // @User: Standard
34  AP_GROUPINFO("STARTUP", 2, AP_LandingGear, _startup_behaviour, (uint8_t)AP_LandingGear::LandingGear_Startup_WaitForPilotInput),
35 
37 };
38 
41 {
42  switch ((enum LandingGearStartupBehaviour)_startup_behaviour.get()) {
43  default:
45  // do nothing
46  break;
48  retract();
49  break;
51  deploy();
52  break;
53  }
54 }
55 
58 {
59  switch (cmd) {
61  if (!_deploy_lock) {
62  retract();
63  }
64  break;
65  case LandingGear_Deploy:
66  deploy();
67  _deploy_lock = false;
68  break;
70  deploy();
71  _deploy_lock = true;
72  break;
73  }
74 }
75 
78 {
79  // set servo PWM to deployed position
81 
82  // set deployed flag
83  _deployed = true;
84 }
85 
88 {
89  // set servo PWM to retracted position
91 
92  // reset deployed flag
93  _deployed = false;
94 }
Landing gear control library.
#define AP_LANDINGGEAR_SERVO_RETRACT_PWM_DEFAULT
Definition: AP_LandingGear.h:8
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.
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void deploy()
deploy - deploy the landing gear
static const struct AP_Param::GroupInfo var_info[]
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
landing gear controller
Definition: SRV_Channel.h:73
AP_Int8 _startup_behaviour
#define AP_LANDINGGEAR_SERVO_DEPLOY_PWM_DEFAULT
Definition: AP_LandingGear.h:9
AP_Int16 _servo_deploy_pwm
void set_position(LandingGearCommand cmd)
set landing gear position to retract, deploy or deploy-and-keep-deployed
#define AP_GROUPEND
Definition: AP_Param.h:121
APM relay control class.