AC_PrecLand_Companion.cpp 1.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AC_PrecLand_Companion.h"
  3. // perform any required initialisation of backend
  4. void AC_PrecLand_Companion::init()
  5. {
  6. // set healthy
  7. _state.healthy = true;
  8. _have_los_meas = false;
  9. }
  10. // retrieve updates from sensor
  11. void AC_PrecLand_Companion::update()
  12. {
  13. _have_los_meas = _have_los_meas && AP_HAL::millis()-_los_meas_time_ms <= 1000;
  14. }
  15. // provides a unit vector towards the target in body frame
  16. // returns same as have_los_meas()
  17. bool AC_PrecLand_Companion::get_los_body(Vector3f& ret) {
  18. if (have_los_meas()) {
  19. ret = _los_meas_body;
  20. return true;
  21. }
  22. return false;
  23. }
  24. // returns system time in milliseconds of last los measurement
  25. uint32_t AC_PrecLand_Companion::los_meas_time_ms() {
  26. return _los_meas_time_ms;
  27. }
  28. // return true if there is a valid los measurement available
  29. bool AC_PrecLand_Companion::have_los_meas()
  30. {
  31. return _have_los_meas;
  32. }
  33. // return distance to target
  34. float AC_PrecLand_Companion::distance_to_target()
  35. {
  36. return _distance_to_target;
  37. }
  38. void AC_PrecLand_Companion::handle_msg(const mavlink_message_t &msg)
  39. {
  40. // parse mavlink message
  41. __mavlink_landing_target_t packet;
  42. mavlink_msg_landing_target_decode(&msg, &packet);
  43. _timestamp_us = packet.time_usec;
  44. _distance_to_target = packet.distance;
  45. // compute unit vector towards target
  46. _los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f);
  47. _los_meas_body /= _los_meas_body.length();
  48. _los_meas_time_ms = AP_HAL::millis();
  49. _have_los_meas = true;
  50. }