mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: init terrain to locaiton and wpnav sub sytems
This commit is contained in:
parent
572e401894
commit
1a182a52da
@ -789,6 +789,9 @@ bool QuadPlane::setup(void)
|
|||||||
AP_BoardConfig::config_error("Unable to allocate %s", "wp_nav");
|
AP_BoardConfig::config_error("Unable to allocate %s", "wp_nav");
|
||||||
}
|
}
|
||||||
AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info);
|
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);
|
loiter_nav = new AC_Loiter(inertial_nav, *ahrs_view, *pos_control, *attitude_control);
|
||||||
if (!loiter_nav) {
|
if (!loiter_nav) {
|
||||||
|
@ -162,6 +162,11 @@ void Plane::init_ardupilot()
|
|||||||
#if AC_FENCE == ENABLED
|
#if AC_FENCE == ENABLED
|
||||||
fence.init();
|
fence.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_TERRAIN_AVAILABLE
|
||||||
|
Location::set_terrain(&terrain);
|
||||||
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//********************************************************************************
|
//********************************************************************************
|
||||||
|
Loading…
Reference in New Issue
Block a user