AP_Terrain: GCS_MAVLink takes care of mavlink capabilities
This commit is contained in:
parent
7b80f56a80
commit
1b4a2c4d6b
@ -320,7 +320,6 @@ void AP_Terrain::update(void)
|
|||||||
|
|
||||||
// update capabilities and status
|
// update capabilities and status
|
||||||
if (allocate()) {
|
if (allocate()) {
|
||||||
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_TERRAIN);
|
|
||||||
if (!pos_valid) {
|
if (!pos_valid) {
|
||||||
// we don't know where we are
|
// we don't know where we are
|
||||||
system_status = TerrainStatusUnhealthy;
|
system_status = TerrainStatusUnhealthy;
|
||||||
@ -331,7 +330,6 @@ void AP_Terrain::update(void)
|
|||||||
system_status = TerrainStatusOK;
|
system_status = TerrainStatusOK;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
hal.util->clear_capabilities(MAV_PROTOCOL_CAPABILITY_TERRAIN);
|
|
||||||
system_status = TerrainStatusDisabled;
|
system_status = TerrainStatusDisabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -92,6 +92,8 @@ public:
|
|||||||
// 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);
|
||||||
|
|
||||||
|
bool enabled() const { return enable; }
|
||||||
|
|
||||||
// return status enum for health reporting
|
// return status enum for health reporting
|
||||||
enum TerrainStatus status(void) const { return system_status; }
|
enum TerrainStatus status(void) const { return system_status; }
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user