mirror of https://github.com/ArduPilot/ardupilot
AP_Terrain: use ahrs singleton
This commit is contained in:
parent
46f3b5d109
commit
1a853f6f82
|
@ -56,8 +56,7 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
// constructor
|
// constructor
|
||||||
AP_Terrain::AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally) :
|
AP_Terrain::AP_Terrain(const AP_Mission &_mission, const AP_Rally &_rally) :
|
||||||
ahrs(_ahrs),
|
|
||||||
mission(_mission),
|
mission(_mission),
|
||||||
rally(_rally),
|
rally(_rally),
|
||||||
disk_io_state(DiskIoIdle),
|
disk_io_state(DiskIoIdle),
|
||||||
|
@ -81,6 +80,8 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
|
||||||
// quick access for home altitude
|
// quick access for home altitude
|
||||||
if (loc.lat == home_loc.lat &&
|
if (loc.lat == home_loc.lat &&
|
||||||
loc.lng == home_loc.lng) {
|
loc.lng == home_loc.lng) {
|
||||||
|
@ -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)
|
bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool extrapolate)
|
||||||
{
|
{
|
||||||
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
|
||||||
float height_home, height_loc;
|
float height_home, height_loc;
|
||||||
if (!height_amsl(ahrs.get_home(), height_home, false)) {
|
if (!height_amsl(ahrs.get_home(), height_home, false)) {
|
||||||
// we don't know the height of home
|
// we don't know the height of home
|
||||||
|
@ -208,7 +211,7 @@ bool AP_Terrain::height_above_terrain(float &terrain_altitude, bool extrapolate)
|
||||||
}
|
}
|
||||||
|
|
||||||
float relative_home_altitude;
|
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;
|
relative_home_altitude = -relative_home_altitude;
|
||||||
|
|
||||||
terrain_altitude = relative_home_altitude - terrain_difference;
|
terrain_altitude = relative_home_altitude - terrain_difference;
|
||||||
|
@ -254,7 +257,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio)
|
||||||
}
|
}
|
||||||
|
|
||||||
Location loc;
|
Location loc;
|
||||||
if (!ahrs.get_position(loc)) {
|
if (!AP::ahrs().get_position(loc)) {
|
||||||
// we don't know where we are
|
// we don't know where we are
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -295,6 +298,8 @@ void AP_Terrain::update(void)
|
||||||
// just schedule any needed disk IO
|
// just schedule any needed disk IO
|
||||||
schedule_disk_io();
|
schedule_disk_io();
|
||||||
|
|
||||||
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
|
||||||
// try to ensure the home location is populated
|
// try to ensure the home location is populated
|
||||||
float height;
|
float height;
|
||||||
height_amsl(ahrs.get_home(), height, false);
|
height_amsl(ahrs.get_home(), height, false);
|
||||||
|
@ -342,7 +347,7 @@ void AP_Terrain::log_terrain_data(DataFlash_Class &dataflash)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
Location loc;
|
Location loc;
|
||||||
if (!ahrs.get_position(loc)) {
|
if (!AP::ahrs().get_position(loc)) {
|
||||||
// we don't know where we are
|
// we don't know where we are
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -76,7 +76,7 @@
|
||||||
|
|
||||||
class AP_Terrain {
|
class AP_Terrain {
|
||||||
public:
|
public:
|
||||||
AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally);
|
AP_Terrain(const AP_Mission &_mission, const AP_Rally &_rally);
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
AP_Terrain(const AP_Terrain &other) = delete;
|
AP_Terrain(const AP_Terrain &other) = delete;
|
||||||
|
@ -336,10 +336,6 @@ private:
|
||||||
AP_Int8 enable;
|
AP_Int8 enable;
|
||||||
AP_Int16 grid_spacing; // meters between grid points
|
AP_Int16 grid_spacing; // meters between grid points
|
||||||
|
|
||||||
// reference to AHRS, so we can ask for our position,
|
|
||||||
// heading and speed
|
|
||||||
AP_AHRS &ahrs;
|
|
||||||
|
|
||||||
// reference to AP_Mission, so we can ask preload terrain data for
|
// reference to AP_Mission, so we can ask preload terrain data for
|
||||||
// all waypoints
|
// all waypoints
|
||||||
const AP_Mission &mission;
|
const AP_Mission &mission;
|
||||||
|
|
|
@ -92,7 +92,7 @@ void AP_Terrain::send_request(mavlink_channel_t chan)
|
||||||
schedule_disk_io();
|
schedule_disk_io();
|
||||||
|
|
||||||
Location loc;
|
Location loc;
|
||||||
if (!ahrs.get_position(loc)) {
|
if (!AP::ahrs().get_position(loc)) {
|
||||||
// we don't know where we are
|
// we don't know where we are
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -206,6 +206,7 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc
|
||||||
float home_terrain_height = 0;
|
float home_terrain_height = 0;
|
||||||
uint16_t spacing = 0;
|
uint16_t spacing = 0;
|
||||||
Location current_loc;
|
Location current_loc;
|
||||||
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
if (ahrs.get_position(current_loc) &&
|
if (ahrs.get_position(current_loc) &&
|
||||||
height_amsl(ahrs.get_home(), home_terrain_height, false) &&
|
height_amsl(ahrs.get_home(), home_terrain_height, false) &&
|
||||||
height_amsl(loc, terrain_height, false)) {
|
height_amsl(loc, terrain_height, false)) {
|
||||||
|
|
Loading…
Reference in New Issue