mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
Plane: check for optflow enable in more places
This commit is contained in:
parent
d018a32545
commit
e8976d3a89
@ -818,8 +818,10 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
|
||||
|
||||
case MSG_OPTICAL_FLOW:
|
||||
#if OPTFLOW == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(OPTICAL_FLOW);
|
||||
send_opticalflow(plane.ahrs, plane.optflow);
|
||||
if (plane.optflow.enabled()) {
|
||||
CHECK_PAYLOAD_SIZE(OPTICAL_FLOW);
|
||||
send_opticalflow(plane.ahrs, plane.optflow);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
@ -179,7 +179,9 @@ void Plane::init_ardupilot()
|
||||
|
||||
#if OPTFLOW == ENABLED
|
||||
// make optflow available to libraries
|
||||
ahrs.set_optflow(&optflow);
|
||||
if (optflow.enabled()) {
|
||||
ahrs.set_optflow(&optflow);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Register mavlink_delay_cb, which will run anytime you have
|
||||
@ -246,11 +248,9 @@ void Plane::init_ardupilot()
|
||||
|
||||
// initialise sensor
|
||||
#if OPTFLOW == ENABLED
|
||||
if (!optflow.enabled()) {
|
||||
return;
|
||||
if (optflow.enabled()) {
|
||||
optflow.init();
|
||||
}
|
||||
|
||||
optflow.init();
|
||||
#endif
|
||||
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user