mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
global: use static method to construct AP_OpticalFlow
This commit is contained in:
parent
04c3dca3ce
commit
fbe0d9761c
@ -185,7 +185,7 @@ private:
|
||||
FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void));
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
OpticalFlow optflow{ahrs};
|
||||
OpticalFlow optflow = OpticalFlow::create(ahrs);
|
||||
#endif
|
||||
|
||||
// RSSI
|
||||
|
@ -233,7 +233,7 @@ private:
|
||||
|
||||
// Optical flow sensor
|
||||
#if OPTFLOW == ENABLED
|
||||
OpticalFlow optflow{ahrs};
|
||||
OpticalFlow optflow = OpticalFlow::create(ahrs);
|
||||
#endif
|
||||
|
||||
// gnd speed limit required to observe optical flow sensor limits
|
||||
|
@ -279,7 +279,7 @@ private:
|
||||
|
||||
#if OPTFLOW == ENABLED
|
||||
// Optical flow sensor
|
||||
OpticalFlow optflow{ahrs};
|
||||
OpticalFlow optflow = OpticalFlow::create(ahrs);
|
||||
#endif
|
||||
|
||||
// Rally Ponints
|
||||
|
@ -200,7 +200,7 @@ private:
|
||||
|
||||
// Optical flow sensor
|
||||
#if OPTFLOW == ENABLED
|
||||
OpticalFlow optflow {ahrs};
|
||||
OpticalFlow optflow = OpticalFlow::create(ahrs);
|
||||
#endif
|
||||
|
||||
// gnd speed limit required to observe optical flow sensor limits
|
||||
|
@ -34,7 +34,7 @@ public:
|
||||
};
|
||||
|
||||
static DummyVehicle vehicle;
|
||||
static OpticalFlow optflow(vehicle.ahrs);
|
||||
static OpticalFlow optflow = OpticalFlow::create(vehicle.ahrs);
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user