Plane: init terrain to locaiton and wpnav sub sytems

This commit is contained in:
Iampete1 2021-04-07 18:41:24 +01:00 committed by Andrew Tridgell
parent 572e401894
commit 1a182a52da
2 changed files with 8 additions and 0 deletions

View File

@ -789,6 +789,9 @@ bool QuadPlane::setup(void)
AP_BoardConfig::config_error("Unable to allocate %s", "wp_nav");
}
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
#if AP_TERRAIN_AVAILABLE
wp_nav->set_terrain(&plane.terrain);
#endif
loiter_nav = new AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
if (!loiter_nav) {

View File

@ -162,6 +162,11 @@ void Plane::init_ardupilot()
#if AC_FENCE == ENABLED
fence.init();
#endif
#if AP_TERRAIN_AVAILABLE
Location::set_terrain(&terrain);
#endif
}
//********************************************************************************