mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Terrain: make parameter variables private
This commit is contained in:
parent
9d6b745556
commit
679b32b76c
@ -79,10 +79,6 @@ class AP_Terrain
|
||||
public:
|
||||
AP_Terrain(AP_AHRS &_ahrs);
|
||||
|
||||
// parameters
|
||||
AP_Int8 enable;
|
||||
AP_Int16 grid_spacing; // meters between grid points
|
||||
|
||||
enum TerrainStatus {
|
||||
TerrainStatusDisabled = 0, // not enabled
|
||||
TerrainStatusUnhealthy = 1, // no terrain data for current location
|
||||
@ -301,6 +297,10 @@ private:
|
||||
void write_block(void);
|
||||
void read_block(void);
|
||||
|
||||
// parameters
|
||||
AP_Int8 enable;
|
||||
AP_Int16 grid_spacing; // meters between grid points
|
||||
|
||||
// reference to AHRS, so we can ask for our position,
|
||||
// heading and speed
|
||||
AP_AHRS &ahrs;
|
||||
|
Loading…
Reference in New Issue
Block a user