Plane: check for optflow enable in more places

This commit is contained in:
Andrew Tridgell 2016-07-12 08:44:04 +10:00
parent d018a32545
commit e8976d3a89
2 changed files with 9 additions and 7 deletions

View File

@ -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;

View File

@ -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
}