diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index 9d6cd22c9f..e655f1624e 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -31,9 +31,6 @@ Rover::Rover(void) : modes(&g.mode1), L1_controller(ahrs, nullptr), nav_controller(&L1_controller), -#if MOUNT == ENABLED - camera_mount(ahrs, current_loc), -#endif control_mode(&mode_initializing), home(ahrs.get_home()), G_Dt(0.02f) diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 8ab3fde426..ba4b85cd57 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -217,7 +217,7 @@ private: // Camera/Antenna mount tracking and stabilisation stuff #if MOUNT == ENABLED // 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 // true if initialisation has completed diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index f8b52b997a..1d5eb92714 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 MOUNT == ENABLED - camera_mount(ahrs, current_loc), -#endif #if AC_FENCE == ENABLED fence(ahrs, inertial_nav), #endif diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 77cb0ac2a1..63195506e5 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -549,7 +549,7 @@ private: // Camera/Antenna mount tracking and stabilisation stuff #if MOUNT == ENABLED // 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 // AC_Fence library to reduce fly-aways diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 3393c82c3d..c67644fb13 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -764,11 +764,11 @@ private: // last time home was updated while disarmed uint32_t last_home_update_ms; - + // Camera/Antenna mount tracking and stabilisation stuff #if MOUNT == ENABLED // 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 // Arming/Disarming mangement class diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index 3369578344..19504a26ca 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -59,9 +59,6 @@ Sub::Sub(void) pmTest1(0), fast_loopTimer(0), mainLoop_count(0), -#if MOUNT == ENABLED - camera_mount(ahrs, current_loc), -#endif #if AC_FENCE == ENABLED fence(ahrs, inertial_nav), #endif diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 8e62e335b6..d24cfa684b 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -421,7 +421,7 @@ private: // Camera/Antenna mount tracking and stabilisation stuff #if MOUNT == ENABLED // 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 // AC_Fence library to reduce fly-aways