mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Rover: Allow compass to manage buffer space for MAG_CAL
This commit is contained in:
parent
615aa74bf9
commit
6e4354675a
@ -571,12 +571,10 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
||||
break;
|
||||
|
||||
case MSG_MAG_CAL_PROGRESS:
|
||||
CHECK_PAYLOAD_SIZE(MAG_CAL_PROGRESS);
|
||||
rover.compass.send_mag_cal_progress(chan);
|
||||
break;
|
||||
|
||||
case MSG_MAG_CAL_REPORT:
|
||||
CHECK_PAYLOAD_SIZE(MAG_CAL_REPORT);
|
||||
rover.compass.send_mag_cal_report(chan);
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user