AP_Rally.h 3.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495
  1. /// @file AP_Rally.h
  2. /// @brief Handles rally point storage, retrieval and lookup
  3. /*
  4. * The AP_Rally library:
  5. *
  6. * Initial implementation: Michael Day, September 2013
  7. * Moved to AP_Rally lib: Andrew Chapman April 2014
  8. *
  9. * - responsible for managing a list of rally points
  10. * - reads and writes the rally points to storage
  11. * - provides access to the rally points, including logic to find the nearest one
  12. *
  13. */
  14. #pragma once
  15. #include <AP_Common/AP_Common.h>
  16. #include <AP_Common/Location.h>
  17. #include <AP_Param/AP_Param.h>
  18. struct PACKED RallyLocation {
  19. int32_t lat; //Latitude * 10^7
  20. int32_t lng; //Longitude * 10^7
  21. int16_t alt; //transit altitude (and loiter altitude) in meters (absolute);
  22. int16_t break_alt; //when autolanding, break out of loiter at this alt (meters)
  23. uint16_t land_dir; //when the time comes to auto-land, try to land in this direction (centidegrees)
  24. uint8_t flags; //bit 0 = seek favorable winds when choosing a landing poi
  25. //bit 1 = do auto land after arriving
  26. //all other bits are for future use.
  27. };
  28. /// @class AP_Rally
  29. /// @brief Object managing Rally Points
  30. class AP_Rally {
  31. public:
  32. AP_Rally();
  33. /* Do not allow copies */
  34. AP_Rally(const AP_Rally &other) = delete;
  35. AP_Rally &operator=(const AP_Rally&) = delete;
  36. // data handling
  37. bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const;
  38. bool set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc);
  39. uint8_t get_rally_total() const {
  40. return (uint8_t)_rally_point_total_count;
  41. }
  42. uint8_t get_rally_max(void) const {
  43. const uint16_t ret = _storage.size() / uint16_t(sizeof(RallyLocation));
  44. if (ret > 255) {
  45. return 255;
  46. }
  47. return (uint8_t)ret;
  48. }
  49. // reduce point count:
  50. void truncate(uint8_t num);
  51. // append a rally point to the list
  52. bool append(const RallyLocation &loc) WARN_IF_UNUSED;
  53. float get_rally_limit_km() const { return _rally_limit_km; }
  54. Location rally_location_to_location(const RallyLocation &ret) const;
  55. // logic handling
  56. Location calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt) const;
  57. bool find_nearest_rally_point(const Location &myloc, RallyLocation &ret) const;
  58. // last time rally points changed
  59. uint32_t last_change_time_ms(void) const { return _last_change_time_ms; }
  60. // parameter block
  61. static const struct AP_Param::GroupInfo var_info[];
  62. // get singleton instance
  63. static AP_Rally *get_singleton() { return _singleton; }
  64. private:
  65. static AP_Rally *_singleton;
  66. virtual bool is_valid(const Location &rally_point) const { return true; }
  67. static StorageAccess _storage;
  68. // parameters
  69. AP_Int8 _rally_point_total_count;
  70. AP_Float _rally_limit_km;
  71. AP_Int8 _rally_incl_home;
  72. uint32_t _last_change_time_ms = 0xFFFFFFFF;
  73. };
  74. namespace AP {
  75. AP_Rally *rally();
  76. };