mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Terrain: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
3438caebe2
commit
e8e4aef998
@ -193,7 +193,7 @@ bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool
|
|||||||
}
|
}
|
||||||
|
|
||||||
Location loc;
|
Location loc;
|
||||||
if (!ahrs.get_position(loc)) {
|
if (!ahrs.get_location(loc)) {
|
||||||
// we don't know where we are
|
// we don't know where we are
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@ -279,7 +279,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio)
|
|||||||
}
|
}
|
||||||
|
|
||||||
Location loc;
|
Location loc;
|
||||||
if (!AP::ahrs().get_position(loc)) {
|
if (!AP::ahrs().get_location(loc)) {
|
||||||
// we don't know where we are
|
// we don't know where we are
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -329,7 +329,7 @@ void AP_Terrain::update(void)
|
|||||||
|
|
||||||
// update the cached current location height
|
// update the cached current location height
|
||||||
Location loc;
|
Location loc;
|
||||||
bool pos_valid = ahrs.get_position(loc);
|
bool pos_valid = ahrs.get_location(loc);
|
||||||
bool terrain_valid = pos_valid && height_amsl(loc, height, false);
|
bool terrain_valid = pos_valid && height_amsl(loc, height, false);
|
||||||
if (pos_valid && terrain_valid) {
|
if (pos_valid && terrain_valid) {
|
||||||
last_current_loc_height = height;
|
last_current_loc_height = height;
|
||||||
@ -365,7 +365,7 @@ void AP_Terrain::log_terrain_data()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
Location loc;
|
Location loc;
|
||||||
if (!AP::ahrs().get_position(loc)) {
|
if (!AP::ahrs().get_location(loc)) {
|
||||||
// we don't know where we are
|
// we don't know where we are
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -113,7 +113,7 @@ void AP_Terrain::send_request(mavlink_channel_t chan)
|
|||||||
schedule_disk_io();
|
schedule_disk_io();
|
||||||
|
|
||||||
Location loc;
|
Location loc;
|
||||||
if (!AP::ahrs().get_position(loc)) {
|
if (!AP::ahrs().get_location(loc)) {
|
||||||
// we don't know where we are. Send a report and request any cached blocks.
|
// we don't know where we are. Send a report and request any cached blocks.
|
||||||
// this allows for download of mission items when we have no GPS lock
|
// this allows for download of mission items when we have no GPS lock
|
||||||
loc = {};
|
loc = {};
|
||||||
@ -227,7 +227,7 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc
|
|||||||
uint16_t spacing = 0;
|
uint16_t spacing = 0;
|
||||||
Location current_loc;
|
Location current_loc;
|
||||||
const AP_AHRS &ahrs = AP::ahrs();
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
if (ahrs.get_position(current_loc) &&
|
if (ahrs.get_location(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)) {
|
||||||
// non-zero spacing indicates we have data
|
// non-zero spacing indicates we have data
|
||||||
|
Loading…
Reference in New Issue
Block a user