Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp
9552 views
1
#include "AC_PrecLand_config.h"
2
3
#if AC_PRECLAND_IRLOCK_ENABLED
4
5
#include "AC_PrecLand_IRLock.h"
6
#include <AP_HAL/AP_HAL.h>
7
8
// Constructor
9
AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state)
10
: AC_PrecLand_Backend(frontend, state),
11
irlock()
12
{
13
}
14
15
// init - perform initialisation of this backend
16
void AC_PrecLand_IRLock::init()
17
{
18
irlock.init(get_bus());
19
}
20
21
// update - give chance to driver to get updates from sensor
22
void AC_PrecLand_IRLock::update()
23
{
24
// update health
25
_state.healthy = irlock.healthy();
26
27
// get new sensor data
28
irlock.update();
29
30
if (irlock.num_targets() > 0 && irlock.last_update_ms() != _los_meas.time_ms) {
31
irlock.get_unit_vector_body(_los_meas.vec_unit);
32
_los_meas.frame = AC_PrecLand::VectorFrame::BODY_FRD;
33
_los_meas.valid = true;
34
_los_meas.time_ms = irlock.last_update_ms();
35
}
36
_los_meas.valid = _los_meas.valid && AP_HAL::millis() - _los_meas.time_ms <= 1000;
37
}
38
39
#endif // AC_PRECLAND_IRLOCK_ENABLED
40
41