1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495 |
- #pragma once
- #include <AP_Common/AP_Common.h>
- #include <AP_Common/Location.h>
- #include <AP_Param/AP_Param.h>
- struct PACKED RallyLocation {
- int32_t lat;
- int32_t lng;
- int16_t alt;
- int16_t break_alt;
- uint16_t land_dir;
- uint8_t flags;
-
-
- };
- class AP_Rally {
- public:
- AP_Rally();
-
- AP_Rally(const AP_Rally &other) = delete;
- AP_Rally &operator=(const AP_Rally&) = delete;
-
- bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const;
- bool set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc);
- uint8_t get_rally_total() const {
- return (uint8_t)_rally_point_total_count;
- }
- uint8_t get_rally_max(void) const {
- const uint16_t ret = _storage.size() / uint16_t(sizeof(RallyLocation));
- if (ret > 255) {
- return 255;
- }
- return (uint8_t)ret;
- }
-
- void truncate(uint8_t num);
-
- bool append(const RallyLocation &loc) WARN_IF_UNUSED;
- float get_rally_limit_km() const { return _rally_limit_km; }
- Location rally_location_to_location(const RallyLocation &ret) const;
-
- Location calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt) const;
- bool find_nearest_rally_point(const Location &myloc, RallyLocation &ret) const;
-
- uint32_t last_change_time_ms(void) const { return _last_change_time_ms; }
-
- static const struct AP_Param::GroupInfo var_info[];
-
- static AP_Rally *get_singleton() { return _singleton; }
- private:
- static AP_Rally *_singleton;
- virtual bool is_valid(const Location &rally_point) const { return true; }
- static StorageAccess _storage;
-
- AP_Int8 _rally_point_total_count;
- AP_Float _rally_limit_km;
- AP_Int8 _rally_incl_home;
- uint32_t _last_change_time_ms = 0xFFFFFFFF;
- };
- namespace AP {
- AP_Rally *rally();
- };
|