Skip to content

Commit

Permalink
logger use uORB::PublicationQueued for ulog_stream
Browse files Browse the repository at this point in the history
 - queue depth is now set by the msg
  • Loading branch information
dagar committed Aug 6, 2019
1 parent 443d77b commit 8a0ebf0
Show file tree
Hide file tree
Showing 7 changed files with 21 additions and 48 deletions.
2 changes: 2 additions & 0 deletions msg/ulog_stream.msg
Original file line number Diff line number Diff line change
Expand Up @@ -15,3 +15,5 @@ uint8 first_message_offset # offset into data where first message starts. This
uint16 sequence # allows determine drops
uint8 flags # see FLAGS_*
uint8[249] data # ulog data

uint8 ORB_QUEUE_LENGTH = 14 # TODO: we might be able to reduce this if mavlink polled on the topic
4 changes: 2 additions & 2 deletions src/modules/logger/log_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ namespace px4
namespace logger
{

LogWriter::LogWriter(Backend configured_backend, size_t file_buffer_size, unsigned int queue_size)
LogWriter::LogWriter(Backend configured_backend, size_t file_buffer_size)
: _backend(configured_backend)
{
if (configured_backend & BackendFile) {
Expand All @@ -50,7 +50,7 @@ LogWriter::LogWriter(Backend configured_backend, size_t file_buffer_size, unsign
}

if (configured_backend & BackendMavlink) {
_log_writer_mavlink_for_write = _log_writer_mavlink = new LogWriterMavlink(queue_size);
_log_writer_mavlink_for_write = _log_writer_mavlink = new LogWriterMavlink();

if (!_log_writer_mavlink) {
PX4_ERR("LogWriterMavlink allocation failed");
Expand Down
2 changes: 1 addition & 1 deletion src/modules/logger/log_writer.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class LogWriter
static constexpr Backend BackendMavlink = 1 << 1;
static constexpr Backend BackendAll = BackendFile | BackendMavlink;

LogWriter(Backend configured_backend, size_t file_buffer_size, unsigned int queue_size);
LogWriter(Backend configured_backend, size_t file_buffer_size);
~LogWriter();

bool init();
Expand Down
24 changes: 4 additions & 20 deletions src/modules/logger/log_writer_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,7 @@ namespace px4
namespace logger
{


LogWriterMavlink::LogWriterMavlink(unsigned int queue_size) :
_queue_size(queue_size)
LogWriterMavlink::LogWriterMavlink()
{
_ulog_stream_data.length = 0;
}
Expand All @@ -62,31 +60,22 @@ LogWriterMavlink::~LogWriterMavlink()
if (_ulog_stream_ack_sub >= 0) {
orb_unsubscribe(_ulog_stream_ack_sub);
}

if (_ulog_stream_pub) {
orb_unadvertise(_ulog_stream_pub);
}
}

void LogWriterMavlink::start_log()
{
if (_ulog_stream_pub == nullptr) {
memset(&_ulog_stream_data, 0, sizeof(_ulog_stream_data));
// advertise before we subscribe: this is a trick to reduce the number of needed file descriptors
// (the advertise temporarily opens a file descriptor)
_ulog_stream_pub = orb_advertise_queue(ORB_ID(ulog_stream), &_ulog_stream_data, _queue_size);
}

if (_ulog_stream_ack_sub == -1) {
_ulog_stream_ack_sub = orb_subscribe(ORB_ID(ulog_stream_ack));
}

// make sure we don't get any stale ack's by doing an orb_copy
ulog_stream_ack_s ack;
orb_copy(ORB_ID(ulog_stream_ack), _ulog_stream_ack_sub, &ack);

_ulog_stream_data.sequence = 0;
_ulog_stream_data.length = 0;
_ulog_stream_data.first_message_offset = 0;

_is_started = true;
}

Expand Down Expand Up @@ -147,12 +136,7 @@ int LogWriterMavlink::publish_message()
_ulog_stream_data.flags = _ulog_stream_data.FLAGS_NEED_ACK;
}

if (_ulog_stream_pub == nullptr) {
_ulog_stream_pub = orb_advertise_queue(ORB_ID(ulog_stream), &_ulog_stream_data, _queue_size);

} else {
orb_publish(ORB_ID(ulog_stream), _ulog_stream_pub, &_ulog_stream_data);
}
_ulog_stream_pub.publish(_ulog_stream_data);

if (_need_reliable_transfer) {
// we need to wait for an ack. Note that this blocks the main logger thread, so if a file logging
Expand Down
14 changes: 7 additions & 7 deletions src/modules/logger/log_writer_mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#pragma once

#include <stdint.h>
#include <uORB/PublicationQueued.hpp>
#include <uORB/topics/ulog_stream.h>
#include <uORB/topics/ulog_stream_ack.h>

Expand All @@ -49,7 +50,7 @@ namespace logger
class LogWriterMavlink
{
public:
LogWriterMavlink(unsigned int queue_size);
LogWriterMavlink();
~LogWriterMavlink();

bool init();
Expand All @@ -75,12 +76,11 @@ class LogWriterMavlink
/** publish message, wait for ack if needed & reset message */
int publish_message();

ulog_stream_s _ulog_stream_data;
orb_advert_t _ulog_stream_pub = nullptr;
int _ulog_stream_ack_sub = -1;
bool _need_reliable_transfer = false;
bool _is_started = false;
const unsigned int _queue_size;
ulog_stream_s _ulog_stream_data{};
uORB::PublicationQueued<ulog_stream_s> _ulog_stream_pub{ORB_ID(ulog_stream)};
int _ulog_stream_ack_sub{-1};
bool _need_reliable_transfer{false};
bool _is_started{false};
};

}
Expand Down
21 changes: 4 additions & 17 deletions src/modules/logger/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,16 +239,14 @@ 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;

int myoptind = 1;
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);
Expand Down Expand Up @@ -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;
Expand All @@ -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();
Expand Down Expand Up @@ -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");
Expand Down Expand Up @@ -2355,7 +2343,6 @@ Or if already running:
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)");
Expand Down
2 changes: 1 addition & 1 deletion src/modules/logger/logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ class Logger : public ModuleBase<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);

~Logger();

Expand Down

0 comments on commit 8a0ebf0

Please sign in to comment.