Browse Source

Sub: Fix compile-time OPTFLOW enabling switch

mission-4.1.18
Jacob Walser 8 years ago
parent
commit
854275459d
  1. 8
      ArduSub/Sub.h
  2. 4
      ArduSub/sensors.cpp
  3. 2
      ArduSub/system.cpp

8
ArduSub/Sub.h

@ -57,8 +57,6 @@ @@ -57,8 +57,6 @@
#include <RC_Channel/RC_Channel.h> // RC Channel Library
#include <AP_Motors/AP_Motors.h> // AP Motors library
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
#include <Filter/Filter.h> // Filter library
#include <AP_Buffer/AP_Buffer.h> // APM FIFO Buffer
#include <AP_Relay/AP_Relay.h> // APM relay
@ -89,6 +87,10 @@ @@ -89,6 +87,10 @@
#include "GCS_Mavlink.h"
// libraries which are dependent on #defines in defines.h and/or config.h
#if OPTFLOW == ENABLED
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
#endif
#if RCMAP_ENABLED == ENABLED
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
#endif
@ -658,8 +660,10 @@ private: @@ -658,8 +660,10 @@ private:
void read_rangefinder(void);
bool rangefinder_alt_ok(void);
void init_compass();
#if OPTFLOW == ENABLED
void init_optflow();
void update_optical_flow(void);
#endif
void read_battery(void);
void gripper_update();
void terrain_update();

4
ArduSub/sensors.cpp

@ -103,9 +103,9 @@ void Sub::init_compass() @@ -103,9 +103,9 @@ void Sub::init_compass()
}
// initialise optical flow sensor
#if OPTFLOW == ENABLED
void Sub::init_optflow()
{
#if OPTFLOW == ENABLED
// exit immediately if not enabled
if (!optflow.enabled()) {
return;
@ -113,8 +113,8 @@ void Sub::init_optflow() @@ -113,8 +113,8 @@ void Sub::init_optflow()
// initialise optical flow sensor
optflow.init();
#endif // OPTFLOW == ENABLED
}
#endif // OPTFLOW == ENABLED
// called at 200hz
#if OPTFLOW == ENABLED

2
ArduSub/system.cpp

@ -115,7 +115,9 @@ void Sub::init_ardupilot() @@ -115,7 +115,9 @@ void Sub::init_ardupilot()
pos_control.set_dt(MAIN_LOOP_SECONDS);
// init the optical flow sensor
#if OPTFLOW == ENABLED
init_optflow();
#endif
#if MOUNT == ENABLED
// initialise camera mount

Loading…
Cancel
Save