APM:Libraries
AP_Rally.cpp
Go to the documentation of this file.
1 #include "AP_Rally.h"
4 
5 #include <AP_HAL/AP_HAL.h>
6 extern const AP_HAL::HAL& hal;
7 
8 // storage object
10 
11 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
12  #define RALLY_LIMIT_KM_DEFAULT 0.3f
13  #define RALLY_INCLUDE_HOME_DEFAULT 1
14 #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
15  #define RALLY_LIMIT_KM_DEFAULT 5.0f
16  #define RALLY_INCLUDE_HOME_DEFAULT 0
17 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
18  #define RALLY_LIMIT_KM_DEFAULT 0.5f
19  #define RALLY_INCLUDE_HOME_DEFAULT 0
20 #else
21  #define RALLY_LIMIT_KM_DEFAULT 1.0f
22  #define RALLY_INCLUDE_HOME_DEFAULT 0
23 #endif
24 
26  // @Param: TOTAL
27  // @DisplayName: Rally Total
28  // @Description: Number of rally points currently loaded
29  // @User: Advanced
30  AP_GROUPINFO("TOTAL", 0, AP_Rally, _rally_point_total_count, 0),
31 
32  // @Param: LIMIT_KM
33  // @DisplayName: Rally Limit
34  // @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.
35  // @User: Advanced
36  // @Units: km
37  // @Increment: 0.1
38  AP_GROUPINFO("LIMIT_KM", 1, AP_Rally, _rally_limit_km, RALLY_LIMIT_KM_DEFAULT),
39 
40  // @Param: INCL_HOME
41  // @DisplayName: Rally Include Home
42  // @Description: Controls if Home is included as a Rally point (i.e. as a safe landing place) for RTL
43  // @User: Standard
44  // @Values: 0:DoNotIncludeHome,1:IncludeHome
45  AP_GROUPINFO("INCL_HOME", 2, AP_Rally, _rally_incl_home, RALLY_INCLUDE_HOME_DEFAULT),
46 
48 };
49 
50 // constructor
52  : _ahrs(ahrs)
53  , _last_change_time_ms(0xFFFFFFFF)
54 {
56 }
57 
58 // get a rally point from EEPROM
60 {
61  if (i >= (uint8_t) _rally_point_total_count) {
62  return false;
63  }
64 
65  _storage.read_block(&ret, i * sizeof(RallyLocation), sizeof(RallyLocation));
66 
67  if (ret.lat == 0 && ret.lng == 0) {
68  return false; // sanity check
69  }
70 
71  return true;
72 }
73 
74 // save a rally point to EEPROM - this assumes that the RALLY_TOTAL param has been incremented beforehand, which is the case in Mission Planner
75 bool AP_Rally::set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc)
76 {
77  if (i >= (uint8_t) _rally_point_total_count) {
78  return false;
79  }
80 
81  if (i >= get_rally_max()) {
82  return false;
83  }
84 
85  _storage.write_block(i * sizeof(RallyLocation), &rallyLoc, sizeof(RallyLocation));
86 
88 
89  return true;
90 }
91 
92 // helper function to translate a RallyLocation to a Location
94 {
95  Location ret = {};
96 
97  // we return an absolute altitude, as we add homeloc.alt below
98  ret.flags.relative_alt = false;
99 
100  //Currently can't do true AGL on the APM. Relative altitudes are
101  //relative to HOME point's altitude. Terrain on the board is inbound
102  //for the PX4, though. This line will need to be updated when that happens:
103  ret.alt = (rally_loc.alt*100UL) + _ahrs.get_home().alt;
104 
105  ret.lat = rally_loc.lat;
106  ret.lng = rally_loc.lng;
107 
108  return ret;
109 }
110 
111 // returns true if a valid rally point is found, otherwise returns false to indicate home position should be used
112 bool AP_Rally::find_nearest_rally_point(const Location &current_loc, RallyLocation &return_loc) const
113 {
114  float min_dis = -1;
115  const struct Location &home_loc = _ahrs.get_home();
116 
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 = get_distance(current_loc, rally_loc);
124 
125  if (is_valid(rally_loc) && (dis < min_dis || min_dis < 0)) {
126  min_dis = dis;
127  return_loc = next_rally;
128  }
129  }
130 
131  // if home is included, return false (meaning use home) if it is closer than all rally points
132  if (_rally_incl_home && (get_distance(current_loc, home_loc) < min_dis)) {
133  return false;
134  }
135 
136  // if a limit is defined and all rally points are beyond that limit, use home if it is closer
137  if ((_rally_limit_km > 0) && (min_dis > _rally_limit_km*1000.0f) && (get_distance(current_loc, home_loc) < min_dis)) {
138  return false; // use home position
139  }
140 
141  // use home if no rally points found
142  return min_dis >= 0;
143 }
144 
145 // return best RTL location from current position
146 Location AP_Rally::calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt) const
147 {
148  RallyLocation ral_loc = {};
149  Location return_loc = {};
150  const struct Location &home_loc = _ahrs.get_home();
151 
152  if (find_nearest_rally_point(current_loc, ral_loc)) {
153  // valid rally point found
154  return_loc = rally_location_to_location(ral_loc);
155  } else {
156  // no valid rally point, return home position
157  return_loc = home_loc;
158  return_loc.alt = rtl_home_alt;
159  return_loc.flags.relative_alt = false; // read_alt_to_hold returns an absolute altitude
160  }
161 
162  return return_loc;
163 }
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Rally.h:63
int32_t lng
Definition: AP_Rally.h:26
const AP_AHRS & _ahrs
Definition: AP_Rally.h:71
Object managing Rally Points.
Definition: AP_Rally.h:37
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
AP_Float _rally_limit_km
Definition: AP_Rally.h:75
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
uint8_t get_rally_max(void) const
Definition: AP_Rally.h:49
Location calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt) const
Definition: AP_Rally.cpp:146
uint32_t _last_change_time_ms
Definition: AP_Rally.h:78
#define RALLY_LIMIT_KM_DEFAULT
Definition: AP_Rally.cpp:21
bool set_rally_point_with_index(uint8_t i, const RallyLocation &rallyLoc)
Definition: AP_Rally.cpp:75
int16_t alt
Definition: AP_Rally.h:27
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
bool find_nearest_rally_point(const Location &myloc, RallyLocation &ret) const
Definition: AP_Rally.cpp:112
Location rally_location_to_location(const RallyLocation &ret) const
Definition: AP_Rally.cpp:93
Handles rally point storage and retrieval.
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
#define f(i)
uint32_t millis()
Definition: system.cpp:157
virtual bool is_valid(const Location &rally_point) const
Definition: AP_Rally.h:66
bool read_block(void *dst, uint16_t src, size_t n) const
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
static StorageAccess _storage
Definition: AP_Rally.h:68
bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const
Definition: AP_Rally.cpp:59
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
bool write_block(uint16_t dst, const void *src, size_t n) const
AP_Int8 _rally_incl_home
Definition: AP_Rally.h:76
AP_Int8 _rally_point_total_count
Definition: AP_Rally.h:74
int32_t lat
Definition: AP_Rally.h:25
AP_Rally(AP_AHRS &ahrs)
Definition: AP_Rally.cpp:51
#define AP_GROUPEND
Definition: AP_Param.h:121
#define RALLY_INCLUDE_HOME_DEFAULT
Definition: AP_Rally.cpp:22
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214