2016-02-17 21:25:09 -04:00
|
|
|
#pragma once
|
2015-02-16 00:37:13 -04:00
|
|
|
|
2015-08-28 05:11:52 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include "AC_PrecLand_Backend.h"
|
2015-02-16 00:37:13 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
* AC_PrecLand_Companion - implements precision landing using target vectors provided
|
|
|
|
* by a companion computer (i.e. Odroid) communicating via MAVLink
|
2019-02-04 14:10:57 -04:00
|
|
|
* The companion computer must provide "Line-Of-Sight" measurements
|
|
|
|
* in the form of LANDING_TARGET mavlink messages.
|
2015-02-16 00:37:13 -04:00
|
|
|
*/
|
|
|
|
|
|
|
|
class AC_PrecLand_Companion : public AC_PrecLand_Backend
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
// Constructor
|
2018-07-15 21:29:20 -03:00
|
|
|
using AC_PrecLand_Backend::AC_PrecLand_Backend;
|
2017-02-03 03:01:03 -04:00
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// perform any required initialisation of backend
|
2017-02-03 03:01:03 -04:00
|
|
|
void init() override;
|
2015-02-16 00:37:13 -04:00
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// retrieve updates from sensor
|
2017-02-03 03:01:03 -04:00
|
|
|
void update() override;
|
2016-07-05 16:37:17 -03:00
|
|
|
|
|
|
|
// provides a unit vector towards the target in body frame
|
|
|
|
// returns same as have_los_meas()
|
2017-02-03 03:01:03 -04:00
|
|
|
bool get_los_body(Vector3f& ret) override;
|
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// returns system time in milliseconds of last los measurement
|
2017-02-03 03:01:03 -04:00
|
|
|
uint32_t los_meas_time_ms() override;
|
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// return true if there is a valid los measurement available
|
2017-02-03 03:01:03 -04:00
|
|
|
bool have_los_meas() override;
|
|
|
|
|
2017-02-03 03:03:02 -04:00
|
|
|
// returns distance to target in meters (0 means distance is not known)
|
|
|
|
float distance_to_target() override;
|
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
// parses a mavlink message from the companion computer
|
2021-04-12 23:49:59 -03:00
|
|
|
void handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
|
2015-02-16 00:37:13 -04:00
|
|
|
|
2015-09-11 08:00:18 -03:00
|
|
|
private:
|
|
|
|
float _distance_to_target; // distance from the camera to target in meters
|
2017-02-03 03:01:03 -04:00
|
|
|
|
2016-07-05 16:37:17 -03:00
|
|
|
Vector3f _los_meas_body; // unit vector in body frame pointing towards target
|
|
|
|
bool _have_los_meas; // true if there is a valid measurement from the camera
|
|
|
|
uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured
|
2022-07-30 06:54:25 -03:00
|
|
|
bool _wrong_frame_msg_sent;
|
2015-02-16 00:37:13 -04:00
|
|
|
};
|