21 #if (HAL_OS_POSIX_IO || HAL_OS_FATFS_IO) && defined(HAL_BOARD_TERRAIN_DIRECTORY) 22 #define AP_TERRAIN_AVAILABLE 1 24 #define AP_TERRAIN_AVAILABLE 0 27 #if AP_TERRAIN_AVAILABLE 34 #define TERRAIN_DEBUG 0 38 #define TERRAIN_GRID_MAVLINK_SIZE 4 44 #define TERRAIN_GRID_BLOCK_MUL_X 7 45 #define TERRAIN_GRID_BLOCK_MUL_Y 8 48 #define TERRAIN_GRID_BLOCK_SPACING_X ((TERRAIN_GRID_BLOCK_MUL_X-1)*TERRAIN_GRID_MAVLINK_SIZE) 49 #define TERRAIN_GRID_BLOCK_SPACING_Y ((TERRAIN_GRID_BLOCK_MUL_Y-1)*TERRAIN_GRID_MAVLINK_SIZE) 52 #define TERRAIN_GRID_BLOCK_SIZE_X (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_X) 53 #define TERRAIN_GRID_BLOCK_SIZE_Y (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y) 56 #define TERRAIN_GRID_BLOCK_CACHE_SIZE 12 59 #define TERRAIN_GRID_FORMAT_VERSION 1 62 #define ASSERT_RANGE(v,minv,maxv) assert((v)<=(maxv)&&(v)>=(minv)) 64 #define ASSERT_RANGE(v,minv,maxv) 82 AP_Terrain(
const AP_Terrain &other) =
delete;
83 AP_Terrain &operator=(
const AP_Terrain&) =
delete;
86 TerrainStatusDisabled = 0,
87 TerrainStatusUnhealthy = 1,
97 enum TerrainStatus status(
void)
const {
return system_status; }
100 void send_request(mavlink_channel_t
chan);
103 void send_terrain_report(mavlink_channel_t chan,
const Location &loc,
bool extrapolate);
104 void handle_data(mavlink_channel_t chan, mavlink_message_t *msg);
105 void handle_terrain_check(mavlink_channel_t chan, mavlink_message_t *msg);
106 void handle_terrain_data(mavlink_message_t *msg);
117 bool height_amsl(
const Location &loc,
float &height,
bool corrected);
130 bool height_terrain_difference_home(
float &terrain_difference,
131 bool extrapolate =
false);
148 bool height_relative_home_equivalent(
float terrain_altitude,
149 float &relative_altitude,
150 bool extrapolate =
false);
162 bool height_above_terrain(
float &terrain_altitude,
bool extrapolate =
false);
178 void get_statistics(uint16_t &pending, uint16_t &loaded);
189 struct PACKED grid_block {
207 int16_t height[TERRAIN_GRID_BLOCK_SIZE_X][TERRAIN_GRID_BLOCK_SIZE_Y];
221 union grid_io_block {
222 struct grid_block block;
226 enum GridCacheState {
227 GRID_CACHE_INVALID=0,
228 GRID_CACHE_DISKWAIT=1,
238 struct grid_block grid;
240 volatile enum GridCacheState
state;
243 uint32_t last_access_ms;
272 uint32_t file_offset;
276 void calculate_grid_info(
const Location &loc,
struct grid_info &info)
const;
281 struct grid_cache &find_grid_cache(
const struct grid_info &info);
287 uint8_t grid_bitnum(uint8_t idx_x, uint8_t idx_y);
293 bool check_bitmap(
const struct grid_block &grid, uint8_t idx_x, uint8_t idx_y);
298 bool request_missing(mavlink_channel_t chan,
struct grid_cache &gcache);
299 bool request_missing(mavlink_channel_t chan,
const struct grid_info &info);
304 void schedule_disk_io(
void);
309 uint8_t bitcount64(uint64_t b);
314 int16_t find_io_idx(
enum GridCacheState
state);
315 uint16_t get_block_crc(
struct grid_block &block);
316 void check_disk_read(
void);
317 void check_disk_write(
void);
319 void open_file(
void);
320 void seek_offset(
void);
321 void write_block(
void);
322 void read_block(
void);
327 void update_mission_data(
void);
332 void update_rally_data(
void);
337 AP_Int16 grid_spacing;
352 uint8_t cache_size = 0;
353 struct grid_cache *cache =
nullptr;
363 volatile enum DiskIoState disk_io_state;
364 union grid_io_block disk_block;
369 static const uint64_t bitmap_mask = (((uint64_t)1U)<<(TERRAIN_GRID_BLOCK_MUL_X*TERRAIN_GRID_BLOCK_MUL_Y)) - 1;
378 int8_t file_lat_degrees;
379 int16_t file_lon_degrees;
382 volatile bool io_failure;
385 bool directory_created;
394 bool have_current_loc_height;
395 float last_current_loc_height;
398 uint16_t next_mission_index;
401 uint8_t next_mission_pos;
404 uint32_t last_mission_change_ms;
407 uint16_t last_mission_spacing;
410 uint16_t next_rally_index;
413 uint32_t last_rally_change_ms;
416 uint16_t last_rally_spacing;
418 char *file_path =
nullptr;
421 enum TerrainStatus system_status = TerrainStatusDisabled;
423 #endif // AP_TERRAIN_AVAILABLE Object managing Rally Points.
static uint8_t buffer[SRXL_FRAMELEN_MAX]
A system for managing and storing variables that are of general interest to the system.
Handles rally point storage and retrieval.
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
#define MAVLINK_COMM_NUM_BUFFERS