123456789101112131415161718192021222324252627282930313233343536373839404142434445464748 |
- #pragma once
- #include <AP_Math/AP_Math.h>
- #include "AC_PrecLand_Backend.h"
- class AC_PrecLand_Companion : public AC_PrecLand_Backend
- {
- public:
-
- using AC_PrecLand_Backend::AC_PrecLand_Backend;
-
- void init() override;
-
- void update() override;
-
-
- bool get_los_body(Vector3f& ret) override;
-
- uint32_t los_meas_time_ms() override;
-
- bool have_los_meas() override;
-
- float distance_to_target() override;
-
- void handle_msg(const mavlink_message_t &msg) override;
- private:
- uint64_t _timestamp_us;
- float _distance_to_target;
- Vector3f _los_meas_body;
- bool _have_los_meas;
- uint32_t _los_meas_time_ms;
- };
|