APM:Libraries
AC_PrecLand_Companion.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>
5 #include "AC_PrecLand_Backend.h"
6 
7 /*
8  * AC_PrecLand_Companion - implements precision landing using target vectors provided
9  * by a companion computer (i.e. Odroid) communicating via MAVLink
10  */
11 
13 {
14 public:
15  // Constructor
17 
18  // perform any required initialisation of backend
19  void init() override;
20 
21  // retrieve updates from sensor
22  void update() override;
23 
24  // provides a unit vector towards the target in body frame
25  // returns same as have_los_meas()
26  bool get_los_body(Vector3f& ret) override;
27 
28  // returns system time in milliseconds of last los measurement
29  uint32_t los_meas_time_ms() override;
30 
31  // return true if there is a valid los measurement available
32  bool have_los_meas() override;
33 
34  // returns distance to target in meters (0 means distance is not known)
35  float distance_to_target() override;
36 
37  // parses a mavlink message from the companion computer
38  void handle_msg(mavlink_message_t* msg) override;
39 
40 private:
41  uint64_t _timestamp_us; // timestamp from message
42  float _distance_to_target; // distance from the camera to target in meters
43 
44  Vector3f _los_meas_body; // unit vector in body frame pointing towards target
45  bool _have_los_meas; // true if there is a valid measurement from the camera
46  uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured
47 };
AC_PrecLand_Companion(const AC_PrecLand &frontend, AC_PrecLand::precland_state &state)
uint32_t los_meas_time_ms() override
bool get_los_body(Vector3f &ret) override
static int state
Definition: Util.cpp:20
void handle_msg(mavlink_message_t *msg) override
float distance_to_target() override
Common definitions and utility routines for the ArduPilot libraries.