AP_Beacon_Backend.h 2.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_Math/AP_Math.h>
  16. #include <AP_HAL/AP_HAL.h>
  17. #include "AP_Beacon.h"
  18. class AP_Beacon_Backend
  19. {
  20. public:
  21. // constructor. This incorporates initialisation as well.
  22. AP_Beacon_Backend(AP_Beacon &frontend);
  23. // return true if sensor is basically healthy (we are receiving data)
  24. virtual bool healthy() = 0;
  25. // update
  26. virtual void update() = 0;
  27. // set vehicle position, pos should be in the beacon's local frame
  28. void set_vehicle_position(const Vector3f& pos, float accuracy_estimate);
  29. // set individual beacon distance in meters
  30. void set_beacon_distance(uint8_t beacon_instance, float distance);
  31. // configure beacon's position in meters from origin
  32. // pos should be in the beacon's local frame
  33. void set_beacon_position(uint8_t beacon_instance, const Vector3f& pos);
  34. float get_beacon_origin_lat(void) const { return _frontend.origin_lat; }
  35. float get_beacon_origin_lon(void) const { return _frontend.origin_lon; }
  36. float get_beacon_origin_alt(void) const { return _frontend.origin_alt; }
  37. protected:
  38. // references
  39. AP_Beacon &_frontend;
  40. // yaw correction
  41. int16_t orient_yaw_deg; // cached version of orient_yaw parameter
  42. float orient_cos_yaw = 0.0f;
  43. float orient_sin_yaw = 1.0f;
  44. // yaw correction methods
  45. Vector3f correct_for_orient_yaw(const Vector3f &vector);
  46. };