global: use static method to construct AP_Mount

This commit is contained in:
Lucas De Marchi 2017-08-29 12:48:10 -07:00 committed by Francisco Ferreira
parent 563f9bfe89
commit 18aa88b329
7 changed files with 5 additions and 14 deletions

View File

@ -31,9 +31,6 @@ Rover::Rover(void) :
modes(&g.mode1), modes(&g.mode1),
L1_controller(ahrs, nullptr), L1_controller(ahrs, nullptr),
nav_controller(&L1_controller), nav_controller(&L1_controller),
#if MOUNT == ENABLED
camera_mount(ahrs, current_loc),
#endif
control_mode(&mode_initializing), control_mode(&mode_initializing),
home(ahrs.get_home()), home(ahrs.get_home()),
G_Dt(0.02f) G_Dt(0.02f)

View File

@ -217,7 +217,7 @@ private:
// Camera/Antenna mount tracking and stabilisation stuff // Camera/Antenna mount tracking and stabilisation stuff
#if MOUNT == ENABLED #if MOUNT == ENABLED
// current_loc uses the baro/gps solution for altitude rather than gps only. // current_loc uses the baro/gps solution for altitude rather than gps only.
AP_Mount camera_mount; AP_Mount camera_mount = AP_Mount::create(ahrs, current_loc);
#endif #endif
// true if initialisation has completed // true if initialisation has completed

View File

@ -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 MOUNT == ENABLED
camera_mount(ahrs, current_loc),
#endif
#if AC_FENCE == ENABLED #if AC_FENCE == ENABLED
fence(ahrs, inertial_nav), fence(ahrs, inertial_nav),
#endif #endif

View File

@ -549,7 +549,7 @@ private:
// Camera/Antenna mount tracking and stabilisation stuff // Camera/Antenna mount tracking and stabilisation stuff
#if MOUNT == ENABLED #if MOUNT == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only. // current_loc uses the baro/gps soloution for altitude rather than gps only.
AP_Mount camera_mount; AP_Mount camera_mount = AP_Mount::create(ahrs, current_loc);
#endif #endif
// AC_Fence library to reduce fly-aways // AC_Fence library to reduce fly-aways

View File

@ -768,7 +768,7 @@ private:
// Camera/Antenna mount tracking and stabilisation stuff // Camera/Antenna mount tracking and stabilisation stuff
#if MOUNT == ENABLED #if MOUNT == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only. // current_loc uses the baro/gps soloution for altitude rather than gps only.
AP_Mount camera_mount {ahrs, current_loc}; AP_Mount camera_mount = AP_Mount::create(ahrs, current_loc);
#endif #endif
// Arming/Disarming mangement class // Arming/Disarming mangement class

View File

@ -59,9 +59,6 @@ Sub::Sub(void)
pmTest1(0), pmTest1(0),
fast_loopTimer(0), fast_loopTimer(0),
mainLoop_count(0), mainLoop_count(0),
#if MOUNT == ENABLED
camera_mount(ahrs, current_loc),
#endif
#if AC_FENCE == ENABLED #if AC_FENCE == ENABLED
fence(ahrs, inertial_nav), fence(ahrs, inertial_nav),
#endif #endif

View File

@ -421,7 +421,7 @@ private:
// Camera/Antenna mount tracking and stabilisation stuff // Camera/Antenna mount tracking and stabilisation stuff
#if MOUNT == ENABLED #if MOUNT == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only. // current_loc uses the baro/gps soloution for altitude rather than gps only.
AP_Mount camera_mount; AP_Mount camera_mount = AP_Mount::create(ahrs, current_loc);
#endif #endif
// AC_Fence library to reduce fly-aways // AC_Fence library to reduce fly-aways