APM:Libraries
AC_PrecLand_IRLock.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Math/AP_Math.h>
6 #include <AP_IRLock/AP_IRLock.h>
7 
8 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
10 #endif
11 
12 /*
13  * AC_PrecLand_IRLock - implements precision landing using target vectors provided
14  * by a companion computer (i.e. Odroid) communicating via MAVLink
15  */
16 
18 {
19 public:
20 
21  // Constructor
23 
24  // perform any required initialisation of backend
25  void init() override;
26 
27  // retrieve updates from sensor
28  void update() override;
29 
30  // provides a unit vector towards the target in body frame
31  // returns same as have_los_meas()
32  bool get_los_body(Vector3f& ret) override;
33 
34  // returns system time in milliseconds of last los measurement
35  uint32_t los_meas_time_ms() override;
36 
37  // return true if there is a valid los measurement available
38  bool have_los_meas() override;
39 
40 private:
42 
43  Vector3f _los_meas_body; // unit vector in body frame pointing towards target
44  bool _have_los_meas; // true if there is a valid measurement from the camera
45  uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured
46 };
AC_PrecLand_IRLock(const AC_PrecLand &frontend, AC_PrecLand::precland_state &state)
bool get_los_body(Vector3f &ret) override
uint32_t los_meas_time_ms() override
static int state
Definition: Util.cpp:20
Common definitions and utility routines for the ArduPilot libraries.
void update() override
bool have_los_meas() override