Browse Source

AP_Logger: use existing LoggerMessageWriter to log uploaded missions

Instead of creating a MessageWriter explicitly to log uploaded missions
we fiddle the state of the one stored in the startup message writer.

This has the advantage of being much more likely to log the entire
mission (as the buffer constraint is removed), and with the addition of
a time-remaining check much less likely to cause a timing glitch.
c415-sdk
Peter Barker 5 years ago committed by Peter Barker
parent
commit
678d6f43c5
  1. 7
      libraries/AP_Logger/AP_Logger_Backend.cpp
  2. 4
      libraries/AP_Logger/AP_Logger_Backend.h
  3. 7
      libraries/AP_Logger/LogFile.cpp
  4. 67
      libraries/AP_Logger/LoggerMessageWriter.cpp
  5. 9
      libraries/AP_Logger/LoggerMessageWriter.h

7
libraries/AP_Logger/AP_Logger_Backend.cpp

@ -440,9 +440,8 @@ bool AP_Logger_Backend::Write_RallyPoint(uint8_t total, @@ -440,9 +440,8 @@ bool AP_Logger_Backend::Write_RallyPoint(uint8_t total,
}
// Write rally points
void AP_Logger_Backend::Write_Rally()
bool AP_Logger_Backend::Write_Rally()
{
LoggerMessageWriter_WriteAllRallyPoints writer;
writer.set_logger_backend(this);
writer.process();
// kick off asynchronous write:
return _startup_messagewriter->writeallrallypoints();
}

4
libraries/AP_Logger/AP_Logger_Backend.h

@ -83,11 +83,11 @@ public: @@ -83,11 +83,11 @@ public:
uint8_t num_multipliers() const;
const struct MultiplierStructure *multiplier(uint8_t multiplier) const;
void Write_EntireMission();
bool Write_EntireMission();
bool Write_RallyPoint(uint8_t total,
uint8_t sequence,
const RallyLocation &rally_point);
void Write_Rally();
bool Write_Rally();
bool Write_Format(const struct LogStructure *structure);
bool Write_Message(const char *message);
bool Write_MessageF(const char *fmt, ...);

7
libraries/AP_Logger/LogFile.cpp

@ -448,11 +448,10 @@ bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission, @@ -448,11 +448,10 @@ bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission,
return WriteBlock(&pkt, sizeof(pkt));
}
void AP_Logger_Backend::Write_EntireMission()
bool AP_Logger_Backend::Write_EntireMission()
{
LoggerMessageWriter_WriteEntireMission writer{};
writer.set_logger_backend(this);
writer.process();
// kick off asynchronous write:
return _startup_messagewriter->writeentiremission();
}
// Write a text message to the log

67
libraries/AP_Logger/LoggerMessageWriter.cpp

@ -104,38 +104,27 @@ void LoggerMessageWriter_DFLogStart::process() @@ -104,38 +104,27 @@ void LoggerMessageWriter_DFLogStart::process()
ap = AP_Param::next_scalar(&token, &type);
}
stage = Stage::SYSINFO;
stage = Stage::RUNNING_SUBWRITERS;
FALLTHROUGH;
case Stage::SYSINFO:
_writesysinfo.process();
if (AP::scheduler().time_available_usec() < MIN_LOOP_TIME_REMAINING_FOR_MESSAGE_WRITE_US) {
return;
}
case Stage::RUNNING_SUBWRITERS:
if (!_writesysinfo.finished()) {
return;
}
stage = Stage::WRITE_ENTIRE_MISSION;
FALLTHROUGH;
case Stage::WRITE_ENTIRE_MISSION:
_writeentiremission.process();
if (AP::scheduler().time_available_usec() < MIN_LOOP_TIME_REMAINING_FOR_MESSAGE_WRITE_US) {
return;
_writesysinfo.process();
if (!_writesysinfo.finished()) {
return;
}
}
if (!_writeentiremission.finished()) {
return;
}
stage = Stage::WRITE_ALL_RALLY_POINTS;
FALLTHROUGH;
case Stage::WRITE_ALL_RALLY_POINTS:
_writeallrallypoints.process();
if (AP::scheduler().time_available_usec() < MIN_LOOP_TIME_REMAINING_FOR_MESSAGE_WRITE_US) {
return;
_writeentiremission.process();
if (!_writeentiremission.finished()) {
return;
}
}
if (!_writeallrallypoints.finished()) {
return;
_writeallrallypoints.process();
if (!_writeallrallypoints.finished()) {
return;
}
}
stage = Stage::VEHICLE_MESSAGES;
FALLTHROUGH;
@ -160,6 +149,28 @@ void LoggerMessageWriter_DFLogStart::process() @@ -160,6 +149,28 @@ void LoggerMessageWriter_DFLogStart::process()
_finished = true;
}
bool LoggerMessageWriter_DFLogStart::writeentiremission()
{
if (stage != Stage::DONE) {
return false;
}
stage = Stage::RUNNING_SUBWRITERS;
_finished = false;
_writeentiremission.reset();
return true;
}
bool LoggerMessageWriter_DFLogStart::writeallrallypoints()
{
if (stage != Stage::DONE) {
return false;
}
stage = Stage::RUNNING_SUBWRITERS;
_finished = false;
_writeallrallypoints.reset();
return true;
}
void LoggerMessageWriter_WriteSysInfo::reset()
{
LoggerMessageWriter::reset();
@ -250,6 +261,9 @@ void LoggerMessageWriter_WriteAllRallyPoints::process() @@ -250,6 +261,9 @@ void LoggerMessageWriter_WriteAllRallyPoints::process()
case Stage::WRITE_ALL_RALLY_POINTS:
while (_rally_number_to_send < _rally->get_rally_total()) {
if (AP::scheduler().time_available_usec() < MIN_LOOP_TIME_REMAINING_FOR_MESSAGE_WRITE_US) {
return;
}
RallyLocation rallypoint;
if (_rally->get_rally_point_with_index(_rally_number_to_send, rallypoint)) {
if (!_logger_backend->Write_RallyPoint(
@ -297,6 +311,9 @@ void LoggerMessageWriter_WriteEntireMission::process() { @@ -297,6 +311,9 @@ void LoggerMessageWriter_WriteEntireMission::process() {
case Stage::WRITE_MISSION_ITEMS: {
AP_Mission::Mission_Command cmd;
while (_mission_number_to_send < _mission->num_commands()) {
if (AP::scheduler().time_available_usec() < MIN_LOOP_TIME_REMAINING_FOR_MESSAGE_WRITE_US) {
return;
}
// 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)) {

9
libraries/AP_Logger/LoggerMessageWriter.h

@ -91,6 +91,11 @@ public: @@ -91,6 +91,11 @@ public:
void process() override;
bool fmt_done() { return _fmt_done; }
// reset some writers so we push stuff out to logs again. Will
// only work if we are in state DONE!
bool writeentiremission();
bool writeallrallypoints();
private:
enum Stage {
@ -99,10 +104,8 @@ private: @@ -99,10 +104,8 @@ private:
MULTIPLIERS,
FORMAT_UNITS,
PARMS,
SYSINFO,
WRITE_ENTIRE_MISSION,
WRITE_ALL_RALLY_POINTS,
VEHICLE_MESSAGES,
RUNNING_SUBWRITERS, // must be last thing to run as we can redo bits of these
DONE,
};

Loading…
Cancel
Save