AP_Rally.cpp 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201
  1. /// @file AP_Rally.h
  2. /// @brief Handles rally point storage and retrieval.
  3. #include "AP_Rally.h"
  4. #include <AP_AHRS/AP_AHRS.h>
  5. #include <AP_Logger/AP_Logger.h>
  6. #include <StorageManager/StorageManager.h>
  7. // storage object
  8. StorageAccess AP_Rally::_storage(StorageManager::StorageRally);
  9. assert_storage_size<RallyLocation, 15> _assert_storage_size_RallyLocation;
  10. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
  11. #define RALLY_LIMIT_KM_DEFAULT 0.3f
  12. #define RALLY_INCLUDE_HOME_DEFAULT 1
  13. #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  14. #define RALLY_LIMIT_KM_DEFAULT 5.0f
  15. #define RALLY_INCLUDE_HOME_DEFAULT 0
  16. #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
  17. #define RALLY_LIMIT_KM_DEFAULT 0.5f
  18. #define RALLY_INCLUDE_HOME_DEFAULT 1
  19. #else
  20. #define RALLY_LIMIT_KM_DEFAULT 1.0f
  21. #define RALLY_INCLUDE_HOME_DEFAULT 0
  22. #endif
  23. const AP_Param::GroupInfo AP_Rally::var_info[] = {
  24. // @Param: TOTAL
  25. // @DisplayName: Rally Total
  26. // @Description: Number of rally points currently loaded
  27. // @User: Advanced
  28. AP_GROUPINFO("TOTAL", 0, AP_Rally, _rally_point_total_count, 0),
  29. // @Param: LIMIT_KM
  30. // @DisplayName: Rally Limit
  31. // @Description: Maximum distance to rally point. If the closest rally point is more than this number of kilometers from the current position and the home location is closer than any of the rally points from the current position then do RTL to home rather than to the closest rally point. This prevents a leftover rally point from a different airfield being used accidentally. If this is set to 0 then the closest rally point is always used.
  32. // @User: Advanced
  33. // @Units: km
  34. // @Increment: 0.1
  35. AP_GROUPINFO("LIMIT_KM", 1, AP_Rally, _rally_limit_km, RALLY_LIMIT_KM_DEFAULT),
  36. // @Param: INCL_HOME
  37. // @DisplayName: Rally Include Home
  38. // @Description: Controls if Home is included as a Rally point (i.e. as a safe landing place) for RTL
  39. // @User: Standard
  40. // @Values: 0:DoNotIncludeHome,1:IncludeHome
  41. AP_GROUPINFO("INCL_HOME", 2, AP_Rally, _rally_incl_home, RALLY_INCLUDE_HOME_DEFAULT),
  42. AP_GROUPEND
  43. };
  44. // constructor
  45. AP_Rally::AP_Rally()
  46. {
  47. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  48. if (_singleton != nullptr) {
  49. AP_HAL::panic("Rally must be singleton");
  50. }
  51. #endif
  52. _singleton = this;
  53. AP_Param::setup_object_defaults(this, var_info);
  54. }
  55. // get a rally point from EEPROM
  56. bool AP_Rally::get_rally_point_with_index(uint8_t i, RallyLocation &ret) const
  57. {
  58. if (i >= (uint8_t) _rally_point_total_count) {
  59. return false;
  60. }
  61. _storage.read_block(&ret, i * sizeof(RallyLocation), sizeof(RallyLocation));
  62. if (ret.lat == 0 && ret.lng == 0) {
  63. return false; // sanity check
  64. }
  65. return true;
  66. }
  67. void AP_Rally::truncate(uint8_t num)
  68. {
  69. if (num > _rally_point_total_count) {
  70. // we never make the space larger this way
  71. return;
  72. }
  73. _rally_point_total_count.set_and_save_ifchanged(num);
  74. }
  75. bool AP_Rally::append(const RallyLocation &loc)
  76. {
  77. const uint8_t current_total = get_rally_total();
  78. _rally_point_total_count.set_and_save_ifchanged(current_total + 1);
  79. if (!set_rally_point_with_index(current_total, loc)) {
  80. _rally_point_total_count.set_and_save_ifchanged(current_total);
  81. return false;
  82. }
  83. return true;
  84. }
  85. // save a rally point to EEPROM - this assumes that the RALLY_TOTAL param has been incremented beforehand, which is the case in Mission Planner
  86. bool AP_Rally::set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc)
  87. {
  88. if (i >= (uint8_t) _rally_point_total_count) {
  89. return false;
  90. }
  91. if (i >= get_rally_max()) {
  92. return false;
  93. }
  94. _storage.write_block(i * sizeof(RallyLocation), &rallyLoc, sizeof(RallyLocation));
  95. _last_change_time_ms = AP_HAL::millis();
  96. AP::logger().Write_RallyPoint(_rally_point_total_count, i, rallyLoc);
  97. return true;
  98. }
  99. // helper function to translate a RallyLocation to a Location
  100. Location AP_Rally::rally_location_to_location(const RallyLocation &rally_loc) const
  101. {
  102. Location ret = {};
  103. // we return an absolute altitude, as we add homeloc.alt below
  104. ret.relative_alt = false;
  105. //Currently can't do true AGL on the APM. Relative altitudes are
  106. //relative to HOME point's altitude. Terrain on the board is inbound
  107. //for the PX4, though. This line will need to be updated when that happens:
  108. ret.alt = (rally_loc.alt*100UL) + AP::ahrs().get_home().alt;
  109. ret.lat = rally_loc.lat;
  110. ret.lng = rally_loc.lng;
  111. return ret;
  112. }
  113. // returns true if a valid rally point is found, otherwise returns false to indicate home position should be used
  114. bool AP_Rally::find_nearest_rally_point(const Location &current_loc, RallyLocation &return_loc) const
  115. {
  116. float min_dis = -1;
  117. for (uint8_t i = 0; i < (uint8_t) _rally_point_total_count; i++) {
  118. RallyLocation next_rally;
  119. if (!get_rally_point_with_index(i, next_rally)) {
  120. continue;
  121. }
  122. Location rally_loc = rally_location_to_location(next_rally);
  123. float dis = current_loc.get_distance(rally_loc);
  124. if (is_valid(rally_loc) && (dis < min_dis || min_dis < 0)) {
  125. min_dis = dis;
  126. return_loc = next_rally;
  127. }
  128. }
  129. // if a limit is defined and all rally points are beyond that limit, use home if it is closer
  130. if ((_rally_limit_km > 0) && (min_dis > _rally_limit_km*1000.0f)) {
  131. return false; // use home position
  132. }
  133. // use home if no rally points found
  134. return min_dis >= 0;
  135. }
  136. // return best RTL location from current position
  137. Location AP_Rally::calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt) const
  138. {
  139. RallyLocation ral_loc = {};
  140. Location return_loc = {};
  141. const struct Location &home_loc = AP::ahrs().get_home();
  142. // no valid rally point, return home position
  143. return_loc = home_loc;
  144. return_loc.alt = rtl_home_alt;
  145. return_loc.relative_alt = false; // read_alt_to_hold returns an absolute altitude
  146. if (find_nearest_rally_point(current_loc, ral_loc)) {
  147. Location loc = rally_location_to_location(ral_loc);
  148. // use the rally point if it's closer then home, or we aren't generally considering home as acceptable
  149. if (!_rally_incl_home || (current_loc.get_distance(loc) < current_loc.get_distance(return_loc))) {
  150. return_loc = rally_location_to_location(ral_loc);
  151. }
  152. }
  153. return return_loc;
  154. }
  155. // singleton instance
  156. AP_Rally *AP_Rally::_singleton;
  157. namespace AP {
  158. AP_Rally *rally()
  159. {
  160. return AP_Rally::get_singleton();
  161. }
  162. }