26 #if AP_TERRAIN_AVAILABLE 36 bool AP_Terrain::request_missing(mavlink_channel_t
chan,
struct grid_cache &gcache)
38 struct grid_block &grid = gcache.grid;
40 if (grid.spacing != grid_spacing) {
46 if (gcache.state == GRID_CACHE_DISKWAIT) {
52 if ((grid.bitmap & bitmap_mask) == bitmap_mask) {
65 mavlink_msg_terrain_request_send(chan, grid.lat, grid.lon, grid_spacing, bitmap_mask & ~grid.bitmap);
74 bool AP_Terrain::request_missing(mavlink_channel_t chan,
const struct grid_info &info)
77 struct grid_cache &gcache = find_grid_cache(info);
78 return request_missing(chan, gcache);
84 void AP_Terrain::send_request(mavlink_channel_t chan)
86 if (enable == 0 || !allocate()) {
101 send_terrain_report(chan, loc,
true);
110 struct grid_info info;
111 calculate_grid_info(loc, info);
113 if (request_missing(chan, info)) {
118 for (int8_t
x=-1;
x<=1;
x++) {
119 for (int8_t y=-1; y<=1; y++) {
122 x*TERRAIN_GRID_BLOCK_SIZE_X*0.7
f*grid_spacing,
123 y*TERRAIN_GRID_BLOCK_SIZE_Y*0.7
f*grid_spacing);
124 struct grid_info info2;
125 calculate_grid_info(loc2, info2);
126 if (request_missing(chan, info2)) {
133 for (uint16_t i=0; i<cache_size; i++) {
134 if (cache[i].
state >= GRID_CACHE_VALID) {
135 if (request_missing(chan, cache[i])) {
143 if (request_missing(chan, info)) {
151 uint8_t AP_Terrain::bitcount64(uint64_t b)
153 return __builtin_popcount((
unsigned)(b&0xFFFFFFFF)) + __builtin_popcount((
unsigned)(b>>32));
159 void AP_Terrain::get_statistics(uint16_t &pending, uint16_t &loaded)
163 for (uint16_t i=0; i<cache_size; i++) {
164 if (cache[i].grid.spacing != grid_spacing) {
167 if (cache[i].
state == GRID_CACHE_INVALID) {
170 uint8_t maskbits = TERRAIN_GRID_BLOCK_MUL_X*TERRAIN_GRID_BLOCK_MUL_Y;
171 if (cache[i].
state == GRID_CACHE_DISKWAIT) {
175 if (cache[i].
state == GRID_CACHE_DIRTY) {
180 uint8_t bitcount = bitcount64(cache[i].grid.bitmap);
181 pending += maskbits - bitcount;
190 void AP_Terrain::handle_data(mavlink_channel_t chan, mavlink_message_t *msg)
192 if (msg->msgid == MAVLINK_MSG_ID_TERRAIN_DATA) {
193 handle_terrain_data(msg);
194 }
else if (msg->msgid == MAVLINK_MSG_ID_TERRAIN_CHECK) {
195 handle_terrain_check(chan, msg);
203 void AP_Terrain::send_terrain_report(mavlink_channel_t chan,
const Location &loc,
bool extrapolate)
205 float terrain_height = 0;
206 float home_terrain_height = 0;
207 uint16_t spacing = 0;
210 height_amsl(
ahrs.
get_home(), home_terrain_height,
false) &&
211 height_amsl(loc, terrain_height,
false)) {
213 spacing = grid_spacing;
214 }
else if (extrapolate && have_current_loc_height) {
217 terrain_height = last_current_loc_height;
219 uint16_t pending, loaded;
220 get_statistics(pending, loaded);
222 float current_height;
223 if (spacing == 0 && !(extrapolate && have_current_loc_height)) {
227 current_height = current_loc.
alt*0.01f;
232 current_height += home_terrain_height - terrain_height;
235 mavlink_msg_terrain_report_send(chan, loc.
lat, loc.
lng, spacing,
236 terrain_height, current_height,
244 void AP_Terrain::handle_terrain_check(mavlink_channel_t chan, mavlink_message_t *msg)
246 mavlink_terrain_check_t packet;
247 mavlink_msg_terrain_check_decode(msg, &packet);
249 loc.
lat = packet.lat;
250 loc.
lng = packet.lon;
251 send_terrain_report(chan, loc,
false);
257 void AP_Terrain::handle_terrain_data(mavlink_message_t *msg)
259 mavlink_terrain_data_t packet;
260 mavlink_msg_terrain_data_decode(msg, &packet);
263 for (i=0; i<cache_size; i++) {
264 if (cache[i].grid.lat == packet.lat &&
265 cache[i].grid.lon == packet.lon &&
266 cache[i].grid.spacing == packet.grid_spacing &&
267 grid_spacing == packet.grid_spacing &&
268 packet.gridbit < 56) {
272 if (i == cache_size) {
276 struct grid_cache &gcache = cache[i];
277 struct grid_block &grid = gcache.grid;
278 uint8_t idx_x = (packet.gridbit / TERRAIN_GRID_BLOCK_MUL_Y) * TERRAIN_GRID_MAVLINK_SIZE;
279 uint8_t idx_y = (packet.gridbit % TERRAIN_GRID_BLOCK_MUL_Y) * TERRAIN_GRID_MAVLINK_SIZE;
280 ASSERT_RANGE(idx_x,0,(TERRAIN_GRID_BLOCK_MUL_X-1)*TERRAIN_GRID_MAVLINK_SIZE);
281 ASSERT_RANGE(idx_y,0,(TERRAIN_GRID_BLOCK_MUL_Y-1)*TERRAIN_GRID_MAVLINK_SIZE);
282 for (uint8_t
x=0;
x<TERRAIN_GRID_MAVLINK_SIZE;
x++) {
283 for (uint8_t y=0; y<TERRAIN_GRID_MAVLINK_SIZE; y++) {
284 grid.height[idx_x+
x][idx_y+y] = packet.data[
x*TERRAIN_GRID_MAVLINK_SIZE+y];
287 gcache.grid.bitmap |= ((uint64_t)1) << packet.gridbit;
290 gcache.state = GRID_CACHE_DIRTY;
294 (
unsigned)packet.gridbit, (
unsigned)idx_x, (
unsigned)idx_y);
295 if (gcache.grid.bitmap == bitmap_mask) {
307 grid.height[27][31]);
316 #endif // AP_TERRAIN_AVAILABLE
AP_HAL::UARTDriver * console
Interface definition for the various Ground Control System.
const struct Location & get_home(void) const
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
int32_t lat
param 3 - Latitude * 10**7
#define HAVE_PAYLOAD_SPACE(chan, id)
virtual void printf(const char *,...) FMT_PRINTF(2
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
bool get_position(struct Location &loc) const override
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Common definitions and utility routines for the ArduPilot libraries.
int32_t lng
param 4 - Longitude * 10**7
AP_HAL::AnalogSource * chan