mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: split logging of mission-upload vs mission-execution
This commit is contained in:
parent
1d947396b3
commit
4237a33ce6
|
@ -896,9 +896,10 @@ void AP_Logger::Write_Parameter(const char *name, float value)
|
|||
}
|
||||
|
||||
void AP_Logger::Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd)
|
||||
const AP_Mission::Mission_Command &cmd,
|
||||
LogMessages id)
|
||||
{
|
||||
FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd));
|
||||
FOR_EACH_BACKEND(Write_Mission_Cmd(mission, cmd, id));
|
||||
}
|
||||
|
||||
#if HAL_RALLY_ENABLED
|
||||
|
|
|
@ -273,8 +273,15 @@ public:
|
|||
uint8_t source_component,
|
||||
MAV_RESULT result,
|
||||
bool was_command_long=false);
|
||||
void Write_MISE(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd) {
|
||||
Write_Mission_Cmd(mission, cmd, LOG_MISE_MSG);
|
||||
}
|
||||
void Write_CMD(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd) {
|
||||
Write_Mission_Cmd(mission, cmd, LOG_CMD_MSG);
|
||||
}
|
||||
void Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd);
|
||||
const AP_Mission::Mission_Command &cmd,
|
||||
LogMessages id);
|
||||
void Write_RallyPoint(uint8_t total,
|
||||
uint8_t sequence,
|
||||
const class RallyLocation &rally_point);
|
||||
|
|
|
@ -140,7 +140,8 @@ public:
|
|||
bool Write_Message(const char *message);
|
||||
bool Write_MessageF(const char *fmt, ...);
|
||||
bool Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd);
|
||||
const AP_Mission::Mission_Command &cmd,
|
||||
LogMessages id);
|
||||
bool Write_Mode(uint8_t mode, const ModeReason reason);
|
||||
bool Write_Parameter(const char *name, float value, float default_val);
|
||||
bool Write_Parameter(const AP_Param *ap,
|
||||
|
|
|
@ -300,12 +300,13 @@ void AP_Logger::Write_Command(const mavlink_command_int_t &packet,
|
|||
}
|
||||
|
||||
bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission,
|
||||
const AP_Mission::Mission_Command &cmd)
|
||||
const AP_Mission::Mission_Command &cmd,
|
||||
LogMessages msgid)
|
||||
{
|
||||
mavlink_mission_item_int_t mav_cmd = {};
|
||||
AP_Mission::mission_cmd_to_mavlink_int(cmd,mav_cmd);
|
||||
const struct log_CMD pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
|
||||
LOG_PACKET_HEADER_INIT(msgid),
|
||||
time_us : AP_HAL::micros64(),
|
||||
command_total : mission.num_commands(),
|
||||
sequence : mav_cmd.seq,
|
||||
|
|
|
@ -437,7 +437,7 @@ void LoggerMessageWriter_WriteEntireMission::process() {
|
|||
// upon failure to write the mission we will re-read from
|
||||
// storage; this could be improved.
|
||||
if (_mission->read_cmd_from_storage(_mission_number_to_send,cmd)) {
|
||||
if (!_logger_backend->Write_Mission_Cmd(*_mission, cmd)) {
|
||||
if (!_logger_backend->Write_Mission_Cmd(*_mission, cmd, LOG_CMD_MSG)) {
|
||||
return; // call me again
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue