|
|
|
@ -56,8 +56,7 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = {
@@ -56,8 +56,7 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = {
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
// constructor
|
|
|
|
|
AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally) : |
|
|
|
|
ahrs(_ahrs), |
|
|
|
|
AP_Terrain::AP_Terrain(const AP_Mission &_mission, const AP_Rally &_rally) : |
|
|
|
|
mission(_mission), |
|
|
|
|
rally(_rally), |
|
|
|
|
disk_io_state(DiskIoIdle), |
|
|
|
@ -81,6 +80,8 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected)
@@ -81,6 +80,8 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected)
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
const AP_AHRS &ahrs = AP::ahrs(); |
|
|
|
|
|
|
|
|
|
// quick access for home altitude
|
|
|
|
|
if (loc.lat == home_loc.lat && |
|
|
|
|
loc.lng == home_loc.lng) { |
|
|
|
@ -161,6 +162,8 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected)
@@ -161,6 +162,8 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected)
|
|
|
|
|
*/ |
|
|
|
|
bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool extrapolate) |
|
|
|
|
{ |
|
|
|
|
const AP_AHRS &ahrs = AP::ahrs(); |
|
|
|
|
|
|
|
|
|
float height_home, height_loc; |
|
|
|
|
if (!height_amsl(ahrs.get_home(), height_home, false)) { |
|
|
|
|
// we don't know the height of home
|
|
|
|
@ -208,7 +211,7 @@ bool AP_Terrain::height_above_terrain(float &terrain_altitude, bool extrapolate)
@@ -208,7 +211,7 @@ bool AP_Terrain::height_above_terrain(float &terrain_altitude, bool extrapolate)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
float relative_home_altitude; |
|
|
|
|
ahrs.get_relative_position_D_home(relative_home_altitude); |
|
|
|
|
AP::ahrs().get_relative_position_D_home(relative_home_altitude); |
|
|
|
|
relative_home_altitude = -relative_home_altitude; |
|
|
|
|
|
|
|
|
|
terrain_altitude = relative_home_altitude - terrain_difference; |
|
|
|
@ -254,7 +257,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio)
@@ -254,7 +257,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
Location loc; |
|
|
|
|
if (!ahrs.get_position(loc)) { |
|
|
|
|
if (!AP::ahrs().get_position(loc)) { |
|
|
|
|
// we don't know where we are
|
|
|
|
|
return 0; |
|
|
|
|
} |
|
|
|
@ -295,6 +298,8 @@ void AP_Terrain::update(void)
@@ -295,6 +298,8 @@ void AP_Terrain::update(void)
|
|
|
|
|
// just schedule any needed disk IO
|
|
|
|
|
schedule_disk_io(); |
|
|
|
|
|
|
|
|
|
const AP_AHRS &ahrs = AP::ahrs(); |
|
|
|
|
|
|
|
|
|
// try to ensure the home location is populated
|
|
|
|
|
float height; |
|
|
|
|
height_amsl(ahrs.get_home(), height, false); |
|
|
|
@ -342,7 +347,7 @@ void AP_Terrain::log_terrain_data(DataFlash_Class &dataflash)
@@ -342,7 +347,7 @@ void AP_Terrain::log_terrain_data(DataFlash_Class &dataflash)
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
Location loc; |
|
|
|
|
if (!ahrs.get_position(loc)) { |
|
|
|
|
if (!AP::ahrs().get_position(loc)) { |
|
|
|
|
// we don't know where we are
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|