Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Logger: make block logger conform to logging expectations #14299

Merged
merged 2 commits into from
Sep 5, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -5476,6 +5476,14 @@ def tests2(self):
"Test that Alt Estimation is mandatory for ALT_HOLD",
self.test_alt_estimate_prearm),

("DataFlash",
"Test DataFlash Block backend",
self.test_dataflash_sitl),

("DataFlashErase",
"Test DataFlash Block backend erase",
self.test_dataflash_erase),

("LogUpload",
"Log upload",
self.log_upload),
Expand Down
149 changes: 144 additions & 5 deletions Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
from pymavlink import mavparm

from pysim import util, vehicleinfo
from io import StringIO

# a list of pexpect objects to read while waiting for
# messages. This keeps the output to stdout flowing
Expand Down Expand Up @@ -5302,20 +5303,57 @@ def test_dataflash_over_mavlink(self):
raise ex

def test_dataflash_sitl(self):
"""Test the basic functionality of block logging"""
self.context_push()
ex = None
try:
self.set_parameter("LOG_BACKEND_TYPE", 5)
self.set_parameter("LOG_BACKEND_TYPE", 4)
self.set_parameter("LOG_FILE_DSRMROT", 1)
self.reboot_sitl()
self.drain_mav() # hopefully draining COMMAND_ACK from that failed arm
# First log created here, but we are in chip erase so ignored
self.mavproxy.send("module load log\n")
# self.mavproxy.expect("Loaded module log\n")
self.mavproxy.send("log erase\n")
self.mavproxy.expect("Chip erase complete")

self.wait_ready_to_arm()
if self.is_copter() or self.is_plane():
self.set_autodisarm_delay(0)
self.arm_vehicle()
self.delay_sim_time(5)
self.disarm_vehicle()
# First log created here
andyp1per marked this conversation as resolved.
Show resolved Hide resolved
self.delay_sim_time(2)
self.arm_vehicle()
self.delay_sim_time(5)
self.disarm_vehicle()
# Second log created here
andyp1per marked this conversation as resolved.
Show resolved Hide resolved
self.delay_sim_time(2)
self.mavproxy.send("log list\n")
self.mavproxy.expect("Log 1 numLogs 1 lastLog 1 size")
self.mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)
log_num = int(self.mavproxy.match.group(1))
numlogs = int(self.mavproxy.match.group(2))
lastlog = int(self.mavproxy.match.group(3))
size = int(self.mavproxy.match.group(4))
if numlogs != 2 or log_num != 1 or size <= 0:
raise NotAchievedException("Unexpected log information %d %d %d" % (log_num, numlogs, lastlog))
self.progress("Log size: %d" % size)
self.reboot_sitl()
# This starts a new log with a time of 0, wait for arm so that we can insert the correct time
self.wait_ready_to_arm()
# Third log created here
self.mavproxy.send("log list\n")
self.mavproxy.expect("Log 1 numLogs 2 lastLog 2 size")
self.mavproxy.expect("Log 1 numLogs 3 lastLog 3 size")

# Download second and third logs
self.mavproxy.send("log download 2 logs/dataflash-log-002.BIN\n")
self.mavproxy.expect("Finished downloading", timeout=120)
self.mavproxy.send("log download 3 logs/dataflash-log-003.BIN\n")
self.mavproxy.expect("Finished downloading", timeout=120)

# Erase the logs
self.mavproxy.send("log erase\n")
self.mavproxy.expect("Chip erase complete")
andyp1per marked this conversation as resolved.
Show resolved Hide resolved

except Exception as e:
self.progress("Exception (%s) caught" % str(e))
ex = e
Expand All @@ -5325,6 +5363,107 @@ def test_dataflash_sitl(self):
if ex is not None:
raise ex

def validate_log_file(self, logname, header_errors=0):
"""Validate the contents of a log file"""
# read the downloaded log - it must parse without error
class Capturing(list):
def __enter__(self):
self._stderr = sys.stderr
sys.stderr = self._stringio = StringIO()
return self
def __exit__(self, *args):
self.extend(self._stringio.getvalue().splitlines())
del self._stringio # free up some memory
sys.stderr = self._stderr

with Capturing() as df_output:
try:
mlog = mavutil.mavlink_connection(logname)
while True:
m = mlog.recv_match()
if m is None:
break
except Exception as e:
raise NotAchievedException("Error reading log file %s: %s" % (logname, str(e)))

herrors = 0

for msg in df_output:
if msg.startswith("bad header") or msg.startswith("unknown msg type"):
herrors = herrors + 1

if herrors > header_errors:
raise NotAchievedException("Error parsing log file %s, %d header errors" % (logname, herrors))

def test_dataflash_erase(self):
"""Test that erasing the dataflash chip and creating a new log is error free"""
ex = None
self.context_push()
try:
self.set_parameter("LOG_BACKEND_TYPE", 4)
self.reboot_sitl()
self.mavproxy.send("module load log\n")
self.mavproxy.send("log erase\n")
self.mavproxy.expect("Chip erase complete")
self.set_parameter("LOG_DISARMED", 1)
self.delay_sim_time(3)
self.set_parameter("LOG_DISARMED", 0)
self.mavproxy.send("log download 1 logs/dataflash-log-erase.BIN\n")
self.mavproxy.expect("Finished downloading", timeout=120)
# read the downloaded log - it must parse without error
self.validate_log_file("logs/dataflash-log-erase.BIN")

self.start_subtest("Test file wrapping results in a valid file")
# roughly 4mb
self.set_parameter("LOG_FILE_DSRMROT", 1)
self.set_parameter("LOG_BITMASK", 131071)
self.wait_ready_to_arm()
if self.is_copter() or self.is_plane():
self.set_autodisarm_delay(0)
self.arm_vehicle()
self.delay_sim_time(30)
self.disarm_vehicle()
# roughly 4mb
self.arm_vehicle()
self.delay_sim_time(30)
self.disarm_vehicle()
# roughly 9mb, should wrap around
self.arm_vehicle()
self.delay_sim_time(50)
self.disarm_vehicle()
# make sure we have finished logging
self.delay_sim_time(15)
self.mavproxy.send("log list\n")
self.mavproxy.expect("Log ([0-9]+) numLogs ([0-9]+) lastLog ([0-9]+) size ([0-9]+)", timeout=120)
if int(self.mavproxy.match.group(2)) != 2:
raise NotAchievedException("Expected 2 logs")

self.mavproxy.send("log download 1 logs/dataflash-log-erase2.BIN\n")
self.mavproxy.expect("Finished downloading", timeout=120)
self.validate_log_file("logs/dataflash-log-erase2.BIN", 1)

self.mavproxy.send("log download latest logs/dataflash-log-erase3.BIN\n")
self.mavproxy.expect("Finished downloading", timeout=120)
self.validate_log_file("logs/dataflash-log-erase3.BIN", 1)

# clean up
self.mavproxy.send("log erase\n")
self.mavproxy.expect("Chip erase complete")

# clean up
self.mavproxy.send("log erase\n")
self.mavproxy.expect("Chip erase complete")

except Exception as e:
self.progress("Exception (%s) caught" % str(e))
ex = e

self.mavproxy.send("module unload log\n")
self.context_pop()
self.reboot_sitl()
if ex is not None:
raise ex

def test_arm_feature(self):
"""Common feature to test."""
# TEST ARMING/DISARM
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_Logger/AP_Logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
AP_GROUPINFO("_BACKEND_TYPE", 0, AP_Logger, _params.backend_types, uint8_t(HAL_LOGGING_BACKENDS_DEFAULT)),

// @Param: _FILE_BUFSIZE
// @DisplayName: Maximum AP_Logger File Backend buffer size (in kilobytes)
// @Description: The AP_Logger_File backend uses a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes.
// @DisplayName: Maximum AP_Logger File and Block Backend buffer size (in kilobytes)
// @Description: The File and Block backends use a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes.
// @User: Standard
AP_GROUPINFO("_FILE_BUFSIZE", 1, AP_Logger, _params.file_bufsize, HAL_LOGGING_FILE_BUFSIZE),

Expand All @@ -75,7 +75,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {

// @Param: _FILE_DSRMROT
// @DisplayName: Stop logging to current file on disarm
// @Description: When set, the current log file is closed when the vehicle is disarmed. If LOG_DISARMED is set then a fresh log will be opened.
// @Description: When set, the current log file is closed when the vehicle is disarmed. If LOG_DISARMED is set then a fresh log will be opened. Applies to the File and Block logging backends.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("_FILE_DSRMROT", 4, AP_Logger, _params.file_disarm_rot, 0),
Expand Down
120 changes: 120 additions & 0 deletions libraries/AP_Logger/AP_Logger_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,20 @@ AP_Logger_Backend::vehicle_startup_message_Writer AP_Logger_Backend::vehicle_mes
void AP_Logger_Backend::periodic_10Hz(const uint32_t now)
{
}

void AP_Logger_Backend::periodic_1Hz()
{
if (_rotate_pending && !logging_enabled()) {
_rotate_pending = false;
// handle log rotation once we stop logging
stop_logging();
}
df_stats_log();
}

void AP_Logger_Backend::periodic_fullrate()
{
push_log_blocks();
}

void AP_Logger_Backend::periodic_tasks()
Expand All @@ -74,8 +83,10 @@ void AP_Logger_Backend::periodic_tasks()

void AP_Logger_Backend::start_new_log_reset_variables()
{
_dropped = 0;
_startup_messagewriter->reset();
_front.backend_starting_new_log(this);
_log_file_size_bytes = 0;
}

// this method can be overridden to do extra things with your buffer.
Expand Down Expand Up @@ -410,6 +421,18 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical)
return true;
}

void AP_Logger_Backend::PrepForArming()
{
if (_rotate_pending) {
_rotate_pending = false;
stop_logging();
}
if (logging_started()) {
return;
}
start_new_log();
}

bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...)
{
char msg[65] {}; // sizeof(log_Message.msg) + null-termination
Expand Down Expand Up @@ -445,3 +468,100 @@ bool AP_Logger_Backend::Write_Rally()
// kick off asynchronous write:
return _startup_messagewriter->writeallrallypoints();
}

/*
convert a list entry number back into a log number (which can then
be converted into a filename). A "list entry number" is a sequence
where the oldest log has a number of 1, the second-from-oldest 2,
and so on. Thus the highest list entry number is equal to the
number of logs.
*/
uint16_t AP_Logger_Backend::log_num_from_list_entry(const uint16_t list_entry)
{
uint16_t oldest_log = find_oldest_log();
if (oldest_log == 0) {
return 0;
}

uint32_t log_num = oldest_log + list_entry - 1;
if (log_num > MAX_LOG_FILES) {
log_num -= MAX_LOG_FILES;
}
return (uint16_t)log_num;
}

// find_oldest_log - find oldest log
// returns 0 if no log was found
uint16_t AP_Logger_Backend::find_oldest_log()
{
if (_cached_oldest_log != 0) {
return _cached_oldest_log;
}

uint16_t last_log_num = find_last_log();
if (last_log_num == 0) {
return 0;
}

_cached_oldest_log = last_log_num - get_num_logs() + 1;

return _cached_oldest_log;
}

void AP_Logger_Backend::vehicle_was_disarmed()
{
if (_front._params.file_disarm_rot) {
// rotate our log. Closing the current one and letting the
// logging restart naturally based on log_disarmed should do
// the trick:
_rotate_pending = true;
}
}

// this sensor is enabled if we should be logging at the moment
bool AP_Logger_Backend::logging_enabled() const
{
if (hal.util->get_soft_armed() ||
_front.log_while_disarmed()) {
return true;
}
return false;
}

void AP_Logger_Backend::Write_AP_Logger_Stats_File(const struct df_stats &_stats)
{
struct log_DSF pkt = {
andyp1per marked this conversation as resolved.
Show resolved Hide resolved
LOG_PACKET_HEADER_INIT(LOG_DF_FILE_STATS),
time_us : AP_HAL::micros64(),
dropped : _dropped,
blocks : _stats.blocks,
bytes : _stats.bytes,
buf_space_min : _stats.buf_space_min,
buf_space_max : _stats.buf_space_max,
buf_space_avg : (_stats.blocks) ? (_stats.buf_space_sigma / _stats.blocks) : 0,
};
WriteBlock(&pkt, sizeof(pkt));
}

void AP_Logger_Backend::df_stats_gather(const uint16_t bytes_written, uint32_t space_remaining) {
andyp1per marked this conversation as resolved.
Show resolved Hide resolved
if (space_remaining < stats.buf_space_min) {
stats.buf_space_min = space_remaining;
}
if (space_remaining > stats.buf_space_max) {
stats.buf_space_max = space_remaining;
}
stats.buf_space_sigma += space_remaining;
stats.bytes += bytes_written;
_log_file_size_bytes += bytes_written;
stats.blocks++;
}

void AP_Logger_Backend::df_stats_clear() {
memset(&stats, '\0', sizeof(stats));
stats.buf_space_min = -1;
}

void AP_Logger_Backend::df_stats_log() {
Write_AP_Logger_Stats_File(stats);
df_stats_clear();
}
Loading