AC_PrecLand_SITL.cpp 1.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AC_PrecLand_SITL.h"
  3. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  4. #include "AP_AHRS/AP_AHRS.h"
  5. // init - perform initialisation of this backend
  6. void AC_PrecLand_SITL::init()
  7. {
  8. _sitl = AP::sitl();
  9. }
  10. // update - give chance to driver to get updates from sensor
  11. void AC_PrecLand_SITL::update()
  12. {
  13. _state.healthy = _sitl->precland_sim.healthy();
  14. if (_state.healthy && _sitl->precland_sim.last_update_ms() != _los_meas_time_ms) {
  15. const Vector3f position = _sitl->precland_sim.get_target_position();
  16. const Matrix3f &body_to_ned = AP::ahrs().get_rotation_body_to_ned();
  17. _los_meas_body = body_to_ned.mul_transpose(-position);
  18. _los_meas_body /= _los_meas_body.length();
  19. _have_los_meas = true;
  20. _los_meas_time_ms = _sitl->precland_sim.last_update_ms();
  21. } else {
  22. _have_los_meas = false;
  23. }
  24. _have_los_meas = _have_los_meas && AP_HAL::millis() - _los_meas_time_ms <= 1000;
  25. }
  26. bool AC_PrecLand_SITL::have_los_meas() {
  27. return AP_HAL::millis() - _los_meas_time_ms < 1000;
  28. }
  29. // provides a unit vector towards the target in body frame
  30. // returns same as have_los_meas()
  31. bool AC_PrecLand_SITL::get_los_body(Vector3f& ret) {
  32. if (AP_HAL::millis() - _los_meas_time_ms > 1000) {
  33. // no measurement for a full second; no vector available
  34. return false;
  35. }
  36. ret = _los_meas_body;
  37. return true;
  38. }
  39. #endif