123456789101112131415161718192021222324252627282930313233343536373839404142434445 |
- #pragma once
- #include "AP_Proximity.h"
- #include "AP_Proximity_Backend.h"
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- #include <SITL/SITL.h>
- #include <AC_Fence/AC_PolyFence_loader.h>
- #include <AP_Common/Location.h>
- class AP_Proximity_SITL : public AP_Proximity_Backend
- {
- public:
-
- AP_Proximity_SITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
-
- void update(void) override;
-
- float distance_max() const override;
- float distance_min() const override;
-
- bool get_upward_distance(float &distance) const override;
- private:
- SITL::SITL *sitl;
- Vector2l *fence;
- AP_Int8 *fence_count;
- AP_Float *fence_alt_max;
- uint32_t last_load_ms;
- AC_PolyFence_loader fence_loader;
- Location current_loc;
-
- uint8_t last_sector;
- void load_fence(void);
-
- bool get_distance_to_fence(float angle_deg, float &distance) const;
- };
- #endif
|