12345678910111213141516171819202122232425262728293031323334353637383940414243444546 |
- #pragma once
- #include <AP_Math/AP_Math.h>
- #include <AC_PID/AC_PID.h>
- #include "AC_PrecLand.h"
- class AC_PrecLand_Backend
- {
- public:
-
- AC_PrecLand_Backend(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) :
- _frontend(frontend),
- _state(state) {}
-
- virtual ~AC_PrecLand_Backend() {}
-
- virtual void init() = 0;
-
- virtual void update() = 0;
-
-
- virtual bool get_los_body(Vector3f& dir_body) = 0;
-
- virtual uint32_t los_meas_time_ms() = 0;
-
- virtual bool have_los_meas() = 0;
-
- virtual float distance_to_target() { return 0.0f; };
-
- virtual void handle_msg(const mavlink_message_t &msg) {};
-
- int8_t get_bus(void) const { return _frontend._bus.get(); }
-
- protected:
- const AC_PrecLand& _frontend;
- AC_PrecLand::precland_state &_state;
- };
|