AC_PrecLand_IRLock.h 1.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748
  1. #pragma once
  2. #include <AP_Math/AP_Math.h>
  3. #include <AC_PrecLand/AC_PrecLand_Backend.h>
  4. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  5. #include <AP_IRLock/AP_IRLock_SITL.h>
  6. #else
  7. #include <AP_IRLock/AP_IRLock.h>
  8. #endif
  9. /*
  10. * AC_PrecLand_IRLock - implements precision landing using target vectors provided
  11. * by a companion computer (i.e. Odroid) communicating via MAVLink
  12. */
  13. class AC_PrecLand_IRLock : public AC_PrecLand_Backend
  14. {
  15. public:
  16. // Constructor
  17. AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state);
  18. // perform any required initialisation of backend
  19. void init() override;
  20. // retrieve updates from sensor
  21. void update() override;
  22. // provides a unit vector towards the target in body frame
  23. // returns same as have_los_meas()
  24. bool get_los_body(Vector3f& ret) override;
  25. // returns system time in milliseconds of last los measurement
  26. uint32_t los_meas_time_ms() override;
  27. // return true if there is a valid los measurement available
  28. bool have_los_meas() override;
  29. private:
  30. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  31. AP_IRLock_SITL irlock;
  32. #else
  33. AP_IRLock_I2C irlock;
  34. #endif
  35. Vector3f _los_meas_body; // unit vector in body frame pointing towards target
  36. bool _have_los_meas; // true if there is a valid measurement from the camera
  37. uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured
  38. };