APM:Libraries
AC_PrecLand_IRLock.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AC_PrecLand_IRLock.h"
3 
4 extern const AP_HAL::HAL& hal;
5 
6 // Constructor
8  : AC_PrecLand_Backend(frontend, state),
9  irlock(),
10  _have_los_meas(false),
11  _los_meas_time_ms(0)
12 {
13 }
14 
15 // init - perform initialisation of this backend
17 {
18  irlock.init(get_bus());
19 }
20 
21 // update - give chance to driver to get updates from sensor
23 {
24  // update health
26 
27  // get new sensor data
28  irlock.update();
29 
32  _have_los_meas = true;
34  }
36 }
37 
38 // provides a unit vector towards the target in body frame
39 // returns same as have_los_meas()
41  if (have_los_meas()) {
42  ret = _los_meas_body;
43  return true;
44  }
45  return false;
46 }
47 
48 // returns system time in milliseconds of last los measurement
50  return _los_meas_time_ms;
51 }
52 
53 // return true if there is a valid los measurement available
55  return _have_los_meas;
56 }
uint32_t last_update_ms() const
Definition: IRLock.h:37
bool get_unit_vector_body(Vector3f &ret) const
Definition: IRLock.cpp:27
bool update() override
AC_PrecLand_IRLock(const AC_PrecLand &frontend, AC_PrecLand::precland_state &state)
bool get_los_body(Vector3f &ret) override
size_t num_targets() const
Definition: IRLock.h:40
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint32_t millis()
Definition: system.cpp:157
void init(int8_t bus) override
uint32_t los_meas_time_ms() override
static int state
Definition: Util.cpp:20
int8_t get_bus(void) const
AC_PrecLand::precland_state & _state
bool healthy() const
Definition: IRLock.h:34
void update() override
bool have_los_meas() override