system: add generic shutdown API

This commit is contained in:
Beat Küng 2017-04-18 14:02:30 +02:00 committed by Lorenz Meier
parent 211837c73b
commit 694bf48422
6 changed files with 263 additions and 3 deletions

View File

@ -103,7 +103,7 @@ static char *param_user_file = NULL;
#include <px4_workqueue.h>
/* autosaving variables */
static hrt_abstime last_autosave_timestamp = 0;
struct work_s autosave_work;
static struct work_s autosave_work;
static bool autosave_scheduled = false;
static bool autosave_disabled = false;
#endif /* PARAM_NO_AUTOSAVE */

View File

@ -89,7 +89,7 @@ static char *param_user_file = NULL;
#include <px4_workqueue.h>
/* autosaving variables */
static hrt_abstime last_autosave_timestamp = 0;
struct work_s autosave_work;
static struct work_s autosave_work;
static bool autosave_scheduled = false;
static bool autosave_disabled = false;

View File

@ -42,6 +42,7 @@ px4_add_module(
MODULE platforms__common
SRCS
px4_getopt.c
shutdown.cpp
DEPENDS
${depends}
)

View File

@ -0,0 +1,172 @@
/****************************************************************************
*
* Copyright (C) 2017 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.
*
****************************************************************************/
/**
* @file shutdown.cpp
* Implementation of the API declared in px4_shutdown.h.
*/
#include <board_config.h>
#include <px4_log.h>
#include <px4_workqueue.h>
#include <px4_shutdown.h>
#include <px4_tasks.h>
#include <stdint.h>
#include <errno.h>
#include <pthread.h>
static struct work_s shutdown_work = {};
static uint8_t shutdown_counter = 0;
#define SHUTDOWN_ARG_IN_PROGRESS (1<<0)
#define SHUTDOWN_ARG_REBOOT (1<<1)
#define SHUTDOWN_ARG_TO_BOOTLOADER (1<<2)
static uint8_t shutdown_args = 0;
pthread_mutex_t shutdown_hooks_mutex = PTHREAD_MUTEX_INITIALIZER; // protects access to shutdown_hooks
static const int max_shutdown_hooks = 1;
static shutdown_hook_t shutdown_hooks[max_shutdown_hooks] = {};
static const int shutdown_timeout_ms = 300; // force shutdown after this time if modules do not respond in time
/**
* work queue callback method to shutdown.
* @param arg unused
*/
static void shutdown_worker(void *arg);
int px4_register_shutdown_hook(shutdown_hook_t hook)
{
pthread_mutex_lock(&shutdown_hooks_mutex);
for (int i = 0; i < max_shutdown_hooks; ++i) {
if (!shutdown_hooks[i]) {
shutdown_hooks[i] = hook;
pthread_mutex_unlock(&shutdown_hooks_mutex);
return 0;
}
}
pthread_mutex_unlock(&shutdown_hooks_mutex);
return -ENOMEM;
}
int px4_unregister_shutdown_hook(shutdown_hook_t hook)
{
pthread_mutex_lock(&shutdown_hooks_mutex);
for (int i = 0; i < max_shutdown_hooks; ++i) {
if (shutdown_hooks[i] == hook) {
shutdown_hooks[i] = nullptr;
pthread_mutex_unlock(&shutdown_hooks_mutex);
return 0;
}
}
pthread_mutex_unlock(&shutdown_hooks_mutex);
return -EINVAL;
}
void shutdown_worker(void *arg)
{
PX4_DEBUG("shutdown worker (%i)", shutdown_counter);
bool done = true;
pthread_mutex_lock(&shutdown_hooks_mutex);
for (int i = 0; i < max_shutdown_hooks; ++i) {
if (shutdown_hooks[i]) {
if (!shutdown_hooks[i]()) {
done = false;
}
}
}
pthread_mutex_unlock(&shutdown_hooks_mutex);
if (done || ++shutdown_counter > shutdown_timeout_ms / 10) {
if (shutdown_args & SHUTDOWN_ARG_REBOOT) {
PX4_WARN("Reboot NOW.");
px4_systemreset(shutdown_args & SHUTDOWN_ARG_TO_BOOTLOADER);
} else {
PX4_WARN("Shutdown NOW. Good Bye.");
board_shutdown();
}
} else {
work_queue(HPWORK, &shutdown_work, (worker_t)&shutdown_worker, NULL, USEC2TICK(10000));
}
}
int px4_shutdown_request(bool reboot, bool to_bootloader)
{
// fail immediately if the board does not support the requested method
#if defined BOARD_HAS_NO_RESET
if (reboot) {
return -EINVAL;
}
#endif
#if !defined(BOARD_HAS_POWER_CONTROL)
if (!reboot) {
return -EINVAL;
}
#endif
if (shutdown_args & SHUTDOWN_ARG_IN_PROGRESS) {
return 0;
}
shutdown_args |= SHUTDOWN_ARG_IN_PROGRESS;
if (reboot) {
shutdown_args |= SHUTDOWN_ARG_REBOOT;
}
if (to_bootloader) {
shutdown_args |= SHUTDOWN_ARG_TO_BOOTLOADER;
}
return work_queue(HPWORK, &shutdown_work, (worker_t)&shutdown_worker, NULL, USEC2TICK(0));
}

View File

@ -0,0 +1,86 @@
/****************************************************************************
*
* Copyright (C) 2017 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.
*
****************************************************************************/
/**
* @file px4_shutdown.h
* Power-related API
*/
#pragma once
#include <stdbool.h>
__BEGIN_DECLS
/**
* Shutdown hook callback method (@see px4_register_shutdown_hook()).
* @return true if it's ok to shutdown, false if more time needed for cleanup
*/
typedef bool (*shutdown_hook_t)(void);
/**
* Register a method that should be called when powering off (and also on reboot).
* @param hook callback method. It must not block, but return immediately.
* When the system is requested to shutdown, the registered hooks will be
* called regularily until either all of them return true, or a timeout
* is reached.
* @return 0 on success, <0 on error
*/
__EXPORT int px4_register_shutdown_hook(shutdown_hook_t hook);
/**
* Unregister a shutdown hook
* @param hook callback method to be removed
* @return 0 on success, <0 on error
*/
__EXPORT int px4_unregister_shutdown_hook(shutdown_hook_t hook);
/**
* Request the system to shut down. It's save to call this from an IRQ context,
* but the work queues need to be initialized already.
* Note the following:
* - The system might not support to shutdown (or reboot). In that case -EINVAL will
* be returned.
* - The system might not shutdown immediately, so expect this method to return even
* on success.
* @param reboot perform a reboot instead of a shutdown
* @param to_bootloader reboot into bootloader mode (only used if reboot is true)
* @return 0 on success, <0 on error
*/
__EXPORT int px4_shutdown_request(bool reboot, bool to_bootloader);
__END_DECLS

View File

@ -103,7 +103,8 @@ typedef int (*px4_main_t)(int argc, char *argv[]);
__BEGIN_DECLS
/** Reboots the board */
/** Reboots the board (without waiting for clean shutdown). Modules should use px4_shutdown_request() in most cases.
*/
__EXPORT void px4_systemreset(bool to_bootloader) noreturn_function;
/** Starts a task and performs any specific accounting, scheduler setup, etc. */