mirror of https://github.com/ArduPilot/ardupilot
AP_Terrain: add get_grid_spacing accessor
This commit is contained in:
parent
0e2261832e
commit
11e541f123
|
@ -182,6 +182,11 @@ public:
|
|||
*/
|
||||
void get_statistics(uint16_t &pending, uint16_t &loaded) const;
|
||||
|
||||
/*
|
||||
get grid spacing in meters
|
||||
*/
|
||||
uint16_t get_grid_spacing() const { return MAX(grid_spacing, 0); };
|
||||
|
||||
/*
|
||||
returns true if initialisation failed because out-of-memory
|
||||
*/
|
||||
|
|
|
@ -196,7 +196,6 @@ void AP_Terrain::get_statistics(uint16_t &pending, uint16_t &loaded) const
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
handle terrain messages from GCS
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue