AC_PrecLand_Companion.h 1.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748
  1. #pragma once
  2. #include <AP_Math/AP_Math.h>
  3. #include "AC_PrecLand_Backend.h"
  4. /*
  5. * AC_PrecLand_Companion - implements precision landing using target vectors provided
  6. * by a companion computer (i.e. Odroid) communicating via MAVLink
  7. * The companion computer must provide "Line-Of-Sight" measurements
  8. * in the form of LANDING_TARGET mavlink messages.
  9. */
  10. class AC_PrecLand_Companion : public AC_PrecLand_Backend
  11. {
  12. public:
  13. // Constructor
  14. using AC_PrecLand_Backend::AC_PrecLand_Backend;
  15. // perform any required initialisation of backend
  16. void init() override;
  17. // retrieve updates from sensor
  18. void update() override;
  19. // provides a unit vector towards the target in body frame
  20. // returns same as have_los_meas()
  21. bool get_los_body(Vector3f& ret) override;
  22. // returns system time in milliseconds of last los measurement
  23. uint32_t los_meas_time_ms() override;
  24. // return true if there is a valid los measurement available
  25. bool have_los_meas() override;
  26. // returns distance to target in meters (0 means distance is not known)
  27. float distance_to_target() override;
  28. // parses a mavlink message from the companion computer
  29. void handle_msg(const mavlink_message_t &msg) override;
  30. private:
  31. uint64_t _timestamp_us; // timestamp from message
  32. float _distance_to_target; // distance from the camera to target in meters
  33. Vector3f _los_meas_body; // unit vector in body frame pointing towards target
  34. bool _have_los_meas; // true if there is a valid measurement from the camera
  35. uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured
  36. };