mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Rally: add is_valid method
method will be used in Copter to check if a rally point is inside fence
This commit is contained in:
parent
b8011fd46c
commit
ef28be9ce8
@ -132,7 +132,7 @@ bool AP_Rally::find_nearest_rally_point(const Location ¤t_loc, RallyLocati
|
||||
Location rally_loc = rally_location_to_location(next_rally);
|
||||
float dis = get_distance(current_loc, rally_loc);
|
||||
|
||||
if (dis < min_dis || min_dis < 0) {
|
||||
if (is_valid(rally_loc) && (dis < min_dis || min_dis < 0)) {
|
||||
min_dis = dis;
|
||||
return_loc = next_rally;
|
||||
}
|
||||
|
@ -62,6 +62,8 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
virtual bool is_valid(const Location &rally_point) const { return true; }
|
||||
|
||||
static StorageAccess _storage;
|
||||
|
||||
// internal variables
|
||||
|
Loading…
Reference in New Issue
Block a user