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
+6 -21
View File
@@ -41,6 +41,8 @@
#include <px4_platform_common/log.h>
#include <px4_platform_common/tasks.h>
#include <nuttx/board.h>
#include <sys/wait.h>
#include <stdbool.h>
#include <stdio.h>
@@ -52,23 +54,10 @@
#include <errno.h>
#include <stdbool.h>
void
px4_systemreset(bool to_bootloader)
{
board_set_bootload_mode(to_bootloader ? board_reset_enter_bootloader : board_reset_normal);
board_system_reset(to_bootloader ? 1 : 0);
#if defined BOARD_HAS_NO_RESET
/* In case there is no HW support Just exit*/
PX4_WARN("System Reset Called");
exit(1);
#endif
}
int px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char *const argv[])
{
int pid;
sched_lock();
#if !defined(CONFIG_DISABLE_ENVIRON)
/* None of the modules access the environment variables (via getenv() for instance), so delete them
* all. They are only used within the startup script, and NuttX automatically exports them to the children
@@ -77,18 +66,14 @@ int px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_
*/
clearenv();
#endif
/* create the task */
pid = task_create(name, priority, stack_size, entry, argv);
int pid = task_create(name, priority, stack_size, entry, argv);
if (pid > 0) {
/* configure the scheduler */
struct sched_param param;
param.sched_priority = priority;
struct sched_param param = { .sched_priority = priority };
sched_setscheduler(pid, scheduler, &param);
/* XXX do any other private task accounting here before the task starts */
}
sched_unlock();
@@ -32,5 +32,5 @@
############################################################################
px4_add_library(arch_board_reset
board_reset.c
board_reset.cpp
)
@@ -33,7 +33,7 @@
****************************************************************************/
/**
* @file board_reset.c
* @file board_reset.cpp
* Implementation of IMXRT based Board RESET API
*/
@@ -49,43 +49,23 @@
# error CONFIG_IMXRT_RTC_MAGIC_REG can nt have the save value as PX4_IMXRT_RTC_REBOOT_REG
#endif
int board_reset(int status)
static int board_reset_enter_bootloader()
{
up_systemreset();
return 0;
}
int board_set_bootload_mode(board_reset_e mode)
{
uint32_t regvalue = 0;
switch (mode) {
case board_reset_normal:
case board_reset_extended:
break;
case board_reset_enter_bootloader:
regvalue = 0xb007b007;
break;
default:
return -EINVAL;
}
uint32_t regvalue = 0xb007b007;
putreg32(regvalue, IMXRT_SNVS_LPGPR(PX4_IMXRT_RTC_REBOOT_REG));
return OK;
}
void board_system_reset(int status)
int board_reset(int status)
{
if (status == 1) {
board_reset_enter_bootloader();
}
#if defined(BOARD_HAS_ON_RESET)
board_on_reset(status);
#endif
#ifdef CONFIG_BOARDCTL_RESET
board_reset(status);
#endif
while (1);
up_systemreset();
return 0;
}
@@ -32,5 +32,5 @@
############################################################################
px4_add_library(arch_board_reset
board_reset.c
board_reset.cpp
)
@@ -33,7 +33,7 @@
****************************************************************************/
/**
* @file board_reset.c
* @file board_reset.cpp
* Implementation of kinetis based Board RESET API
*/
@@ -41,12 +41,14 @@
#include <errno.h>
#include <nuttx/board.h>
#ifdef CONFIG_BOARDCTL_RESET
/****************************************************************************
* Public functions
****************************************************************************/
static int board_reset_enter_bootloader()
{
uint32_t regvalue = 0xb007b007;
*((uint32_t *) KINETIS_VBATR_BASE) = regvalue;
return OK;
}
/****************************************************************************
* Name: board_reset
@@ -70,38 +72,16 @@
int board_reset(int status)
{
if (status == 1) {
board_reset_enter_bootloader();
}
#if defined(BOARD_HAS_ON_RESET)
board_on_reset(status);
#endif
up_systemreset();
return 0;
}
#endif /* CONFIG_BOARDCTL_RESET */
int board_set_bootload_mode(board_reset_e mode)
{
uint32_t regvalue = 0;
switch (mode) {
case board_reset_normal:
case board_reset_extended:
break;
case board_reset_enter_bootloader:
regvalue = 0xb007b007;
break;
default:
return -EINVAL;
}
*((uint32_t *) KINETIS_VBATR_BASE) = regvalue;
return OK;
}
void board_system_reset(int status)
{
board_reset(status);
while (1);
}
@@ -32,5 +32,5 @@
############################################################################
px4_add_library(arch_board_reset
board_reset.c
board_reset.cpp
)
@@ -34,7 +34,7 @@
****************************************************************************/
/**
* @file board_reset.c
* @file board_reset.cpp
* Implementation of kinetis based Board RESET API
*/
@@ -46,9 +46,12 @@
#ifdef CONFIG_BOARDCTL_RESET
/****************************************************************************
* Public functions
****************************************************************************/
static int board_reset_enter_bootloader()
{
uint32_t regvalue = RCM_PARAM_ESW;
*((uint32_t *) S32K1XX_RCM_SRS) = regvalue;
return OK;
}
/****************************************************************************
* Name: board_reset
@@ -72,38 +75,16 @@
int board_reset(int status)
{
if (status == 1) {
board_reset_enter_bootloader();
}
#if defined(BOARD_HAS_ON_RESET)
board_on_reset(status);
#endif
up_systemreset();
return 0;
}
#endif /* CONFIG_BOARDCTL_RESET */
int board_set_bootload_mode(board_reset_e mode)
{
uint32_t regvalue = 0;
switch (mode) {
case board_reset_normal:
case board_reset_extended:
break;
case board_reset_enter_bootloader:
regvalue = RCM_PARAM_ESW;
break;
default:
return -EINVAL;
}
*((uint32_t *) S32K1XX_RCM_SRS) = regvalue;
return OK;
}
void board_system_reset(int status)
{
board_reset(status);
while (1);
}
@@ -32,5 +32,5 @@
############################################################################
px4_add_library(arch_board_reset
board_reset.c
board_reset.cpp
)
@@ -33,7 +33,7 @@
****************************************************************************/
/**
* @file board_reset.c
* @file board_reset.cpp
* Implementation of STM32 based Board RESET API
*/
@@ -45,9 +45,21 @@
#ifdef CONFIG_BOARDCTL_RESET
/****************************************************************************
* Public functions
****************************************************************************/
static int board_reset_enter_bootloader()
{
stm32_pwr_enablebkp(true);
uint32_t regvalue = 0xb007b007;
// Check if we can to use the new register definition
#ifndef STM32_RTC_BK0R
*(uint32_t *)STM32_BKP_BASE = regvalue;
#else
*(uint32_t *)STM32_RTC_BK0R = regvalue;
#endif
stm32_pwr_enablebkp(false);
return OK;
}
/****************************************************************************
* Name: board_reset
@@ -71,51 +83,16 @@
int board_reset(int status)
{
if (status == 1) {
board_reset_enter_bootloader();
}
#if defined(BOARD_HAS_ON_RESET)
board_on_reset(status);
#endif
up_systemreset();
return 0;
}
#endif /* CONFIG_BOARDCTL_RESET */
int board_set_bootload_mode(board_reset_e mode)
{
uint32_t regvalue = 0;
switch (mode) {
case board_reset_normal:
case board_reset_extended:
break;
case board_reset_enter_bootloader:
regvalue = 0xb007b007;
break;
default:
return -EINVAL;
}
stm32_pwr_enablebkp(true);
// Check if we can to use the new register definition
#ifndef STM32_RTC_BK0R
*(uint32_t *)STM32_BKP_BASE = regvalue;
#else
*(uint32_t *)STM32_RTC_BK0R = regvalue;
#endif
stm32_pwr_enablebkp(false);
return OK;
}
void board_system_reset(int status)
{
#if defined(BOARD_HAS_ON_RESET)
board_on_reset(status);
#endif
#ifdef CONFIG_BOARDCTL_RESET
board_reset(status);
#endif
while (1);
}