Plane: Allow compass calibrator to manage size of buffer

This commit is contained in:
Michael du Breuil 2016-10-24 22:18:22 -07:00 committed by Andrew Tridgell
parent deec4ec6af
commit fd24e944b8
1 changed files with 0 additions and 2 deletions

View File

@ -855,12 +855,10 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
break; break;
case MSG_MAG_CAL_PROGRESS: case MSG_MAG_CAL_PROGRESS:
CHECK_PAYLOAD_SIZE(MAG_CAL_PROGRESS);
plane.compass.send_mag_cal_progress(chan); plane.compass.send_mag_cal_progress(chan);
break; break;
case MSG_MAG_CAL_REPORT: case MSG_MAG_CAL_REPORT:
CHECK_PAYLOAD_SIZE(MAG_CAL_REPORT);
plane.compass.send_mag_cal_report(chan); plane.compass.send_mag_cal_report(chan);
break; break;