mirror of https://github.com/ArduPilot/ardupilot
Copter: precision landing does not use terrain database
precision landing was always only using the range finder, there was no use of the provided alt unless the rangefinder was good
This commit is contained in:
parent
ea22e888c7
commit
3e7fb66a77
|
@ -888,7 +888,6 @@ private:
|
|||
// terrain.cpp
|
||||
void terrain_update();
|
||||
void terrain_logging();
|
||||
bool terrain_use();
|
||||
|
||||
// tuning.cpp
|
||||
void tuning();
|
||||
|
|
|
@ -15,13 +15,9 @@ void Copter::update_precland()
|
|||
{
|
||||
int32_t height_above_ground_cm = current_loc.alt;
|
||||
|
||||
// use range finder altitude if it is valid, else try to get terrain alt
|
||||
// use range finder altitude if it is valid, otherwise use home alt
|
||||
if (rangefinder_alt_ok()) {
|
||||
height_above_ground_cm = rangefinder_state.alt_cm;
|
||||
} else if (terrain_use() && !current_loc.is_zero()) {
|
||||
if (!current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height_above_ground_cm)) {
|
||||
height_above_ground_cm = current_loc.alt;
|
||||
}
|
||||
}
|
||||
|
||||
precland.update(height_above_ground_cm, rangefinder_alt_ok());
|
||||
|
|
|
@ -26,13 +26,3 @@ void Copter::terrain_logging()
|
|||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// should we use terrain data for things including the home altitude
|
||||
bool Copter::terrain_use()
|
||||
{
|
||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||
return (g.terrain_follow > 0);
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue