ArduPlane: support MAVLINK_MSG_ID_MISSION_ITEM_INT

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

View File

@ -1662,8 +1662,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break; break;
} }
// XXX read a WP from EEPROM and send it to the GCS // XXX read a WP from EEPROM and send it to the GCS
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
case MAVLINK_MSG_ID_MISSION_REQUEST: case MAVLINK_MSG_ID_MISSION_REQUEST:
{ {
handle_mission_request(plane.mission, msg); handle_mission_request(plane.mission, msg);
@ -1735,6 +1735,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} }
break; break;
} }
// GCS has sent us a mission item, store to EEPROM
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
{
if (handle_mission_item(msg, plane.mission)) {
plane.DataFlash.Log_Write_EntireMission(plane.mission);
}
break;
}
#if GEOFENCE_ENABLED == ENABLED #if GEOFENCE_ENABLED == ENABLED
// receive a fence point from GCS and store in EEPROM // receive a fence point from GCS and store in EEPROM

View File

@ -7,4 +7,5 @@ void Plane::init_capabilities(void)
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT); 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_PARAM_FLOAT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_COMMAND_INT); hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_COMMAND_INT);
hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_INT);
} }