Browse Source

global: use static method to construct AP_Terrain

mission-4.1.18
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
cf6ea9642e
  1. 3
      ArduCopter/Copter.cpp
  2. 2
      ArduCopter/Copter.h
  3. 2
      ArduPlane/Plane.h
  4. 3
      ArduSub/Sub.cpp
  5. 2
      ArduSub/Sub.h

3
ArduCopter/Copter.cpp

@ -66,9 +66,6 @@ Copter::Copter(void) @@ -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

2
ArduCopter/Copter.h

@ -584,7 +584,7 @@ private: @@ -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

2
ArduPlane/Plane.h

@ -611,7 +611,7 @@ private: @@ -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,

3
ArduSub/Sub.cpp

@ -56,9 +56,6 @@ Sub::Sub(void) @@ -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)

2
ArduSub/Sub.h

@ -436,7 +436,7 @@ private: @@ -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

Loading…
Cancel
Save