Plane: if receiving last mission item then log new mission to dataflash
This commit is contained in:
parent
d94c95a6ef
commit
ba29967454
@ -1359,7 +1359,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
// GCS has sent us a command from GCS, store to EEPROM
|
||||
case MAVLINK_MSG_ID_MISSION_ITEM:
|
||||
{
|
||||
handle_mission_item(msg, mission);
|
||||
if (handle_mission_item(msg, mission)) {
|
||||
Log_Write_EntireMission();
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -245,6 +245,13 @@ static void Log_Write_Startup(uint8_t type)
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
|
||||
// write all commands to the dataflash as well
|
||||
Log_Write_EntireMission();
|
||||
}
|
||||
|
||||
static void Log_Write_EntireMission()
|
||||
{
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("New mission"));
|
||||
|
||||
AP_Mission::Mission_Command cmd;
|
||||
for (uint16_t i = 0; i < mission.num_commands(); i++) {
|
||||
if (mission.read_cmd_from_storage(i,cmd)) {
|
||||
@ -518,6 +525,7 @@ static void start_logging()
|
||||
|
||||
// dummy functions
|
||||
static void Log_Write_Startup(uint8_t type) {}
|
||||
static void Log_Write_EntireMission() {}
|
||||
static void Log_Write_Current() {}
|
||||
static void Log_Write_Nav_Tuning() {}
|
||||
static void Log_Write_TECS_Tuning() {}
|
||||
|
Loading…
Reference in New Issue
Block a user