|
|
@ -1459,11 +1459,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg) |
|
|
|
send_autopilot_version(FIRMWARE_VERSION); |
|
|
|
send_autopilot_version(FIRMWARE_VERSION); |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_LED_CONTROL: |
|
|
|
|
|
|
|
// send message to Notify
|
|
|
|
|
|
|
|
AP_Notify::handle_led_control(msg); |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_SET_HOME_POSITION: { |
|
|
|
case MAVLINK_MSG_ID_SET_HOME_POSITION: { |
|
|
|
mavlink_set_home_position_t packet; |
|
|
|
mavlink_set_home_position_t packet; |
|
|
|
mavlink_msg_set_home_position_decode(msg, &packet); |
|
|
|
mavlink_msg_set_home_position_decode(msg, &packet); |
|
|
|