|
|
|
@ -589,13 +589,24 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
@@ -589,13 +589,24 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|
|
|
|
mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index); |
|
|
|
|
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; |
|
|
|
|
|
|
|
|
|
case MSG_RETRY_DEFERRED: |
|
|
|
|
case MSG_TERRAIN: |
|
|
|
|
case MSG_OPTICAL_FLOW: |
|
|
|
|
case MSG_GIMBAL_REPORT: |
|
|
|
|
case MSG_RPM: |
|
|
|
|
break; // just here to prevent a warning
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
return true; |
|
|
|
@ -820,6 +831,8 @@ GCS_MAVLINK::data_stream_send(void)
@@ -820,6 +831,8 @@ GCS_MAVLINK::data_stream_send(void)
|
|
|
|
|
send_message(MSG_RANGEFINDER); |
|
|
|
|
send_message(MSG_SYSTEM_TIME); |
|
|
|
|
send_message(MSG_BATTERY2); |
|
|
|
|
send_message(MSG_MAG_CAL_REPORT); |
|
|
|
|
send_message(MSG_MAG_CAL_PROGRESS); |
|
|
|
|
send_message(MSG_MOUNT_STATUS); |
|
|
|
|
send_message(MSG_EKF_STATUS_REPORT); |
|
|
|
|
} |
|
|
|
@ -1036,6 +1049,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1036,6 +1049,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_START_MAG_CAL: |
|
|
|
|
case MAV_CMD_DO_ACCEPT_MAG_CAL: |
|
|
|
|
case MAV_CMD_DO_CANCEL_MAG_CAL: |
|
|
|
|
result = rover.compass.handle_mag_cal_command(packet); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|