APM:Libraries
AC_PrecLand_SITL.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AC_PrecLand_SITL.h"
3 
4 extern const AP_HAL::HAL& hal;
5 
6 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
7 
8 #include <stdio.h>
9 
10 // Constructor
12  : AC_PrecLand_Backend(frontend, state)
13 {
14 }
15 
16 // init - perform initialisation of this backend
18 {
19 }
20 
21 // update - give chance to driver to get updates from sensor
23 {
24  const uint32_t now = AP_HAL::millis();
25  if (_los_meas_time_ms + 10 > now) { // 100Hz update
26  return;
27  }
28 
29  // get new sensor data; we always point home
30  Vector3f home;
32  _state.healthy = false;
33  return;
34  }
35  if (home.length() > 10.0f) { // we can see the target out to 10 metres
36  return;
37  }
38  _state.healthy = true;
39 
40  const Matrix3f &body_to_ned = _frontend._ahrs.get_rotation_body_to_ned();
41 
42  _los_meas_body = body_to_ned.mul_transpose(-home);
44  _los_meas_time_ms = now;
45 }
46 
48  return AP_HAL::millis() - _los_meas_time_ms < 1000;
49 }
50 
51 
52 // provides a unit vector towards the target in body frame
53 // returns same as have_los_meas()
55  if (AP_HAL::millis() - _los_meas_time_ms > 1000) {
56  // no measurement for a full second; no vector available
57  return false;
58  }
59  ret = _los_meas_body;
60  return true;
61 }
62 
63 #endif
void init() override
const AC_PrecLand & _frontend
AC_PrecLand_SITL(const AC_PrecLand &frontend, AC_PrecLand::precland_state &state)
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool get_relative_position_NED_home(Vector3f &vec) const override
bool get_los_body(Vector3f &ret) override
uint32_t _los_meas_time_ms
void update() override
uint32_t millis()
Definition: system.cpp:157
static int state
Definition: Util.cpp:20
float length(void) const
Definition: vector3.cpp:288
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
AC_PrecLand::precland_state & _state
bool have_los_meas() override
const AP_AHRS_NavEKF & _ahrs
Definition: AC_PrecLand.h:106
const Matrix3f & get_rotation_body_to_ned(void) const override