Browse Source

AP_Terrain: prevent valgrind error when terrain not available

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
37b357f282
  1. 4
      libraries/AP_Terrain/TerrainGCS.cpp

4
libraries/AP_Terrain/TerrainGCS.cpp

@ -204,11 +204,15 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc @@ -204,11 +204,15 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc
get_statistics(pending, loaded);
float current_height;
if (spacing == 0) {
current_height = 0;
} else {
if (current_loc.flags.relative_alt) {
current_height = current_loc.alt*0.01f;
} else {
current_height = (current_loc.alt - ahrs.get_home().alt)*0.01f;
}
}
current_height += home_terrain_height - terrain_height;
if (comm_get_txspace(chan) >= MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_TERRAIN_REPORT_LEN) {

Loading…
Cancel
Save