APM:Libraries
TerrainGCS.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  handle vehicle <-> GCS communications for terrain library
17  */
18 
19 #include <AP_HAL/AP_HAL.h>
20 #include <AP_Common/AP_Common.h>
21 #include <AP_Math/AP_Math.h>
23 #include <GCS_MAVLink/GCS.h>
24 #include "AP_Terrain.h"
25 
26 #if AP_TERRAIN_AVAILABLE
27 
28 #include <assert.h>
29 #include <stdio.h>
30 
31 extern const AP_HAL::HAL& hal;
32 
33 /*
34  request any missing 4x4 grids from a block, given a grid_cache
35  */
36 bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcache)
37 {
38  struct grid_block &grid = gcache.grid;
39 
40  if (grid.spacing != grid_spacing) {
41  // an invalid grid
42  return false;
43  }
44 
45  // see if we are waiting for disk read
46  if (gcache.state == GRID_CACHE_DISKWAIT) {
47  // don't request data from the GCS till we know it's not on disk
48  return false;
49  }
50 
51  // see if it is fully populated
52  if ((grid.bitmap & bitmap_mask) == bitmap_mask) {
53  // it is fully populated, nothing to do
54  return false;
55  }
56 
57  if (!HAVE_PAYLOAD_SPACE(chan, TERRAIN_REQUEST)) {
58  // not enough buffer space
59  return false;
60  }
61 
62  /*
63  ask the GCS to send a set of 4x4 grids
64  */
65  mavlink_msg_terrain_request_send(chan, grid.lat, grid.lon, grid_spacing, bitmap_mask & ~grid.bitmap);
66  last_request_time_ms[chan] = AP_HAL::millis();
67 
68  return true;
69 }
70 
71 /*
72  request any missing 4x4 grids from a block
73  */
74 bool AP_Terrain::request_missing(mavlink_channel_t chan, const struct grid_info &info)
75 {
76  // find the grid
77  struct grid_cache &gcache = find_grid_cache(info);
78  return request_missing(chan, gcache);
79 }
80 
81 /*
82  send any pending terrain request to the GCS
83  */
84 void AP_Terrain::send_request(mavlink_channel_t chan)
85 {
86  if (enable == 0 || !allocate()) {
87  // not enabled
88  return;
89  }
90 
91  // see if we need to schedule some disk IO
92  schedule_disk_io();
93 
94  Location loc;
95  if (!ahrs.get_position(loc)) {
96  // we don't know where we are
97  return;
98  }
99 
100  // always send a terrain report
101  send_terrain_report(chan, loc, true);
102 
103  // did we request recently?
104  if (AP_HAL::millis() - last_request_time_ms[chan] < 2000) {
105  // too soon to request again
106  return;
107  }
108 
109  // request any missing 4x4 blocks in the current grid
110  struct grid_info info;
111  calculate_grid_info(loc, info);
112 
113  if (request_missing(chan, info)) {
114  return;
115  }
116 
117  // also request a larger set of up to 9 grids
118  for (int8_t x=-1; x<=1; x++) {
119  for (int8_t y=-1; y<=1; y++) {
120  Location loc2 = loc;
121  location_offset(loc2,
122  x*TERRAIN_GRID_BLOCK_SIZE_X*0.7f*grid_spacing,
123  y*TERRAIN_GRID_BLOCK_SIZE_Y*0.7f*grid_spacing);
124  struct grid_info info2;
125  calculate_grid_info(loc2, info2);
126  if (request_missing(chan, info2)) {
127  return;
128  }
129  }
130  }
131 
132  // check cache blocks that may have been setup by a TERRAIN_CHECK
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])) {
136  return;
137  }
138  }
139  }
140 
141  // request the current loc last to ensure it has highest last
142  // access time
143  if (request_missing(chan, info)) {
144  return;
145  }
146 }
147 
148 /*
149  count bits in a uint64_t
150 */
151 uint8_t AP_Terrain::bitcount64(uint64_t b)
152 {
153  return __builtin_popcount((unsigned)(b&0xFFFFFFFF)) + __builtin_popcount((unsigned)(b>>32));
154 }
155 
156 /*
157  get some statistics for TERRAIN_REPORT
158 */
159 void AP_Terrain::get_statistics(uint16_t &pending, uint16_t &loaded)
160 {
161  pending = 0;
162  loaded = 0;
163  for (uint16_t i=0; i<cache_size; i++) {
164  if (cache[i].grid.spacing != grid_spacing) {
165  continue;
166  }
167  if (cache[i].state == GRID_CACHE_INVALID) {
168  continue;
169  }
170  uint8_t maskbits = TERRAIN_GRID_BLOCK_MUL_X*TERRAIN_GRID_BLOCK_MUL_Y;
171  if (cache[i].state == GRID_CACHE_DISKWAIT) {
172  pending += maskbits;
173  continue;
174  }
175  if (cache[i].state == GRID_CACHE_DIRTY) {
176  // count dirty grids as a pending, so we know where there
177  // are disk writes pending
178  pending++;
179  }
180  uint8_t bitcount = bitcount64(cache[i].grid.bitmap);
181  pending += maskbits - bitcount;
182  loaded += bitcount;
183  }
184 }
185 
186 
187 /*
188  handle terrain messages from GCS
189  */
190 void AP_Terrain::handle_data(mavlink_channel_t chan, mavlink_message_t *msg)
191 {
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);
196  }
197 }
198 
199 
200 /*
201  send a TERRAIN_REPORT for a location
202  */
203 void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc, bool extrapolate)
204 {
205  float terrain_height = 0;
206  float home_terrain_height = 0;
207  uint16_t spacing = 0;
208  Location current_loc;
209  if (ahrs.get_position(current_loc) &&
210  height_amsl(ahrs.get_home(), home_terrain_height, false) &&
211  height_amsl(loc, terrain_height, false)) {
212  // non-zero spacing indicates we have data
213  spacing = grid_spacing;
214  } else if (extrapolate && have_current_loc_height) {
215  // show the extrapolated height, so logs show what height is
216  // being used for navigation
217  terrain_height = last_current_loc_height;
218  }
219  uint16_t pending, loaded;
220  get_statistics(pending, loaded);
221 
222  float current_height;
223  if (spacing == 0 && !(extrapolate && have_current_loc_height)) {
224  current_height = 0;
225  } else {
226  if (current_loc.flags.relative_alt) {
227  current_height = current_loc.alt*0.01f;
228  } else {
229  current_height = (current_loc.alt - ahrs.get_home().alt)*0.01f;
230  }
231  }
232  current_height += home_terrain_height - terrain_height;
233 
234  if (HAVE_PAYLOAD_SPACE(chan, TERRAIN_REPORT)) {
235  mavlink_msg_terrain_report_send(chan, loc.lat, loc.lng, spacing,
236  terrain_height, current_height,
237  pending, loaded);
238  }
239 }
240 
241 /*
242  handle TERRAIN_CHECK messages from GCS
243  */
244 void AP_Terrain::handle_terrain_check(mavlink_channel_t chan, mavlink_message_t *msg)
245 {
246  mavlink_terrain_check_t packet;
247  mavlink_msg_terrain_check_decode(msg, &packet);
248  Location loc;
249  loc.lat = packet.lat;
250  loc.lng = packet.lon;
251  send_terrain_report(chan, loc, false);
252 }
253 
254 /*
255  handle TERRAIN_DATA messages from GCS
256  */
257 void AP_Terrain::handle_terrain_data(mavlink_message_t *msg)
258 {
259  mavlink_terrain_data_t packet;
260  mavlink_msg_terrain_data_decode(msg, &packet);
261 
262  uint16_t i;
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) {
269  break;
270  }
271  }
272  if (i == cache_size) {
273  // we don't have that grid, ignore data
274  return;
275  }
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];
285  }
286  }
287  gcache.grid.bitmap |= ((uint64_t)1) << packet.gridbit;
288 
289  // mark dirty for disk IO
290  gcache.state = GRID_CACHE_DIRTY;
291 
292 #if TERRAIN_DEBUG
293  hal.console->printf("Filled bit %u idx_x=%u idx_y=%u\n",
294  (unsigned)packet.gridbit, (unsigned)idx_x, (unsigned)idx_y);
295  if (gcache.grid.bitmap == bitmap_mask) {
296  hal.console->printf("--lat=%12.7f --lon=%12.7f %u\n",
297  grid.lat*1.0e-7f,
298  grid.lon*1.0e-7f,
299  grid.height[0][0]);
300  Location loc2;
301  loc2.lat = grid.lat;
302  loc2.lng = grid.lon;
303  location_offset(loc2, 28*grid_spacing, 32*grid_spacing);
304  hal.console->printf("--lat=%12.7f --lon=%12.7f %u\n",
305  loc2.lat*1.0e-7f,
306  loc2.lng*1.0e-7f,
307  grid.height[27][31]);
308  }
309 #endif
310 
311  // see if we need to schedule some disk IO
312  update();
313 }
314 
315 
316 #endif // AP_TERRAIN_AVAILABLE
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
AP_HAL::UARTDriver * console
Definition: HAL.h:110
Interface definition for the various Ground Control System.
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
#define HAVE_PAYLOAD_SPACE(chan, id)
Definition: GCS.h:28
#define x(i)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
#define f(i)
uint32_t millis()
Definition: system.cpp:157
static int state
Definition: Util.cpp:20
bool get_position(struct Location &loc) const override
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
Common definitions and utility routines for the ArduPilot libraries.
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8