AP_Terrain: Reduce memory consumption, simplify enable checking

This commit is contained in:
Michael du Breuil 2018-06-28 14:57:49 -07:00 committed by Andrew Tridgell
parent e2f5ae6a4c
commit 4299eb9ba8
2 changed files with 6 additions and 17 deletions

View File

@ -61,20 +61,9 @@ AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rall
mission(_mission),
rally(_rally),
disk_io_state(DiskIoIdle),
fd(-1),
timer_setup(false),
file_lat_degrees(0),
file_lon_degrees(0),
io_failure(false),
directory_created(false),
home_height(0),
have_current_loc_height(false),
last_current_loc_height(0)
fd(-1)
{
AP_Param::setup_object_defaults(this, var_info);
memset(&home_loc, 0, sizeof(home_loc));
memset(&disk_block, 0, sizeof(disk_block));
memset(last_request_time_ms, 0, sizeof(last_request_time_ms));
}
/*
@ -88,7 +77,7 @@ AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rall
*/
bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected)
{
if (!enable || !allocate()) {
if (!allocate()) {
return false;
}
@ -260,7 +249,7 @@ bool AP_Terrain::height_relative_home_equivalent(float terrain_altitude,
*/
float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio)
{
if (!enable || !allocate() || grid_spacing <= 0) {
if (!allocate() || grid_spacing <= 0) {
return 0;
}
@ -326,7 +315,7 @@ void AP_Terrain::update(void)
update_rally_data();
// update capabilities and status
if (enable) {
if (allocate()) {
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_TERRAIN);
if (!pos_valid) {
// we don't know where we are
@ -349,7 +338,7 @@ void AP_Terrain::update(void)
*/
void AP_Terrain::log_terrain_data(DataFlash_Class &dataflash)
{
if (!enable) {
if (!allocate()) {
return;
}
Location loc;

View File

@ -83,7 +83,7 @@ bool AP_Terrain::request_missing(mavlink_channel_t chan, const struct grid_info
*/
void AP_Terrain::send_request(mavlink_channel_t chan)
{
if (enable == 0 || !allocate()) {
if (!allocate()) {
// not enabled
return;
}