APM:Libraries
AC_PrecLand_Companion.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
3 
4 extern const AP_HAL::HAL& hal;
5 
6 // Constructor
8  : AC_PrecLand_Backend(frontend, state),
9  _timestamp_us(0),
10  _distance_to_target(0.0f),
11  _have_los_meas(false),
12  _los_meas_time_ms(0)
13 {
14 }
15 
16 // perform any required initialisation of backend
18 {
19  // set healthy
20  _state.healthy = true;
21  _have_los_meas = false;
22 }
23 
24 // retrieve updates from sensor
26 {
28 }
29 
30 // provides a unit vector towards the target in body frame
31 // returns same as have_los_meas()
33  if (have_los_meas()) {
34  ret = _los_meas_body;
35  return true;
36  }
37  return false;
38 }
39 
40 // returns system time in milliseconds of last los measurement
42  return _los_meas_time_ms;
43 }
44 
45 // return true if there is a valid los measurement available
47 {
48  return _have_los_meas;
49 }
50 
51 // return distance to target
53 {
54  return _distance_to_target;
55 }
56 
57 void AC_PrecLand_Companion::handle_msg(mavlink_message_t* msg)
58 {
59  // parse mavlink message
60  __mavlink_landing_target_t packet;
61  mavlink_msg_landing_target_decode(msg, &packet);
62 
63  _timestamp_us = packet.time_usec;
64  _distance_to_target = packet.distance;
65 
66  // compute unit vector towards target
67  _los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f);
69 
71  _have_los_meas = true;
72 }
Vector3< float > Vector3f
Definition: vector3.h:246
AC_PrecLand_Companion(const AC_PrecLand &frontend, AC_PrecLand::precland_state &state)
#define f(i)
uint32_t los_meas_time_ms() override
bool get_los_body(Vector3f &ret) override
uint32_t millis()
Definition: system.cpp:157
static int state
Definition: Util.cpp:20
void handle_msg(mavlink_message_t *msg) override
float distance_to_target() override
float length(void) const
Definition: vector3.cpp:288
AC_PrecLand::precland_state & _state
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14