Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/landing_gear.cpp
9593 views
1
#include "Copter.h"
2
3
#if AP_LANDINGGEAR_ENABLED
4
5
// Run landing gear controller at 10Hz
6
void Copter::landinggear_update()
7
{
8
// exit immediately if no landing gear output has been enabled
9
if (!SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) {
10
return;
11
}
12
13
// support height based triggering using rangefinder or altitude above ground
14
float height_m = flightmode->get_alt_above_ground_m();
15
16
// use rangefinder if available
17
#if AP_RANGEFINDER_ENABLED
18
switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
19
case RangeFinder::Status::NotConnected:
20
case RangeFinder::Status::NoData:
21
// use altitude above home for non-functioning rangefinder
22
break;
23
24
case RangeFinder::Status::OutOfRangeLow:
25
// altitude is close to zero (gear should deploy)
26
height_m = 0;
27
break;
28
29
case RangeFinder::Status::OutOfRangeHigh:
30
case RangeFinder::Status::Good:
31
// use last good reading
32
height_m = rangefinder_state.alt_m_filt.get();
33
break;
34
}
35
#endif // AP_RANGEFINDER_ENABLED
36
37
landinggear.update(height_m);
38
}
39
40
#endif // AP_LANDINGGEAR_ENABLED
41
42