APM:Libraries
AP_Rally.h
Go to the documentation of this file.
1 
4 /*
5  * The AP_Rally library:
6  *
7  * Initial implementation: Michael Day, September 2013
8  * Moved to AP_Rally lib: Andrew Chapman April 2014
9  *
10  * - responsible for managing a list of rally points
11  * - reads and writes the rally points to storage
12  * - provides access to the rally points, including logic to find the nearest one
13  *
14  */
15 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_Param/AP_Param.h>
19 #include <AP_AHRS/AP_AHRS.h>
21 
22 #define AP_RALLY_WP_SIZE 15 // eeprom size of rally points
23 
25  int32_t lat; //Latitude * 10^7
26  int32_t lng; //Longitude * 10^7
27  int16_t alt; //transit altitude (and loiter altitude) in meters (absolute);
28  int16_t break_alt; //when autolanding, break out of loiter at this alt (meters)
29  uint16_t land_dir; //when the time comes to auto-land, try to land in this direction (centidegrees)
30  uint8_t flags; //bit 0 = seek favorable winds when choosing a landing poi
31  //bit 1 = do auto land after arriving
32  //all other bits are for future use.
33 };
34 
37 class AP_Rally {
38 public:
40 
41  /* Do not allow copies */
42  AP_Rally(const AP_Rally &other) = delete;
43  AP_Rally &operator=(const AP_Rally&) = delete;
44 
45  // data handling
46  bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const;
47  bool set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc);
48  uint8_t get_rally_total() const { return _rally_point_total_count; }
49  uint8_t get_rally_max(void) const { return _storage.size() / AP_RALLY_WP_SIZE; }
50 
51  float get_rally_limit_km() const { return _rally_limit_km; }
52 
53  Location rally_location_to_location(const RallyLocation &ret) const;
54 
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 
59  // last time rally points changed
60  uint32_t last_change_time_ms(void) const { return _last_change_time_ms; }
61 
62  // parameter block
63  static const struct AP_Param::GroupInfo var_info[];
64 
65 private:
66  virtual bool is_valid(const Location &rally_point) const { return true; }
67 
69 
70  // internal variables
71  const AP_AHRS& _ahrs; // used only for home position
72 
73  // parameters
75  AP_Float _rally_limit_km;
77 
79 };
int32_t lng
Definition: AP_Rally.h:26
#define AP_RALLY_WP_SIZE
Definition: AP_Rally.h:22
const AP_AHRS & _ahrs
Definition: AP_Rally.h:71
uint8_t get_rally_total() const
Definition: AP_Rally.h:48
Object managing Rally Points.
Definition: AP_Rally.h:37
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
AP_Float _rally_limit_km
Definition: AP_Rally.h:75
uint8_t flags
Definition: AP_Rally.h:30
uint8_t get_rally_max(void) const
Definition: AP_Rally.h:49
uint16_t land_dir
Definition: AP_Rally.h:29
uint32_t _last_change_time_ms
Definition: AP_Rally.h:78
int16_t alt
Definition: AP_Rally.h:27
A system for managing and storing variables that are of general interest to the system.
int16_t break_alt
Definition: AP_Rally.h:28
virtual bool is_valid(const Location &rally_point) const
Definition: AP_Rally.h:66
float get_rally_limit_km() const
Definition: AP_Rally.h:51
Common definitions and utility routines for the ArduPilot libraries.
static StorageAccess _storage
Definition: AP_Rally.h:68
AP_Int8 _rally_incl_home
Definition: AP_Rally.h:76
#define PACKED
Definition: AP_Common.h:28
uint32_t last_change_time_ms(void) const
Definition: AP_Rally.h:60
AP_Int8 _rally_point_total_count
Definition: AP_Rally.h:74
int32_t lat
Definition: AP_Rally.h:25