logger: remove watchdog priority boost

This commit is contained in:
Daniel Agar
2021-11-25 12:56:19 -05:00
parent 8defbc8829
commit 223f0ef8b4
5 changed files with 0 additions and 285 deletions
-1
View File
@@ -45,7 +45,6 @@ px4_add_module(
log_writer_file.cpp
log_writer_mavlink.cpp
util.cpp
watchdog.cpp
DEPENDS
version
)
-36
View File
@@ -36,7 +36,6 @@
#include "logged_topics.h"
#include "logger.h"
#include "messages.h"
#include "watchdog.h"
#include <dirent.h>
#include <sys/stat.h>
@@ -85,22 +84,14 @@ using namespace time_literals;
struct timer_callback_data_s {
px4_sem_t semaphore;
watchdog_data_t watchdog_data;
volatile bool watchdog_triggered = false;
};
/* This is used to schedule work for the logger (periodic scan for updated topics) */
static void timer_callback(void *arg)
{
/* Note: we are in IRQ context here (on NuttX) */
timer_callback_data_s *data = (timer_callback_data_s *)arg;
if (watchdog_update(data->watchdog_data)) {
data->watchdog_triggered = true;
}
/* check the value of the semaphore: if the logger cannot keep up with running it's main loop as fast
* as the timer_callback here increases the semaphore count, the counter would increase unbounded,
* leading to an overflow at some point. This case we want to avoid here, so we check the current
@@ -114,10 +105,8 @@ static void timer_callback(void *arg)
}
px4_sem_post(&data->semaphore);
}
int logger_main(int argc, char *argv[])
{
// logger currently assumes little endian
@@ -643,17 +632,6 @@ void Logger::run()
}
} else {
if (_writer.backend() & LogWriter::BackendFile) {
const pid_t pid_self = getpid();
const pthread_t writer_thread = _writer.thread_id_file();
// sched_note_start is already called from pthread_create and task_create,
// which means we can expect to find the tasks in system_load.tasks, as required in watchdog_initialize
watchdog_initialize(pid_self, writer_thread, timer_callback_data.watchdog_data);
}
hrt_call_every(&timer_call, _log_interval, _log_interval, timer_callback, &timer_callback_data);
}
@@ -681,12 +659,6 @@ void Logger::run()
/* check for logging command from MAVLink (start/stop streaming) */
handle_vehicle_command_update();
if (timer_callback_data.watchdog_triggered) {
timer_callback_data.watchdog_triggered = false;
initialize_load_output(PrintLoadReason::Watchdog);
}
const hrt_abstime loop_time = hrt_absolute_time();
if (_writer.is_started(LogType::Full)) { // mission log only runs when full log is also started
@@ -1536,10 +1508,6 @@ void Logger::print_load_callback(void *user)
perf_name = "perf_top_postflight";
break;
case PrintLoadReason::Watchdog:
perf_name = "perf_top_watchdog";
break;
default:
perf_name = "perf_top";
break;
@@ -1559,10 +1527,6 @@ void Logger::initialize_load_output(PrintLoadReason reason)
void Logger::write_load_output()
{
if (_print_load_reason == PrintLoadReason::Watchdog) {
PX4_ERR("Writing watchdog data"); // this is just that we see it easily in the log
}
perf_callback_data_t callback_data = {};
char buffer[140];
callback_data.logger = this;
-1
View File
@@ -134,7 +134,6 @@ private:
enum class PrintLoadReason {
Preflight,
Postflight,
Watchdog
};
static constexpr int MAX_MISSION_TOPICS_NUM = 5; /**< Maximum number of mission topics */
-169
View File
@@ -1,169 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "watchdog.h"
#include <px4_platform_common/log.h>
#if defined(__PX4_NUTTX) && !defined(CONFIG_SCHED_INSTRUMENTATION)
# error watchdog support requires CONFIG_SCHED_INSTRUMENTATION
#endif
using namespace time_literals;
namespace px4
{
namespace logger
{
bool watchdog_update(watchdog_data_t &watchdog_data)
{
#ifdef __PX4_NUTTX
if (system_load.initialized && watchdog_data.logger_main_task_index >= 0
&& watchdog_data.logger_writer_task_index >= 0) {
const hrt_abstime now = hrt_absolute_time();
const system_load_taskinfo_s &log_writer_task = system_load.tasks[watchdog_data.logger_writer_task_index];
if (log_writer_task.valid) {
// Trigger the watchdog if the log writer task has been ready to run for a
// minimum duration and it has not been scheduled during that time.
// When the writer is waiting for an SD transfer, it is not in ready state, thus a long dropout
// will not trigger it. The longest period in ready state I measured was around 70ms,
// after a param change.
// We only check the log writer because it runs at lower priority than the main thread.
// No need to lock the tcb access, since we are in IRQ context
// update the timestamp if it has been scheduled recently
if (log_writer_task.curr_start_time > watchdog_data.ready_to_run_timestamp) {
watchdog_data.ready_to_run_timestamp = log_writer_task.curr_start_time;
}
// update the timestamp if not ready to run or if transitioned into ready to run
uint8_t current_state = log_writer_task.tcb->task_state;
if (current_state != TSTATE_TASK_READYTORUN
|| (watchdog_data.last_state != TSTATE_TASK_READYTORUN && current_state == TSTATE_TASK_READYTORUN)) {
watchdog_data.ready_to_run_timestamp = now;
}
watchdog_data.last_state = current_state;
#if 0 // for debugging
// test code that prints the maximum time in ready state.
// Note: we are in IRQ context, and thus are strictly speaking not allowed to use PX4_ERR -
// we do it anyway since it's only used for debugging.
static uint64_t max_time = 0;
if (now - watchdog_data.ready_to_run_timestamp > max_time) {
max_time = now - watchdog_data.ready_to_run_timestamp;
}
static int counter = 0;
if (++counter > 300) {
PX4_ERR("max time in ready: %i ms", (int)max_time / 1000);
counter = 0;
max_time = 0;
}
#endif
if (now - watchdog_data.ready_to_run_timestamp > 1_s) {
// boost the priority to make sure the logger continues to write to the log.
// Note that we never restore the priority, to keep the logic simple and because it is
// an event that must not occur under normal circumstances (if it does, there's a bug
// somewhere)
sched_param param{};
param.sched_priority = SCHED_PRIORITY_MAX;
if (system_load.tasks[watchdog_data.logger_main_task_index].valid) {
sched_setparam(system_load.tasks[watchdog_data.logger_main_task_index].tcb->pid, &param);
}
sched_setparam(log_writer_task.tcb->pid, &param);
// make sure we won't trigger again
watchdog_data.logger_main_task_index = -1;
return true;
}
} else {
// should never happen
watchdog_data.logger_main_task_index = -1;
}
}
#endif /* __PX4_NUTTX */
return false;
}
void watchdog_initialize(const pid_t pid_logger_main, const pthread_t writer_thread, watchdog_data_t &watchdog_data)
{
#ifdef __PX4_NUTTX
// The pthread_t ID is equal to the PID on NuttX
const pthread_t pid_logger_writer = writer_thread;
sched_lock(); // need to lock the tcb access
for (int i = 0; i < CONFIG_FS_PROCFS_MAX_TASKS; i++) {
if (system_load.tasks[i].valid) {
if (system_load.tasks[i].tcb->pid == pid_logger_writer) {
watchdog_data.logger_writer_task_index = i;
}
if (system_load.tasks[i].tcb->pid == pid_logger_main) {
watchdog_data.logger_main_task_index = i;
}
}
}
sched_unlock();
if (watchdog_data.logger_writer_task_index == -1 ||
watchdog_data.logger_main_task_index == -1) {
// If we land here it means the NuttX implementation changed
// and one of our assumptions is not valid anymore
PX4_ERR("watchdog init failed");
}
#endif /* __PX4_NUTTX */
}
} // namespace logger
} // namespace px4
-78
View File
@@ -1,78 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <drivers/drv_hrt.h>
#ifdef __PX4_NUTTX
#include <nuttx/sched.h>
#include <px4_platform/cpuload.h>
#endif /* __PX4_NUTTX */
namespace px4
{
namespace logger
{
struct watchdog_data_t {
#ifdef __PX4_NUTTX
int logger_main_task_index = -1;
int logger_writer_task_index = -1;
hrt_abstime ready_to_run_timestamp = hrt_absolute_time();
uint8_t last_state = TSTATE_TASK_INVALID;
#endif /* __PX4_NUTTX */
};
/**
* Initialize the watchdog, fill in watchdog_data.
*/
void watchdog_initialize(const pid_t pid_logger_main, const pthread_t writer_thread, watchdog_data_t &watchdog_data);
/**
* Update the watchdog and trigger it if necessary. It is triggered when the log writer task is in
* ready state for a certain period of time, but did not get scheduled. It means that most likely
* some other higher-prio task runs busy.
* When the watchdog triggers, it boosts the priority of the logger's main & writer tasks to maximum, so
* that they get scheduled again.
*
* Expected to be called from IRQ context.
*
* @param watchdog_data
* @return true if watchdog is triggered, false otherwise
*/
bool watchdog_update(watchdog_data_t &watchdog_data);
} //namespace logger
} //namespace px4