mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: avoid linking optflow on APM2
not used, just taking memory
This commit is contained in:
parent
954ec71630
commit
266857c595
@ -259,8 +259,10 @@ private:
|
|||||||
AP_Camera camera {&relay};
|
AP_Camera camera {&relay};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if OPTFLOW == ENABLED
|
||||||
// Optical flow sensor
|
// Optical flow sensor
|
||||||
OpticalFlow optflow;
|
OpticalFlow optflow;
|
||||||
|
#endif
|
||||||
|
|
||||||
// Rally Ponints
|
// Rally Ponints
|
||||||
AP_Rally rally {ahrs};
|
AP_Rally rally {ahrs};
|
||||||
|
@ -184,8 +184,10 @@ void Plane::init_ardupilot()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if OPTFLOW == ENABLED
|
||||||
// make optflow available to libraries
|
// make optflow available to libraries
|
||||||
ahrs.set_optflow(&optflow);
|
ahrs.set_optflow(&optflow);
|
||||||
|
#endif
|
||||||
|
|
||||||
// Register mavlink_delay_cb, which will run anytime you have
|
// Register mavlink_delay_cb, which will run anytime you have
|
||||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||||
|
Loading…
Reference in New Issue
Block a user