/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include #include #include #include // this only builds for PX4 so far #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN /* * AC_PrecLand_IRLock - implements precision landing using target vectors provided * by a companion computer (i.e. Odroid) communicating via MAVLink */ class AC_PrecLand_IRLock : public AC_PrecLand_Backend { public: // Constructor AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); // perform any required initialisation of backend void init(); // retrieve updates from sensor void update(); // provides a unit vector towards the target in body frame // returns same as have_los_meas() bool get_los_body(Vector3f& ret); // returns system time in milliseconds of last los measurement uint32_t los_meas_time_ms(); // return true if there is a valid los measurement available bool have_los_meas(); // parses a mavlink message from the companion computer void handle_msg(mavlink_message_t* msg) {}; private: AP_IRLock_PX4 irlock; 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 }; #endif