diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 45bf91caa8..1268a8bcfc 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -66,9 +66,6 @@ Copter::Copter(void) mainLoop_count(0), rtl_loiter_start_time(0), auto_trim_counter(0), -#if AP_TERRAIN_AVAILABLE && AC_TERRAIN - terrain(ahrs, mission, rally), -#endif #if PRECISION_LANDING == ENABLED precland(ahrs, inertial_nav), #endif diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 9549fd5155..3836c2cd50 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -584,7 +584,7 @@ private: // terrain handling #if AP_TERRAIN_AVAILABLE && AC_TERRAIN - AP_Terrain terrain; + AP_Terrain terrain = AP_Terrain::create(ahrs, mission, rally); #endif // Precision Landing diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index a3ca2b46f4..66a18ddd32 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -611,7 +611,7 @@ private: // terrain handling #if AP_TERRAIN_AVAILABLE - AP_Terrain terrain {ahrs, mission, rally}; + AP_Terrain terrain = AP_Terrain::create(ahrs, mission, rally); #endif AP_Landing landing {mission,ahrs,SpdHgt_Controller,nav_controller,aparm, diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index 340fdf987d..e619b6a5b4 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -56,9 +56,6 @@ Sub::Sub(void) pmTest1(0), fast_loopTimer(0), mainLoop_count(0), -#if AP_TERRAIN_AVAILABLE && AC_TERRAIN - terrain(ahrs, mission, rally), -#endif in_mavlink_delay(false), param_loader(var_info), last_pilot_yaw_input_ms(0) diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index d0f3085043..9cd78134a7 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -436,7 +436,7 @@ private: // terrain handling #if AP_TERRAIN_AVAILABLE && AC_TERRAIN - AP_Terrain terrain; + AP_Terrain terrain = AP_Terrain::create(ahrs, mission, rally); #endif // use this to prevent recursion during sensor init