12345678910111213141516171819202122232425262728293031323334353637383940414243 |
- #pragma once
- #include <AC_WPNav/AC_WPNav.h>
- #include <AC_Avoidance/AP_OAPathPlanner.h>
- class AC_WPNav_OA : public AC_WPNav
- {
- public:
-
- AC_WPNav_OA(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
-
-
- bool get_oa_wp_destination(Location& destination) const override;
-
-
-
- bool set_wp_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt = false) override;
-
-
- float get_wp_distance_to_destination() const override;
-
-
- int32_t get_wp_bearing_to_destination() const override;
-
- bool reached_wp_destination() const override;
-
- bool update_wpnav() override;
- protected:
-
- AP_OAPathPlanner::OA_RetState _oa_state;
- Vector3f _origin_oabak;
- Vector3f _destination_oabak;
- Location _oa_destination;
- };
|