Browse Source

global: use static method to construct AP_Mount

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
18aa88b329
  1. 3
      APMrover2/Rover.cpp
  2. 2
      APMrover2/Rover.h
  3. 3
      ArduCopter/Copter.cpp
  4. 2
      ArduCopter/Copter.h
  5. 4
      ArduPlane/Plane.h
  6. 3
      ArduSub/Sub.cpp
  7. 2
      ArduSub/Sub.h

3
APMrover2/Rover.cpp

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

2
APMrover2/Rover.h

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

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

2
ArduCopter/Copter.h

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

4
ArduPlane/Plane.h

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

3
ArduSub/Sub.cpp

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

2
ArduSub/Sub.h

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

Loading…
Cancel
Save