AC_WPNav_OA.h 2.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243
  1. #pragma once
  2. #include <AC_WPNav/AC_WPNav.h>
  3. #include <AC_Avoidance/AP_OAPathPlanner.h>
  4. class AC_WPNav_OA : public AC_WPNav
  5. {
  6. public:
  7. /// Constructor
  8. AC_WPNav_OA(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
  9. // returns object avoidance adjusted wp location using location class
  10. // returns false if unable to convert from target vector to global coordinates
  11. bool get_oa_wp_destination(Location& destination) const override;
  12. /// set origin and destination waypoints using position vectors (distance from ekf origin in cm)
  13. /// terrain_alt should be true if origin.z and destination.z are desired altitudes above terrain (false if these are alt-above-ekf-origin)
  14. /// returns false on failure (likely caused by missing terrain data)
  15. bool set_wp_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt = false) override;
  16. /// get horizontal distance to destination in cm
  17. /// always returns distance to final destination (i.e. does not use oa adjusted destination)
  18. float get_wp_distance_to_destination() const override;
  19. /// get bearing to next waypoint in centi-degrees
  20. /// always returns bearing to final destination (i.e. does not use oa adjusted destination)
  21. int32_t get_wp_bearing_to_destination() const override;
  22. /// true when we have come within RADIUS cm of the final destination
  23. bool reached_wp_destination() const override;
  24. /// run the wp controller
  25. bool update_wpnav() override;
  26. protected:
  27. // oa path planning variables
  28. AP_OAPathPlanner::OA_RetState _oa_state; // state of object avoidance, if OA_SUCCESS we use _oa_destination to avoid obstacles
  29. Vector3f _origin_oabak; // backup of _origin so it can be restored when oa completes
  30. Vector3f _destination_oabak; // backup of _destination so it can be restored when oa completes
  31. Location _oa_destination; // intermediate destination during avoidance
  32. };