mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 09:22:18 +00:00
logger use uORB::PublicationQueued for ulog_stream
- queue depth is now set by the msg
This commit is contained in:
@@ -239,8 +239,6 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
Logger::LogMode log_mode = Logger::LogMode::while_armed;
|
||||
bool error_flag = false;
|
||||
bool log_name_timestamp = false;
|
||||
unsigned int queue_size = 14; //TODO: we might be able to reduce this if mavlink polled on the topic and/or
|
||||
// topic sizes get reduced
|
||||
LogWriter::Backend backend = LogWriter::BackendAll;
|
||||
const char *poll_topic = nullptr;
|
||||
|
||||
@@ -248,7 +246,7 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
int ch;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "r:b:etfm:q:p:x", &myoptind, &myoptarg)) != EOF) {
|
||||
while ((ch = px4_getopt(argc, argv, "r:b:etfm:p:x", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'r': {
|
||||
unsigned long r = strtoul(myoptarg, nullptr, 10);
|
||||
@@ -310,15 +308,6 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
poll_topic = myoptarg;
|
||||
break;
|
||||
|
||||
case 'q':
|
||||
queue_size = strtoul(myoptarg, nullptr, 10);
|
||||
|
||||
if (queue_size == 0) {
|
||||
queue_size = 1;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case '?':
|
||||
error_flag = true;
|
||||
break;
|
||||
@@ -343,8 +332,7 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
Logger *logger = new Logger(backend, log_buffer_size, log_interval, poll_topic, log_mode, log_name_timestamp,
|
||||
queue_size);
|
||||
Logger *logger = new Logger(backend, log_buffer_size, log_interval, poll_topic, log_mode, log_name_timestamp);
|
||||
|
||||
#if defined(DBGPRINT) && defined(__PX4_NUTTX)
|
||||
struct mallinfo alloc_info = mallinfo();
|
||||
@@ -373,10 +361,10 @@ Logger *Logger::instantiate(int argc, char *argv[])
|
||||
|
||||
|
||||
Logger::Logger(LogWriter::Backend backend, size_t buffer_size, uint32_t log_interval, const char *poll_topic_name,
|
||||
LogMode log_mode, bool log_name_timestamp, unsigned int queue_size) :
|
||||
LogMode log_mode, bool log_name_timestamp) :
|
||||
_log_mode(log_mode),
|
||||
_log_name_timestamp(log_name_timestamp),
|
||||
_writer(backend, buffer_size, queue_size),
|
||||
_writer(backend, buffer_size),
|
||||
_log_interval(log_interval)
|
||||
{
|
||||
_log_utc_offset = param_find("SDLOG_UTC_OFFSET");
|
||||
@@ -2355,7 +2343,6 @@ $ logger on
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('t', "Use date/time for naming log directories and files", true);
|
||||
PRINT_MODULE_USAGE_PARAM_INT('r', 280, 0, 8000, "Log rate in Hz, 0 means unlimited rate", true);
|
||||
PRINT_MODULE_USAGE_PARAM_INT('b', 12, 4, 10000, "Log buffer size in KiB", true);
|
||||
PRINT_MODULE_USAGE_PARAM_INT('q', 14, 1, 100, "uORB queue size for mavlink mode", true);
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('p', nullptr, "<topic_name>",
|
||||
"Poll on a topic instead of running with fixed rate (Log rate and topic intervals are ignored if this is set)", true);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("on", "start logging now, override arming (logger must be running)");
|
||||
|
||||
Reference in New Issue
Block a user