commander: reboot/shutdown usability fixes

- always check with state machine before reboot/shutdown
 - respect BOARD_HAS_POWER_CONTROL (shutdown from command, low battery, power button)
 - px4_shutdown_request add optional delay and always execute from HPWORK
 - px4_shutdown_request split out px4_reboot_request
This commit is contained in:
Daniel Agar
2020-05-04 12:33:31 -04:00
parent 45ebbb895a
commit 746a8f5cf9
96 changed files with 332 additions and 528 deletions

View File

@@ -42,7 +42,7 @@ void list_builtins(apps_map_type &apps)
int shutdown_main(int argc, char *argv[])
{
printf("Shutting down\n");
printf("Exiting NOW.\n");
system_exit(0);
}

View File

@@ -297,17 +297,7 @@
* Public Data
************************************************************************************/
/* board reset control */
typedef enum board_reset_e {
board_reset_normal = 0, /* Perform a normal reset */
board_reset_extended = 1, /* Perform an extend reset as defined by board */
board_reset_power_off = 2, /* Reset to the boot loader, signaling a power off */
board_reset_enter_bootloader = 3 /* Perform a reset to the boot loader */
} board_reset_e;
/* board power button state notification */
typedef enum board_power_button_state_notification_e {
PWR_BUTTON_IDEL, /* Button went up without meeting shutdown button down time */
PWR_BUTTON_DOWN, /* Button went Down */
@@ -321,7 +311,6 @@ typedef enum board_power_button_state_notification_e {
} board_power_button_state_notification_e;
/* board call back signature */
typedef int (*power_button_state_notification_t)(board_power_button_state_notification_e request);
/* PX4_SOC_ARCH_ID is monotonic ordinal number assigned by PX4 to a chip
@@ -416,10 +405,6 @@ typedef uint8_t mfguid_t[PX4_CPU_MFGUID_BYTE_LENGTH];
*/
typedef uint8_t px4_guid_t[PX4_GUID_BYTE_LENGTH];
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
@@ -526,7 +511,7 @@ int board_read_VBUS_state(void);
* Name: board_on_reset
*
* Description:
* Optionally provided function called on entry to board_system_reset
* Optionally provided function called on entry to board_reset
* It should perform any house keeping prior to the rest.
* For example setting PWM outputs to the off state to avoid
* triggering a motor spin.
@@ -547,58 +532,55 @@ int board_read_VBUS_state(void);
*
************************************************************************************/
#if defined(BOARD_HAS_NO_RESET) || !defined(BOARD_HAS_ON_RESET)
# define board_on_reset(status)
#else
#if defined(BOARD_HAS_ON_RESET)
__EXPORT void board_on_reset(int status);
#endif // BOARD_HAS_ON_RESET
/****************************************************************************
* Name: board_power_off
*
* Description:
* Power off the board. This function may or may not be supported by a
* particular board architecture.
*
* Input Parameters:
* status - Status information provided with the reset event. This
* meaning of this status information is board-specific. If not used by
* a board, the value zero may be provided in calls to board_power_off.
*
* Returned Value:
* If this function returns, then it was not possible to power-off the
* board due to some constraints. The return value int this case is a
* board-specific reason for the failure to shutdown.
*
****************************************************************************/
#ifdef CONFIG_BOARDCTL_POWEROFF
int board_power_off(int status);
#endif
/************************************************************************************
/****************************************************************************
* Name: board_reset
*
* Description:
* All boards my optionally provide this API to reset the board
* Reset board. Support for this function is required by board-level
* logic if CONFIG_BOARDCTL_RESET is selected.
*
* Input Parameters:
* status - 1 Resetting to boot loader
* 0 Just resetting CPU
* status - Status information provided with the reset event. This
* meaning of this status information is board-specific. If not
* used by a board, the value zero may be provided in calls to
* board_reset().
*
* Returned Value:
* If function is supported by board it will not return.
* If not supported it is a noop.
* If this function returns, then it was not possible to power-off the
* board due to some constraints. The return value int this case is a
* board-specific reason for the failure to shutdown.
*
************************************************************************************/
#if defined(BOARD_HAS_NO_RESET)
# define board_system_reset(status)
#else
__EXPORT void board_system_reset(int status) noreturn_function;
#endif
****************************************************************************/
/************************************************************************************
* Name: board_set_bootload_mode
*
* Description:
* All boards my optionally provide this API to enter configure the entry to
* boot loader mode on the next system reset.
*
* Input Parameters:
* mode - is an board_reset_e that controls the type of reset.
* board_reset_normal Perform a normal reset
* board_reset_extended Perform an extend reset as defined by board
* board_reset_power_off Reset to the boot loader, signaling a power off
* board_reset_enter_bootloader Perform a reset to the boot loader
*
*
* Returned Value:
* Zero (OK) is returned on success; a negated EINVAL value is returned if an
* invalid mode is requested.
*
************************************************************************************/
#if defined(BOARD_HAS_NO_BOOTLOADER)
# define board_set_bootload_mode(mode)
#else
__EXPORT int board_set_bootload_mode(board_reset_e mode);
#ifdef CONFIG_BOARDCTL_RESET
int board_reset(int status);
#endif
/************************************************************************************
@@ -980,23 +962,6 @@ __EXPORT int board_mcu_version(char *rev, const char **revstr, const char **erra
int board_register_power_state_notification_cb(power_button_state_notification_t cb);
/************************************************************************************
* Name: board_shutdown
*
* Description:
* boards may provide a function to power off the board.
*
* Input Parameters:
* None.
* Returned Value:
* - If supported the function will not return.
* OK, or -EINVAL if unsupported.
*/
int board_shutdown(void);
#else
static inline int board_register_power_state_notification_cb(power_button_state_notification_t cb) { return 0; }
static inline int board_shutdown(void) { return -EINVAL; }
#endif
/************************************************************************************

View File

@@ -38,7 +38,10 @@
#pragma once
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include <inttypes.h>
__BEGIN_DECLS
@@ -69,17 +72,34 @@ __EXPORT int px4_unregister_shutdown_hook(shutdown_hook_t hook);
/**
* Request the system to shut down or reboot.
* Request the system to reboot.
* Note the following:
* - The system might not support to shutdown (or reboot). In that case -EINVAL will
* - The system might not support 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)
* @param delay_us optional delay in microseconds
* @return 0 on success, <0 on error
*/
__EXPORT int px4_shutdown_request(bool reboot, bool to_bootloader);
#if defined(CONFIG_BOARDCTL_RESET)
__EXPORT int px4_reboot_request(bool to_bootloader = false, uint32_t delay_us = 0);
#endif // CONFIG_BOARDCTL_RESET
/**
* Request the system to shut down or reboot.
* Note the following:
* - The system might not support shutdown. In that case -EINVAL will
* be returned.
* - The system might not shutdown immediately, so expect this method to return even
* on success.
* @param delay_us optional delay in microseconds
* @return 0 on success, <0 on error
*/
#if defined(CONFIG_BOARDCTL_POWEROFF) || defined(__PX4_POSIX)
__EXPORT int px4_shutdown_request(uint32_t delay_us = 0);
#endif // CONFIG_BOARDCTL_POWEROFF
/**
@@ -89,10 +109,12 @@ __EXPORT int px4_shutdown_request(bool reboot, bool to_bootloader);
*/
__EXPORT int px4_shutdown_lock(void);
/**
* Release the shutdown lock.
* @return 0 on success, <0 on error
*/
__EXPORT int px4_shutdown_unlock(void);
__END_DECLS

View File

@@ -149,10 +149,6 @@ typedef int (*px4_main_t)(int argc, char *argv[]);
__BEGIN_DECLS
/** 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. */
__EXPORT px4_task_t px4_task_spawn_cmd(const char *name,
int scheduler,

View File

@@ -36,12 +36,13 @@
* Implementation of the API declared in px4_shutdown.h.
*/
#include <board_config.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/workqueue.h>
#include <px4_platform_common/shutdown.h>
#include <px4_platform_common/tasks.h>
#include <drivers/drv_hrt.h>
#ifndef MODULE_NAME
#define MODULE_NAME "shutdown"
#endif
@@ -52,6 +53,12 @@
#include <errno.h>
#include <pthread.h>
#ifdef __PX4_NUTTX
#include <nuttx/board.h>
#endif
using namespace time_literals;
static pthread_mutex_t shutdown_mutex =
PTHREAD_MUTEX_INITIALIZER; // protects access to shutdown_hooks & shutdown_lock_counter
static uint8_t shutdown_lock_counter = 0;
@@ -86,39 +93,7 @@ int px4_shutdown_unlock()
return ret;
}
#if (defined(__PX4_NUTTX) && !defined(CONFIG_SCHED_WORKQUEUE)) || __PX4_QURT
// minimal NuttX/QuRT build without work queue support
int px4_register_shutdown_hook(shutdown_hook_t hook)
{
return -EINVAL;
}
int px4_unregister_shutdown_hook(shutdown_hook_t hook)
{
return -EINVAL;
}
int px4_shutdown_request(bool reboot, bool to_bootloader)
{
int ret = 0;
pthread_mutex_lock(&shutdown_mutex);
// FIXME: if shutdown_lock_counter > 0, we should wait, but unfortunately we don't have work queues
if (reboot) {
px4_systemreset(to_bootloader);
} else {
ret = board_shutdown();
}
pthread_mutex_unlock(&shutdown_mutex);
return ret;
}
#else
#if defined(CONFIG_SCHED_WORKQUEUE)
static struct work_s shutdown_work = {};
static uint16_t shutdown_counter = 0; ///< count how many times the shutdown worker was executed
@@ -128,20 +103,12 @@ static uint16_t shutdown_counter = 0; ///< count how many times the shutdown wor
#define SHUTDOWN_ARG_TO_BOOTLOADER (1<<2)
static uint8_t shutdown_args = 0;
static const int max_shutdown_hooks = 1;
static constexpr int max_shutdown_hooks = 1;
static shutdown_hook_t shutdown_hooks[max_shutdown_hooks] = {};
static const int shutdown_timeout_ms = 5000; ///< 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);
static hrt_abstime shutdown_time_us = 0;
static constexpr hrt_abstime shutdown_timeout_us =
5_s; ///< force shutdown after this time if modules do not respond in time
int px4_register_shutdown_hook(shutdown_hook_t hook)
{
@@ -175,9 +142,11 @@ int px4_unregister_shutdown_hook(shutdown_hook_t hook)
return -EINVAL;
}
void shutdown_worker(void *arg)
/**
* work queue callback method to shutdown.
* @param arg unused
*/
static void shutdown_worker(void *arg)
{
PX4_DEBUG("shutdown worker (%i)", shutdown_counter);
bool done = true;
@@ -192,14 +161,29 @@ void shutdown_worker(void *arg)
}
}
if ((done && shutdown_lock_counter == 0) || ++shutdown_counter > shutdown_timeout_ms / 10) {
const hrt_abstime now = hrt_absolute_time();
const bool delay_elapsed = (now > shutdown_time_us);
if (delay_elapsed && ((done && shutdown_lock_counter == 0) || (now > (shutdown_time_us + shutdown_timeout_us)))) {
if (shutdown_args & SHUTDOWN_ARG_REBOOT) {
PX4_WARN("Reboot NOW.");
px4_systemreset(shutdown_args & SHUTDOWN_ARG_TO_BOOTLOADER);
#if defined(CONFIG_BOARDCTL_RESET)
PX4_INFO_RAW("Reboot NOW.");
board_reset(shutdown_args & SHUTDOWN_ARG_TO_BOOTLOADER);
#else
PX4_PANIC("board reset not available");
#endif
} else {
PX4_WARN("Shutdown NOW. Good Bye.");
board_shutdown();
#if defined(CONFIG_BOARDCTL_POWEROFF)
PX4_INFO_RAW("Powering off NOW.");
board_power_off(0);
#elif !defined(CONFIG_BOARDCTL_POWEROFF) && defined(__PX4_POSIX)
// simply exit on posix if real shutdown (poweroff) not available
PX4_INFO_RAW("Exiting NOW.");
system_exit(0);
#else
PX4_PANIC("board shutdown not available");
#endif
}
pthread_mutex_unlock(&shutdown_mutex); // must NEVER come here
@@ -210,40 +194,56 @@ void shutdown_worker(void *arg)
}
}
int px4_shutdown_request(bool reboot, bool to_bootloader)
#if defined(CONFIG_BOARDCTL_RESET)
int px4_reboot_request(bool to_bootloader, uint32_t delay_us)
{
// 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
pthread_mutex_lock(&shutdown_mutex);
if (shutdown_args & SHUTDOWN_ARG_IN_PROGRESS) {
pthread_mutex_unlock(&shutdown_mutex);
return 0;
}
shutdown_args |= SHUTDOWN_ARG_IN_PROGRESS;
if (reboot) {
shutdown_args |= SHUTDOWN_ARG_REBOOT;
}
shutdown_args |= SHUTDOWN_ARG_REBOOT;
if (to_bootloader) {
shutdown_args |= SHUTDOWN_ARG_TO_BOOTLOADER;
}
shutdown_worker(nullptr);
shutdown_time_us = hrt_absolute_time();
if (delay_us > 0) {
shutdown_time_us += delay_us;
}
work_queue(HPWORK, &shutdown_work, (worker_t)&shutdown_worker, nullptr, 1);
pthread_mutex_unlock(&shutdown_mutex);
return 0;
}
#endif // CONFIG_BOARDCTL_RESET
#if defined(CONFIG_BOARDCTL_POWEROFF) || defined(__PX4_POSIX)
int px4_shutdown_request(uint32_t delay_us)
{
pthread_mutex_lock(&shutdown_mutex);
#endif /* (defined(__PX4_NUTTX) && !defined(CONFIG_SCHED_WORKQUEUE)) || __PX4_QURT */
if (shutdown_args & SHUTDOWN_ARG_IN_PROGRESS) {
pthread_mutex_unlock(&shutdown_mutex);
return 0;
}
shutdown_args |= SHUTDOWN_ARG_IN_PROGRESS;
shutdown_time_us = hrt_absolute_time();
if (delay_us > 0) {
shutdown_time_us += delay_us;
}
work_queue(HPWORK, &shutdown_work, (worker_t)&shutdown_worker, nullptr, 1);
pthread_mutex_unlock(&shutdown_mutex);
return 0;
}
#endif // CONFIG_BOARDCTL_POWEROFF
#endif // CONFIG_SCHED_WORKQUEUE)