global: use static method to construct AP_Terrain
This commit is contained in:
parent
122f3d110b
commit
cf6ea9642e
@ -66,9 +66,6 @@ Copter::Copter(void)
|
|||||||
mainLoop_count(0),
|
mainLoop_count(0),
|
||||||
rtl_loiter_start_time(0),
|
rtl_loiter_start_time(0),
|
||||||
auto_trim_counter(0),
|
auto_trim_counter(0),
|
||||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
|
||||||
terrain(ahrs, mission, rally),
|
|
||||||
#endif
|
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if PRECISION_LANDING == ENABLED
|
||||||
precland(ahrs, inertial_nav),
|
precland(ahrs, inertial_nav),
|
||||||
#endif
|
#endif
|
||||||
|
@ -584,7 +584,7 @@ private:
|
|||||||
|
|
||||||
// terrain handling
|
// terrain handling
|
||||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
AP_Terrain terrain;
|
AP_Terrain terrain = AP_Terrain::create(ahrs, mission, rally);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Precision Landing
|
// Precision Landing
|
||||||
|
@ -611,7 +611,7 @@ private:
|
|||||||
|
|
||||||
// terrain handling
|
// terrain handling
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE
|
||||||
AP_Terrain terrain {ahrs, mission, rally};
|
AP_Terrain terrain = AP_Terrain::create(ahrs, mission, rally);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_Landing landing {mission,ahrs,SpdHgt_Controller,nav_controller,aparm,
|
AP_Landing landing {mission,ahrs,SpdHgt_Controller,nav_controller,aparm,
|
||||||
|
@ -56,9 +56,6 @@ Sub::Sub(void)
|
|||||||
pmTest1(0),
|
pmTest1(0),
|
||||||
fast_loopTimer(0),
|
fast_loopTimer(0),
|
||||||
mainLoop_count(0),
|
mainLoop_count(0),
|
||||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
|
||||||
terrain(ahrs, mission, rally),
|
|
||||||
#endif
|
|
||||||
in_mavlink_delay(false),
|
in_mavlink_delay(false),
|
||||||
param_loader(var_info),
|
param_loader(var_info),
|
||||||
last_pilot_yaw_input_ms(0)
|
last_pilot_yaw_input_ms(0)
|
||||||
|
@ -436,7 +436,7 @@ private:
|
|||||||
|
|
||||||
// terrain handling
|
// terrain handling
|
||||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
AP_Terrain terrain;
|
AP_Terrain terrain = AP_Terrain::create(ahrs, mission, rally);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// use this to prevent recursion during sensor init
|
// use this to prevent recursion during sensor init
|
||||||
|
Loading…
Reference in New Issue
Block a user