ardupilot/libraries/AC_PrecLand/AC_PrecLand_IRLock.h

51 lines
1.5 KiB
C++

#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AC_PrecLand/AC_PrecLand_Backend.h>
#include <AP_IRLock/AP_IRLock.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_IRLock/AP_IRLock_SITL.h>
#endif
// this only builds for PX4 so far
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL
/*
* 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();
private:
AP_IRLock_I2C 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