ArduCopter: support MAVLINK_MSG_ID_MISSION_ITEM_INT

This commit is contained in:
Michael Oborne 2016-03-08 10:41:11 +08:00 committed by Andrew Tridgell
parent 8816c5c681
commit 5848d8a5e6
2 changed files with 11 additions and 1 deletions

View File

@ -1070,9 +1070,18 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
break;
}
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
{
if (handle_mission_item(msg, copter.mission)) {
copter.DataFlash.Log_Write_EntireMission(copter.mission);
}
break;
}
// read an individual command from EEPROM and send it to the GCS
case MAVLINK_MSG_ID_MISSION_REQUEST: // MAV ID: 40
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
case MAVLINK_MSG_ID_MISSION_REQUEST: // MAV ID: 40, 51
{
handle_mission_request(copter.mission, msg);
break;

View File

@ -6,6 +6,7 @@ void Copter::init_capabilities(void)
{
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_INT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION);