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