mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Sub: Fix compile-time OPTFLOW enabling switch
This commit is contained in:
parent
b3beb5e1c4
commit
854275459d
@ -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 @@
|
||||
#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:
|
||||
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();
|
||||
|
@ -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()
|
||||
|
||||
// initialise optical flow sensor
|
||||
optflow.init();
|
||||
#endif // OPTFLOW == ENABLED
|
||||
}
|
||||
#endif // OPTFLOW == ENABLED
|
||||
|
||||
// called at 200hz
|
||||
#if OPTFLOW == ENABLED
|
||||
|
@ -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…
Reference in New Issue
Block a user