AC_WPNav_OA.cpp 5.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130
  1. #include "AC_WPNav_OA.h"
  2. AC_WPNav_OA::AC_WPNav_OA(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
  3. AC_WPNav(inav, ahrs, pos_control, attitude_control)
  4. {
  5. }
  6. // returns object avoidance adjusted wp location using location class
  7. // returns false if unable to convert from target vector to global coordinates
  8. bool AC_WPNav_OA::get_oa_wp_destination(Location& destination) const
  9. {
  10. // if oa inactive return unadjusted location
  11. if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {
  12. return get_wp_destination(destination);
  13. }
  14. // return latest destination provided by oa path planner
  15. destination = _oa_destination;
  16. return true;
  17. }
  18. /// set_origin_and_destination - set origin and destination waypoints using position vectors (distance from home in cm)
  19. /// terrain_alt should be true if origin.z and destination.z are desired altitudes above terrain (false if these are alt-above-ekf-origin)
  20. /// returns false on failure (likely caused by missing terrain data)
  21. bool AC_WPNav_OA::set_wp_origin_and_destination(const Vector3f& origin, const Vector3f& destination, bool terrain_alt)
  22. {
  23. const bool ret = AC_WPNav::set_wp_origin_and_destination(origin, destination, terrain_alt);
  24. if (ret) {
  25. // reset object avoidance state
  26. _oa_state = AP_OAPathPlanner::OA_NOT_REQUIRED;
  27. }
  28. return ret;
  29. }
  30. /// get_wp_distance_to_destination - get horizontal distance to destination in cm
  31. /// always returns distance to final destination (i.e. does not use oa adjusted destination)
  32. float AC_WPNav_OA::get_wp_distance_to_destination() const
  33. {
  34. if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {
  35. return AC_WPNav::get_wp_distance_to_destination();
  36. }
  37. // get current location
  38. const Vector3f &curr = _inav.get_position();
  39. return norm(_destination_oabak.x-curr.x, _destination_oabak.y-curr.y);
  40. }
  41. /// get_wp_bearing_to_destination - get bearing to next waypoint in centi-degrees
  42. /// always returns bearing to final destination (i.e. does not use oa adjusted destination)
  43. int32_t AC_WPNav_OA::get_wp_bearing_to_destination() const
  44. {
  45. if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {
  46. return AC_WPNav::get_wp_bearing_to_destination();
  47. }
  48. return get_bearing_cd(_inav.get_position(), _destination_oabak);
  49. }
  50. /// true when we have come within RADIUS cm of the waypoint
  51. bool AC_WPNav_OA::reached_wp_destination() const
  52. {
  53. return (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) && AC_WPNav::reached_wp_destination();
  54. }
  55. /// update_wpnav - run the wp controller - should be called at 100hz or higher
  56. bool AC_WPNav_OA::update_wpnav()
  57. {
  58. // run path planning around obstacles
  59. AP_OAPathPlanner *oa_ptr = AP_OAPathPlanner::get_singleton();
  60. Location current_loc;
  61. if ((oa_ptr != nullptr) && AP::ahrs().get_position(current_loc)) {
  62. // backup _origin and _destination when not doing oa
  63. if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {
  64. _origin_oabak = _origin;
  65. _destination_oabak = _destination;
  66. }
  67. // convert origin and destination to Locations and pass into oa
  68. const Location origin_loc(_origin_oabak);
  69. const Location destination_loc(_destination_oabak);
  70. Location oa_origin_new, oa_destination_new;
  71. const AP_OAPathPlanner::OA_RetState oa_retstate = oa_ptr->mission_avoidance(current_loc, origin_loc, destination_loc, oa_origin_new, oa_destination_new);
  72. switch (oa_retstate) {
  73. case AP_OAPathPlanner::OA_NOT_REQUIRED:
  74. if (_oa_state != oa_retstate) {
  75. // object avoidance has become inactive so reset target to original destination
  76. set_wp_destination(_destination_oabak, _terrain_alt);
  77. _oa_state = oa_retstate;
  78. }
  79. break;
  80. case AP_OAPathPlanner::OA_PROCESSING:
  81. case AP_OAPathPlanner::OA_ERROR:
  82. // during processing or in case of error stop the vehicle
  83. // by setting the oa_destination to a stopping point
  84. if ((_oa_state != AP_OAPathPlanner::OA_PROCESSING) && (_oa_state != AP_OAPathPlanner::OA_ERROR)) {
  85. // calculate stopping point
  86. Vector3f stopping_point;
  87. get_wp_stopping_point(stopping_point);
  88. _oa_destination = Location(stopping_point);
  89. if (set_wp_destination(stopping_point, false)) {
  90. _oa_state = oa_retstate;
  91. }
  92. }
  93. break;
  94. case AP_OAPathPlanner::OA_SUCCESS:
  95. // if oa destination has become active or destination has changed update wpnav
  96. if ((_oa_state != AP_OAPathPlanner::OA_SUCCESS) || !oa_destination_new.same_latlon_as(_oa_destination)) {
  97. _oa_destination = oa_destination_new;
  98. // convert Location to offset from EKF origin
  99. Vector3f dest_NEU;
  100. if (_oa_destination.get_vector_from_origin_NEU(dest_NEU)) {
  101. // calculate target altitude by calculating OA adjusted destination's distance along the original track
  102. // and then linear interpolate using the original track's origin and destination altitude
  103. const float dist_along_path = constrain_float(oa_destination_new.line_path_proportion(origin_loc, destination_loc), 0.0f, 1.0f);
  104. dest_NEU.z = linear_interpolate(_origin_oabak.z, _destination_oabak.z, dist_along_path, 0.0f, 1.0f);
  105. if (set_wp_destination(dest_NEU, _terrain_alt)) {
  106. _oa_state = oa_retstate;
  107. }
  108. }
  109. }
  110. break;
  111. }
  112. }
  113. // run the non-OA update
  114. return AC_WPNav::update_wpnav();
  115. }