|
|
@ -83,11 +83,20 @@ public: |
|
|
|
AP_Int8 enable; |
|
|
|
AP_Int8 enable; |
|
|
|
AP_Int16 grid_spacing; // meters between grid points
|
|
|
|
AP_Int16 grid_spacing; // meters between grid points
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
enum TerrainStatus { |
|
|
|
|
|
|
|
TerrainStatusDisabled = 0, // not enabled
|
|
|
|
|
|
|
|
TerrainStatusUnhealthy = 1, // no terrain data for current location
|
|
|
|
|
|
|
|
TerrainStatusOK = 2 // terrain data available
|
|
|
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
static const struct AP_Param::GroupInfo var_info[]; |
|
|
|
static const struct AP_Param::GroupInfo var_info[]; |
|
|
|
|
|
|
|
|
|
|
|
// update terrain state. Should be called at 1Hz or more
|
|
|
|
// update terrain state. Should be called at 1Hz or more
|
|
|
|
void update(void); |
|
|
|
void update(void); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// return status enum for health reporting
|
|
|
|
|
|
|
|
enum TerrainStatus status(void); |
|
|
|
|
|
|
|
|
|
|
|
// send any pending terrain request message
|
|
|
|
// send any pending terrain request message
|
|
|
|
void send_request(mavlink_channel_t chan); |
|
|
|
void send_request(mavlink_channel_t chan); |
|
|
|
|
|
|
|
|
|
|
|