APM:Libraries
AC_PrecLand_SITL_Gazebo.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>
8 
9 /*
10  * AC_PrecLand_SITL_Gazebo - implements precision landing using target
11  * vectors provided Gazebo via a network socket
12  */
13 
15 {
16 public:
17 
18  // Constructor
20 
21  // perform any required initialisation of backend
22  void init() override;
23 
24  // retrieve updates from sensor
25  void update() override;
26 
27  // provides a unit vector towards the target in body frame
28  // returns same as have_los_meas()
29  bool get_los_body(Vector3f& ret) override;
30 
31  // returns system time in milliseconds of last los measurement
32  uint32_t los_meas_time_ms() override;
33 
34  // return true if there is a valid los measurement available
35  bool have_los_meas() override;
36 
37 private:
39 
40  Vector3f _los_meas_body; // unit vector in body frame pointing towards target
41  bool _have_los_meas; // true if there is a valid measurement from the camera
42  uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured
43 };
44 
45 #endif
AC_PrecLand_SITL_Gazebo(const AC_PrecLand &frontend, AC_PrecLand::precland_state &state)
bool get_los_body(Vector3f &ret) override
static int state
Definition: Util.cpp:20
Common definitions and utility routines for the ArduPilot libraries.
uint32_t los_meas_time_ms() override