AP_Proximity_SITL.h 1.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445
  1. #pragma once
  2. #include "AP_Proximity.h"
  3. #include "AP_Proximity_Backend.h"
  4. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  5. #include <SITL/SITL.h>
  6. #include <AC_Fence/AC_PolyFence_loader.h>
  7. #include <AP_Common/Location.h>
  8. class AP_Proximity_SITL : public AP_Proximity_Backend
  9. {
  10. public:
  11. // constructor
  12. AP_Proximity_SITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
  13. // update state
  14. void update(void) override;
  15. // get maximum and minimum distances (in meters) of sensor
  16. float distance_max() const override;
  17. float distance_min() const override;
  18. // get distance upwards in meters. returns true on success
  19. bool get_upward_distance(float &distance) const override;
  20. private:
  21. SITL::SITL *sitl;
  22. Vector2l *fence;
  23. AP_Int8 *fence_count;
  24. AP_Float *fence_alt_max;
  25. uint32_t last_load_ms;
  26. AC_PolyFence_loader fence_loader;
  27. Location current_loc;
  28. // latest sector updated
  29. uint8_t last_sector;
  30. void load_fence(void);
  31. // get distance in meters to fence in a particular direction in degrees (0 is forward, angles increase in the clockwise direction)
  32. bool get_distance_to_fence(float angle_deg, float &distance) const;
  33. };
  34. #endif // CONFIG_HAL_BOARD