|
|
|
@ -1762,6 +1762,91 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
@@ -1762,6 +1762,91 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
|
|
|
|
|
case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS: |
|
|
|
|
DataFlash_Class::instance()->handle_mavlink_msg(*this, msg); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: |
|
|
|
|
/* fall through */ |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_COUNT: |
|
|
|
|
/* fall through */ |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: |
|
|
|
|
/* fall through */ |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM: |
|
|
|
|
/* fall through */ |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM_INT: |
|
|
|
|
/* fall through */ |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST_INT: |
|
|
|
|
/* fall through */ |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST: |
|
|
|
|
/* fall through */ |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ACK: |
|
|
|
|
/* fall through */ |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_SET_CURRENT: |
|
|
|
|
handle_common_mission_message(msg); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void GCS_MAVLINK::handle_common_mission_message(mavlink_message_t *msg) |
|
|
|
|
{ |
|
|
|
|
AP_Mission *_mission = get_mission(); |
|
|
|
|
if (_mission == nullptr) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
switch (msg->msgid) { |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: // MAV ID: 38
|
|
|
|
|
{ |
|
|
|
|
handle_mission_write_partial_list(*_mission, msg); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// GCS has sent us a mission item, store to EEPROM
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM: // MAV ID: 39
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ITEM_INT: |
|
|
|
|
{ |
|
|
|
|
if (handle_mission_item(msg, *_mission)) { |
|
|
|
|
DataFlash_Class::instance()->Log_Write_EntireMission(*_mission); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// read an individual command from EEPROM and send it to the GCS
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST_INT: |
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST: // MAV ID: 40, 51
|
|
|
|
|
{ |
|
|
|
|
handle_mission_request(*_mission, msg); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_SET_CURRENT: // MAV ID: 41
|
|
|
|
|
{ |
|
|
|
|
handle_mission_set_current(*_mission, msg); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// GCS request the full list of commands, we return just the number and leave the GCS to then request each command individually
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: // MAV ID: 43
|
|
|
|
|
{ |
|
|
|
|
handle_mission_request_list(*_mission, msg); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// GCS provides the full number of commands it wishes to upload
|
|
|
|
|
// individual commands will then be sent from the GCS using the MAVLINK_MSG_ID_MISSION_ITEM message
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_COUNT: // MAV ID: 44
|
|
|
|
|
{ |
|
|
|
|
handle_mission_count(*_mission, msg); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: // MAV ID: 45
|
|
|
|
|
{ |
|
|
|
|
handle_mission_clear_all(*_mission, msg); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_MISSION_ACK: |
|
|
|
|
/* not used */ |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|