|
|
|
@@ -583,49 +583,6 @@ void Logger::run()
|
|
|
|
|
|
|
|
|
|
uORB::Subscription parameter_update_sub(ORB_ID(parameter_update));
|
|
|
|
|
|
|
|
|
|
if (!initialize_topics()) {
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
//all topics added. Get required message buffer size
|
|
|
|
|
int max_msg_size = 0;
|
|
|
|
|
|
|
|
|
|
for (int sub = 0; sub < _num_subscriptions; ++sub) {
|
|
|
|
|
//use o_size, because that's what orb_copy will use
|
|
|
|
|
if (_subscriptions[sub].get_topic()->o_size > max_msg_size) {
|
|
|
|
|
max_msg_size = _subscriptions[sub].get_topic()->o_size;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (_event_subscription.get_topic()->o_size > max_msg_size) {
|
|
|
|
|
max_msg_size = _event_subscription.get_topic()->o_size;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
max_msg_size += sizeof(ulog_message_data_s);
|
|
|
|
|
|
|
|
|
|
if (sizeof(ulog_message_logging_s) > (size_t)max_msg_size) {
|
|
|
|
|
max_msg_size = sizeof(ulog_message_logging_s);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (_polling_topic_meta && _polling_topic_meta->o_size > max_msg_size) {
|
|
|
|
|
max_msg_size = _polling_topic_meta->o_size;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (max_msg_size > _msg_buffer_len) {
|
|
|
|
|
if (_msg_buffer) {
|
|
|
|
|
delete[](_msg_buffer);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
_msg_buffer_len = max_msg_size;
|
|
|
|
|
_msg_buffer = new uint8_t[_msg_buffer_len];
|
|
|
|
|
|
|
|
|
|
if (!_msg_buffer) {
|
|
|
|
|
PX4_ERR("failed to alloc message buffer");
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (!_writer.init()) {
|
|
|
|
|
PX4_ERR("writer init failed");
|
|
|
|
|
return;
|
|
|
|
@@ -640,7 +597,7 @@ void Logger::run()
|
|
|
|
|
const bool disable_boot_logging = get_disable_boot_logging();
|
|
|
|
|
|
|
|
|
|
if ((_log_mode == LogMode::boot_until_disarm || _log_mode == LogMode::boot_until_shutdown) && !disable_boot_logging) {
|
|
|
|
|
start_log_file(LogType::Full);
|
|
|
|
|
_start_immediately = true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/* init the update timer */
|
|
|
|
@@ -686,9 +643,56 @@ void Logger::run()
|
|
|
|
|
|
|
|
|
|
while (!should_exit()) {
|
|
|
|
|
// Start/stop logging (depending on logging mode, by default when arming/disarming)
|
|
|
|
|
const bool logging_started = start_stop_logging();
|
|
|
|
|
if (should_start_logging()) {
|
|
|
|
|
|
|
|
|
|
if (!initialize_topics()) {
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
//all topics added. Get required message buffer size
|
|
|
|
|
int max_msg_size = 0;
|
|
|
|
|
|
|
|
|
|
for (int sub = 0; sub < _num_subscriptions; ++sub) {
|
|
|
|
|
//use o_size, because that's what orb_copy will use
|
|
|
|
|
if (_subscriptions[sub].get_topic()->o_size > max_msg_size) {
|
|
|
|
|
max_msg_size = _subscriptions[sub].get_topic()->o_size;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (_event_subscription.get_topic()->o_size > max_msg_size) {
|
|
|
|
|
max_msg_size = _event_subscription.get_topic()->o_size;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
max_msg_size += sizeof(ulog_message_data_s);
|
|
|
|
|
|
|
|
|
|
if (sizeof(ulog_message_logging_s) > (size_t)max_msg_size) {
|
|
|
|
|
max_msg_size = sizeof(ulog_message_logging_s);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (_polling_topic_meta && _polling_topic_meta->o_size > max_msg_size) {
|
|
|
|
|
max_msg_size = _polling_topic_meta->o_size;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (max_msg_size > _msg_buffer_len) {
|
|
|
|
|
if (_msg_buffer) {
|
|
|
|
|
delete[](_msg_buffer);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
_msg_buffer_len = max_msg_size;
|
|
|
|
|
_msg_buffer = new uint8_t[_msg_buffer_len];
|
|
|
|
|
|
|
|
|
|
if (!_msg_buffer) {
|
|
|
|
|
PX4_ERR("failed to alloc message buffer");
|
|
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
start_log_file(LogType::Full);
|
|
|
|
|
|
|
|
|
|
if ((MissionLogType)_param_sdlog_mission.get() != MissionLogType::Disabled) {
|
|
|
|
|
start_log_file(LogType::Mission);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (logging_started) {
|
|
|
|
|
#ifdef DBGPRINT
|
|
|
|
|
timer_start = hrt_absolute_time();
|
|
|
|
|
total_bytes = 0;
|
|
|
|
@@ -706,7 +710,7 @@ void Logger::run()
|
|
|
|
|
|
|
|
|
|
const hrt_abstime loop_time = hrt_absolute_time();
|
|
|
|
|
|
|
|
|
|
if (_writer.is_started(LogType::Full)) { // mission log only runs when full log is also started
|
|
|
|
|
if (_msg_buffer && _writer.is_started(LogType::Full)) { // mission log only runs when full log is also started
|
|
|
|
|
|
|
|
|
|
if (!was_started) {
|
|
|
|
|
adjust_subscription_updates();
|
|
|
|
@@ -866,7 +870,7 @@ void Logger::run()
|
|
|
|
|
// - we avoid subscribing to many topics at once, when logging starts
|
|
|
|
|
// - we'll get the data immediately once we start logging (no need to wait for the next subscribe timeout)
|
|
|
|
|
if (next_subscribe_topic_index != -1) {
|
|
|
|
|
if (!_subscriptions[next_subscribe_topic_index].valid()) {
|
|
|
|
|
if (_subscriptions && !_subscriptions[next_subscribe_topic_index].valid()) {
|
|
|
|
|
_subscriptions[next_subscribe_topic_index].subscribe();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
@@ -1091,12 +1095,18 @@ bool Logger::get_disable_boot_logging()
|
|
|
|
|
return false;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
bool Logger::start_stop_logging()
|
|
|
|
|
bool Logger::should_start_logging()
|
|
|
|
|
{
|
|
|
|
|
bool updated = false;
|
|
|
|
|
bool desired_state = false;
|
|
|
|
|
|
|
|
|
|
if (_log_mode == LogMode::rc_aux1) {
|
|
|
|
|
if (_start_immediately) {
|
|
|
|
|
desired_state = true;
|
|
|
|
|
updated = true;
|
|
|
|
|
|
|
|
|
|
_start_immediately = false;
|
|
|
|
|
|
|
|
|
|
} else if (_log_mode == LogMode::rc_aux1) {
|
|
|
|
|
// aux1-based logging
|
|
|
|
|
manual_control_setpoint_s manual_control_setpoint;
|
|
|
|
|
|
|
|
|
@@ -1117,11 +1127,17 @@ bool Logger::start_stop_logging()
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
const bool delayed_start = (_param_sdlog_delay_s.get() > 0);
|
|
|
|
|
|
|
|
|
|
if (delayed_start && (_start_requested_time != HRT_ABSTIME_INVALID)) {
|
|
|
|
|
desired_state = true;
|
|
|
|
|
updated = true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
desired_state = desired_state || _manually_logging_override;
|
|
|
|
|
|
|
|
|
|
// only start/stop if this is a state transition
|
|
|
|
|
if (updated && _prev_state != desired_state) {
|
|
|
|
|
_prev_state = desired_state;
|
|
|
|
|
|
|
|
|
|
if (desired_state) {
|
|
|
|
|
if (_should_stop_file_log) { // happens on quick stop/start toggling
|
|
|
|
@@ -1129,14 +1145,24 @@ bool Logger::start_stop_logging()
|
|
|
|
|
stop_log_file(LogType::Full);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
start_log_file(LogType::Full);
|
|
|
|
|
if (delayed_start) {
|
|
|
|
|
if (_start_requested_time == HRT_ABSTIME_INVALID) {
|
|
|
|
|
_start_requested_time = hrt_absolute_time();
|
|
|
|
|
|
|
|
|
|
if ((MissionLogType)_param_sdlog_mission.get() != MissionLogType::Disabled) {
|
|
|
|
|
start_log_file(LogType::Mission);
|
|
|
|
|
PX4_INFO("Delayed start in %" PRIi32 " seconds", _param_sdlog_delay_s.get());
|
|
|
|
|
return false;
|
|
|
|
|
|
|
|
|
|
} else if (hrt_elapsed_time(&_start_requested_time) > _param_sdlog_delay_s.get() * 1_s) {
|
|
|
|
|
_start_requested_time = HRT_ABSTIME_INVALID; // reset
|
|
|
|
|
_prev_state = true;
|
|
|
|
|
return true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
_prev_state = true;
|
|
|
|
|
return true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
return true;
|
|
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
// delayed stop: we measure the process loads and then stop
|
|
|
|
|
initialize_load_output(PrintLoadReason::Postflight);
|
|
|
|
@@ -1145,6 +1171,8 @@ bool Logger::start_stop_logging()
|
|
|
|
|
if ((MissionLogType)_param_sdlog_mission.get() != MissionLogType::Disabled) {
|
|
|
|
|
stop_log_file(LogType::Mission);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
_prev_state = false;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|