AC_PrecLand_IRLock.cpp 1.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AC_PrecLand_IRLock.h"
  3. // Constructor
  4. AC_PrecLand_IRLock::AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state)
  5. : AC_PrecLand_Backend(frontend, state),
  6. irlock()
  7. {
  8. }
  9. // init - perform initialisation of this backend
  10. void AC_PrecLand_IRLock::init()
  11. {
  12. irlock.init(get_bus());
  13. }
  14. // update - give chance to driver to get updates from sensor
  15. void AC_PrecLand_IRLock::update()
  16. {
  17. // update health
  18. _state.healthy = irlock.healthy();
  19. // get new sensor data
  20. irlock.update();
  21. if (irlock.num_targets() > 0 && irlock.last_update_ms() != _los_meas_time_ms) {
  22. irlock.get_unit_vector_body(_los_meas_body);
  23. _have_los_meas = true;
  24. _los_meas_time_ms = irlock.last_update_ms();
  25. }
  26. _have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000;
  27. }
  28. // provides a unit vector towards the target in body frame
  29. // returns same as have_los_meas()
  30. bool AC_PrecLand_IRLock::get_los_body(Vector3f& ret) {
  31. if (have_los_meas()) {
  32. ret = _los_meas_body;
  33. return true;
  34. }
  35. return false;
  36. }
  37. // returns system time in milliseconds of last los measurement
  38. uint32_t AC_PrecLand_IRLock::los_meas_time_ms() {
  39. return _los_meas_time_ms;
  40. }
  41. // return true if there is a valid los measurement available
  42. bool AC_PrecLand_IRLock::have_los_meas() {
  43. return _have_los_meas;
  44. }