AP_Terrain: replace HAVE_AP_TERRAIN with AP_TERRAIN_AVAILABLE
This commit is contained in:
parent
ce60bf8d3f
commit
3faafc9644
@ -21,7 +21,7 @@
|
|||||||
#include <GCS.h>
|
#include <GCS.h>
|
||||||
#include "AP_Terrain.h"
|
#include "AP_Terrain.h"
|
||||||
|
|
||||||
#if HAVE_AP_TERRAIN
|
#if AP_TERRAIN_AVAILABLE
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -280,4 +280,4 @@ enum AP_Terrain::TerrainStatus AP_Terrain::status(void)
|
|||||||
return TerrainStatusOK;
|
return TerrainStatusOK;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAVE_AP_TERRAIN
|
#endif // AP_TERRAIN_AVAILABLE
|
||||||
|
@ -21,12 +21,12 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if HAL_OS_POSIX_IO && defined(HAL_BOARD_TERRAIN_DIRECTORY)
|
#if HAL_OS_POSIX_IO && defined(HAL_BOARD_TERRAIN_DIRECTORY)
|
||||||
#define HAVE_AP_TERRAIN 1
|
#define AP_TERRAIN_AVAILABLE 1
|
||||||
#else
|
#else
|
||||||
#define HAVE_AP_TERRAIN 0
|
#define AP_TERRAIN_AVAILABLE 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAVE_AP_TERRAIN
|
#if AP_TERRAIN_AVAILABLE
|
||||||
|
|
||||||
#include <AP_Param.h>
|
#include <AP_Param.h>
|
||||||
#include <AP_AHRS.h>
|
#include <AP_AHRS.h>
|
||||||
@ -344,5 +344,5 @@ private:
|
|||||||
float home_height;
|
float home_height;
|
||||||
Location home_loc;
|
Location home_loc;
|
||||||
};
|
};
|
||||||
#endif // HAVE_AP_TERRAIN
|
#endif // AP_TERRAIN_AVAILABLE
|
||||||
#endif // __AP_TERRAIN_H__
|
#endif // __AP_TERRAIN_H__
|
||||||
|
@ -24,7 +24,7 @@
|
|||||||
#include <GCS.h>
|
#include <GCS.h>
|
||||||
#include "AP_Terrain.h"
|
#include "AP_Terrain.h"
|
||||||
|
|
||||||
#if HAVE_AP_TERRAIN
|
#if AP_TERRAIN_AVAILABLE
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -271,4 +271,4 @@ void AP_Terrain::handle_terrain_data(mavlink_message_t *msg)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#endif // HAVE_AP_TERRAIN
|
#endif // AP_TERRAIN_AVAILABLE
|
||||||
|
@ -24,7 +24,7 @@
|
|||||||
#include <GCS.h>
|
#include <GCS.h>
|
||||||
#include "AP_Terrain.h"
|
#include "AP_Terrain.h"
|
||||||
|
|
||||||
#if HAVE_AP_TERRAIN
|
#if AP_TERRAIN_AVAILABLE
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -329,4 +329,4 @@ void AP_Terrain::io_timer(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAVE_AP_TERRAIN
|
#endif // AP_TERRAIN_AVAILABLE
|
||||||
|
@ -24,7 +24,7 @@
|
|||||||
#include <GCS.h>
|
#include <GCS.h>
|
||||||
#include "AP_Terrain.h"
|
#include "AP_Terrain.h"
|
||||||
|
|
||||||
#if HAVE_AP_TERRAIN
|
#if AP_TERRAIN_AVAILABLE
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
@ -188,4 +188,4 @@ uint16_t AP_Terrain::get_block_crc(struct grid_block &block)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAVE_AP_TERRAIN
|
#endif // AP_TERRAIN_AVAILABLE
|
||||||
|
Loading…
Reference in New Issue
Block a user