|
|
|
@ -1396,6 +1396,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1396,6 +1396,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16 |
|
|
|
|
case MAVLINK_MSG_ID_SERIAL_CONTROL: |
|
|
|
|
handle_serial_control(msg, gps); |
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
|
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE: // MAV ID: 202 |
|
|
|
|
camera.configure_msg(msg); |
|
|
|
|