ardupilot/libraries/AC_PrecLand/AC_PrecLand_IRLock.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

56 lines
1.6 KiB
C
Raw Normal View History

#pragma once
#include "AC_PrecLand_config.h"
#if AC_PRECLAND_IRLOCK_ENABLED
2015-08-28 05:11:52 -03:00
#include <AC_PrecLand/AC_PrecLand_Backend.h>
#include <AP_Math/AP_Math.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_IRLock/AP_IRLock_SITL.h>
#else
#include <AP_IRLock/AP_IRLock.h>
#endif
/*
* 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() override;
// retrieve updates from sensor
void update() override;
// provides a unit vector towards the target in body frame
// returns same as have_los_meas()
bool get_los_body(Vector3f& ret) override;
// returns system time in milliseconds of last los measurement
uint32_t los_meas_time_ms() override { return _los_meas_time_ms; }
// return true if there is a valid los measurement available
bool have_los_meas() override { return _have_los_meas; }
private:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
AP_IRLock_SITL irlock;
#else
AP_IRLock_I2C irlock;
#endif
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 // AC_PRECLAND_IRLOCK_ENABLED