Browse Source

global: use static method to construct AP_Camera

master
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
c3647f0185
  1. 3
      APMrover2/Rover.cpp
  2. 8
      APMrover2/Rover.h
  3. 3
      ArduCopter/Copter.cpp
  4. 4
      ArduCopter/Copter.h
  5. 2
      ArduPlane/Plane.h
  6. 3
      ArduSub/Sub.cpp
  7. 4
      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 CAMERA == ENABLED
camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs),
#endif
#if MOUNT == ENABLED
camera_mount(ahrs, current_loc),
#endif

8
APMrover2/Rover.h

@ -206,14 +206,14 @@ private: @@ -206,14 +206,14 @@ private:
AP_ServoRelayEvents ServoRelayEvents = AP_ServoRelayEvents::create(relay);
// The rover's current location
struct Location current_loc;
// Camera
#if CAMERA == ENABLED
AP_Camera camera;
AP_Camera camera = AP_Camera::create(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs);
#endif
// The rover's current location
struct Location current_loc;
// Camera/Antenna mount tracking and stabilisation stuff
#if MOUNT == ENABLED
// current_loc uses the baro/gps solution for altitude rather than gps only.

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 CAMERA == ENABLED
camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs),
#endif
#if MOUNT == ENABLED
camera_mount(ahrs, current_loc),
#endif

4
ArduCopter/Copter.h

@ -541,9 +541,9 @@ private: @@ -541,9 +541,9 @@ private:
// handle repeated servo and relay events
AP_ServoRelayEvents ServoRelayEvents = AP_ServoRelayEvents::create(relay);
// Reference to the camera object (it uses the relay object inside it)
// Camera
#if CAMERA == ENABLED
AP_Camera camera;
AP_Camera camera = AP_Camera::create(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs);
#endif
// Camera/Antenna mount tracking and stabilisation stuff

2
ArduPlane/Plane.h

@ -274,7 +274,7 @@ private: @@ -274,7 +274,7 @@ private:
// Camera
#if CAMERA == ENABLED
AP_Camera camera{&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs};
AP_Camera camera = AP_Camera::create(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs);
#endif
#if OPTFLOW == ENABLED

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 CAMERA == ENABLED
camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs),
#endif
#if MOUNT == ENABLED
camera_mount(ahrs, current_loc),
#endif

4
ArduSub/Sub.h

@ -413,9 +413,9 @@ private: @@ -413,9 +413,9 @@ private:
// handle repeated servo and relay events
AP_ServoRelayEvents ServoRelayEvents = AP_ServoRelayEvents::create(relay);
// Reference to the camera object (it uses the relay object inside it)
// Camera
#if CAMERA == ENABLED
AP_Camera camera;
AP_Camera camera = AP_Camera::create(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs);
#endif
// Camera/Antenna mount tracking and stabilisation stuff

Loading…
Cancel
Save