mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
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:
@@ -74,7 +74,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
||||
@@ -44,9 +44,6 @@
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (10.177939394f)
|
||||
|
||||
#define BOARD_HAS_NO_RESET
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
#define BOARD_MAX_LEDS 1 // Number of external LED's this board has
|
||||
|
||||
#define PX4_NUMBER_I2C_BUSES 4
|
||||
|
||||
@@ -99,7 +99,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -93,9 +93,6 @@ extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: board_on_reset
|
||||
*
|
||||
|
||||
@@ -101,7 +101,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
#tests # tests and test runner
|
||||
|
||||
@@ -42,9 +42,6 @@
|
||||
#define BOARD_OVERRIDE_UUID "EAGLEID000000000" // must be of length 16
|
||||
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_EAGLE
|
||||
|
||||
#define BOARD_HAS_NO_RESET
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
@@ -100,7 +100,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
#tests # tests and test runner
|
||||
|
||||
@@ -42,9 +42,6 @@
|
||||
#define BOARD_OVERRIDE_UUID "EAGLEID000000000" // must be of length 16
|
||||
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_EAGLE
|
||||
|
||||
#define BOARD_HAS_NO_RESET
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
@@ -98,7 +98,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -70,7 +70,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
||||
@@ -44,8 +44,6 @@
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (11.0f)
|
||||
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
#define BOARD_MAX_LEDS 4 // Number external of LED's this board has
|
||||
|
||||
|
||||
|
||||
@@ -53,7 +53,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
||||
@@ -103,7 +103,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -49,6 +49,8 @@
|
||||
|
||||
extern int sercon_main(int c, char **argv);
|
||||
|
||||
__EXPORT void board_on_reset(int status) {}
|
||||
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* configure USB interfaces */
|
||||
|
||||
@@ -70,7 +70,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
||||
@@ -45,9 +45,6 @@
|
||||
#define BOARD_BATTERY1_V_DIV (10.177939394f)
|
||||
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
|
||||
|
||||
#define BOARD_HAS_NO_RESET
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
#define BOARD_MAX_LEDS 1 // Number of external LED's this board has
|
||||
|
||||
|
||||
|
||||
@@ -103,7 +103,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -60,7 +60,6 @@ CONFIG_MM_REGIONS=3
|
||||
CONFIG_NFILE_DESCRIPTORS=5
|
||||
CONFIG_NFILE_STREAMS=3
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PREALLOC_WDOGS=50
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
@@ -92,7 +91,6 @@ CONFIG_TIME_EXTENDED=y
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGINT_CHAR=0x03
|
||||
CONFIG_TTY_SIGSTP=y
|
||||
CONFIG_USART3_DMA=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_TXBUFSIZE=300
|
||||
CONFIG_USBDEV=y
|
||||
|
||||
@@ -34,22 +34,12 @@
|
||||
/**
|
||||
* @file bootloader_main.c
|
||||
*
|
||||
* PX4FMU-specific early startup code for bootloader
|
||||
* FMU-specific early startup code for bootloader
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include "board_config.h"
|
||||
#include "bl.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <chip.h>
|
||||
@@ -59,14 +49,11 @@
|
||||
|
||||
extern int sercon_main(int c, char **argv);
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
__EXPORT void
|
||||
stm32_boardinitialize(void)
|
||||
__EXPORT void board_on_reset(int status) {}
|
||||
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* configure USB interfaces */
|
||||
|
||||
stm32_usbinitialize();
|
||||
}
|
||||
|
||||
|
||||
@@ -104,7 +104,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -67,7 +67,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
||||
@@ -79,7 +79,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
|
||||
@@ -79,7 +79,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
|
||||
@@ -97,7 +97,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -103,7 +103,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -98,7 +98,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -101,7 +101,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -98,7 +98,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -98,7 +98,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -91,7 +91,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
||||
@@ -66,7 +66,6 @@ px4_add_board(
|
||||
reboot
|
||||
#reflect
|
||||
#sd_bench
|
||||
shutdown
|
||||
top
|
||||
#topic_listener
|
||||
#tune_control
|
||||
|
||||
@@ -87,7 +87,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
#tests # tests and test runner
|
||||
top
|
||||
#topic_listener
|
||||
|
||||
@@ -111,7 +111,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -110,7 +110,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -105,7 +105,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -105,7 +105,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -104,7 +104,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -104,7 +104,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -104,7 +104,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -105,7 +105,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -104,7 +104,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -107,7 +107,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -109,7 +109,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -82,7 +82,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
||||
@@ -108,7 +108,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -93,7 +93,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
||||
@@ -103,7 +103,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -82,7 +82,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
||||
@@ -108,7 +108,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -109,7 +109,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -107,7 +107,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -106,7 +106,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
|
||||
@@ -69,7 +69,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
||||
@@ -42,9 +42,6 @@
|
||||
#define BOARD_OVERRIDE_UUID "RPIID00000000000" // must be of length 16
|
||||
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_RPI
|
||||
|
||||
#define BOARD_HAS_NO_RESET
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*/
|
||||
|
||||
@@ -65,7 +65,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
||||
@@ -65,7 +65,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
||||
@@ -11,7 +11,6 @@ px4_add_board(
|
||||
SYSTEMCMDS
|
||||
param
|
||||
perf
|
||||
reboot
|
||||
shutdown
|
||||
topic_listener
|
||||
ver
|
||||
|
||||
@@ -64,7 +64,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
||||
@@ -32,9 +32,8 @@
|
||||
############################################################################
|
||||
|
||||
add_library(drivers_board
|
||||
board_shutdown.cpp
|
||||
i2c.cpp
|
||||
sitl_led.c
|
||||
sitl_board_shutdown.c
|
||||
spi.cpp
|
||||
)
|
||||
|
||||
|
||||
@@ -44,8 +44,9 @@
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (10.177939394f)
|
||||
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
|
||||
#define BOARD_HAS_POWER_CONTROL
|
||||
#define BOARD_HAS_NO_BOOTLOADER
|
||||
|
||||
#define BOARD_HAS_POWER_CONTROL 1
|
||||
#define CONFIG_BOARDCTL_POWEROFF 1
|
||||
|
||||
#define PX4_NUMBER_I2C_BUSES 1
|
||||
|
||||
|
||||
@@ -32,21 +32,28 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file sitl_board_shutdown.c
|
||||
* @file board_shutdown.cpp
|
||||
*
|
||||
* sitl board shutdown backend.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <board_config.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#if defined(BOARD_HAS_POWER_CONTROL)
|
||||
int board_register_power_state_notification_cb(power_button_state_notification_t cb)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
#endif // BOARD_HAS_POWER_CONTROL
|
||||
|
||||
int board_shutdown()
|
||||
#if defined(CONFIG_BOARDCTL_POWEROFF)
|
||||
int board_power_off(int status)
|
||||
{
|
||||
px4_systemreset(false);
|
||||
printf("Exiting NOW.\n");
|
||||
fflush(stdout);
|
||||
system_exit(0);
|
||||
return 0;
|
||||
}
|
||||
#endif // CONFIG_BOARDCTL_POWEROFF
|
||||
@@ -62,7 +62,6 @@ px4_add_board(
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
sd_bench
|
||||
shutdown
|
||||
tests # tests and test runner
|
||||
|
||||
@@ -81,7 +81,6 @@ px4_add_board(
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -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
|
||||
|
||||
/************************************************************************************
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -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)
|
||||
|
||||
@@ -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, ¶m);
|
||||
|
||||
/* 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);
|
||||
}
|
||||
@@ -104,7 +104,7 @@ if(NOT CMAKE_SYSTEM_NAME STREQUAL "CYGWIN")
|
||||
WORKING_DIRECTORY ${SITL_WORKING_DIR})
|
||||
|
||||
#set_tests_properties(shutdown PROPERTIES FAIL_REGULAR_EXPRESSION "shutdown FAILED")
|
||||
set_tests_properties(shutdown PROPERTIES PASS_REGULAR_EXPRESSION "Shutting down")
|
||||
set_tests_properties(shutdown PROPERTIES PASS_REGULAR_EXPRESSION "Exiting NOW.")
|
||||
sanitizer_fail_test_on_error(shutdown)
|
||||
endif()
|
||||
|
||||
@@ -145,7 +145,7 @@ foreach(cmd_name ${test_cmds})
|
||||
WORKING_DIRECTORY ${SITL_WORKING_DIR})
|
||||
|
||||
sanitizer_fail_test_on_error(posix_${cmd_name})
|
||||
set_tests_properties(posix_${cmd_name} PROPERTIES PASS_REGULAR_EXPRESSION "Shutting down")
|
||||
set_tests_properties(posix_${cmd_name} PROPERTIES PASS_REGULAR_EXPRESSION "Exiting NOW.")
|
||||
endforeach()
|
||||
|
||||
if(CMAKE_BUILD_TYPE STREQUAL Coverage)
|
||||
|
||||
@@ -111,13 +111,6 @@ static void *entry_adapter(void *ptr)
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void
|
||||
px4_systemreset(bool to_bootloader)
|
||||
{
|
||||
PX4_WARN("Called px4_system_reset");
|
||||
system_exit(0);
|
||||
}
|
||||
|
||||
px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry,
|
||||
char *const argv[])
|
||||
{
|
||||
|
||||
@@ -107,12 +107,6 @@ static void *entry_adapter(void *ptr)
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void
|
||||
px4_systemreset(bool to_bootloader)
|
||||
{
|
||||
PX4_WARN("Called px4_system_reset but NOT yet implemented.");
|
||||
}
|
||||
|
||||
px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry,
|
||||
char *const argv[])
|
||||
{
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
uorb start
|
||||
|
||||
param load
|
||||
param set CBRK_SUPPLY_CHK 894281
|
||||
param set SYS_RESTART_TYPE 0
|
||||
|
||||
dataman start
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
uorb start
|
||||
|
||||
param load
|
||||
param set CBRK_SUPPLY_CHK 894281
|
||||
param set SYS_RESTART_TYPE 0
|
||||
|
||||
dataman start
|
||||
|
||||
@@ -8,6 +8,7 @@ uorb start
|
||||
param load
|
||||
|
||||
param set BAT_N_CELLS 3
|
||||
param set CBRK_SUPPLY_CHK 894281
|
||||
param set MAV_TYPE 22
|
||||
param set VT_TYPE 2
|
||||
param set SYS_RESTART_TYPE 0
|
||||
@@ -41,7 +42,7 @@ logger start -e -t
|
||||
|
||||
mavlink boot_complete
|
||||
|
||||
sleep 2
|
||||
sleep 1
|
||||
|
||||
echo "Boot complete"
|
||||
|
||||
@@ -80,8 +81,6 @@ ekf2 stop
|
||||
airspeed_selector stop
|
||||
sensors stop
|
||||
|
||||
sleep 2
|
||||
|
||||
simulator stop
|
||||
tone_alarm stop
|
||||
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
uorb start
|
||||
|
||||
param load
|
||||
param set CBRK_SUPPLY_CHK 894281
|
||||
param set SYS_RESTART_TYPE 0
|
||||
|
||||
dataman start
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
uorb start
|
||||
|
||||
param load
|
||||
param set CBRK_SUPPLY_CHK 894281
|
||||
param set SYS_RESTART_TYPE 0
|
||||
|
||||
dataman start
|
||||
|
||||
@@ -223,7 +223,7 @@ void UavcanNode::busevent_signal_trampoline()
|
||||
|
||||
static void cb_reboot(const uavcan::TimerEvent &)
|
||||
{
|
||||
px4_systemreset(false);
|
||||
board_reset(0);
|
||||
}
|
||||
|
||||
void UavcanNode::cb_beginfirmware_update(const uavcan::ReceivedDataStructure<UavcanNode::BeginFirmwareUpdate::Request>
|
||||
@@ -276,7 +276,7 @@ class RestartRequestHandler: public uavcan::IRestartRequestHandler
|
||||
{
|
||||
PX4_INFO("UAVCAN: Restarting by request from %i\n", int(request_source.get()));
|
||||
usleep(20 * 1000 * 1000);
|
||||
px4_systemreset(false);
|
||||
board_reset(0);
|
||||
return true; // Will never be executed BTW
|
||||
}
|
||||
} restart_request_handler;
|
||||
|
||||
@@ -95,7 +95,6 @@ typedef enum VEHICLE_MODE_FLAG {
|
||||
|
||||
/* Mavlink log uORB handle */
|
||||
static orb_advert_t mavlink_log_pub = nullptr;
|
||||
static orb_advert_t power_button_state_pub = nullptr;
|
||||
|
||||
/* flags */
|
||||
static volatile bool thread_should_exit = false; /**< daemon exit flag */
|
||||
@@ -116,6 +115,8 @@ void *commander_low_prio_loop(void *arg);
|
||||
static void answer_command(const vehicle_command_s &cmd, unsigned result,
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> &command_ack_pub);
|
||||
|
||||
#if defined(BOARD_HAS_POWER_CONTROL)
|
||||
static orb_advert_t power_button_state_pub = nullptr;
|
||||
static int power_button_state_notification_cb(board_power_button_state_notification_e request)
|
||||
{
|
||||
// Note: this can be called from IRQ handlers, so we publish a message that will be handled
|
||||
@@ -155,6 +156,7 @@ static int power_button_state_notification_cb(board_power_button_state_notificat
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif // BOARD_HAS_POWER_CONTROL
|
||||
|
||||
#ifndef CONSTRAINED_FLASH
|
||||
static bool send_vehicle_command(uint16_t cmd, float param1 = NAN, float param2 = NAN, float param3 = NAN,
|
||||
@@ -231,9 +233,6 @@ extern "C" __EXPORT int commander_main(int argc, char *argv[])
|
||||
thread_should_exit = true;
|
||||
|
||||
Commander::main(argc, argv);
|
||||
|
||||
PX4_INFO("terminated.");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -992,50 +991,47 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_
|
||||
cmd_result = handle_command_motor_test(cmd);
|
||||
break;
|
||||
|
||||
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
||||
case vehicle_command_s::VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN: {
|
||||
|
||||
// do nothing for autopilot
|
||||
if (((int)(cmd.param1)) == 0) {
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub);
|
||||
const int param1 = cmd.param1;
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
if (shutdown_if_allowed()) {
|
||||
bool shutdown_ret_val = PX4_ERROR;
|
||||
|
||||
if (((int)(cmd.param1)) == 1) {
|
||||
if (param1 == 0) {
|
||||
// 0: Do nothing for autopilot
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub);
|
||||
px4_usleep(200000);
|
||||
// reboot
|
||||
shutdown_ret_val = px4_shutdown_request(true, false);
|
||||
|
||||
} else if (((int)(cmd.param1)) == 2) {
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub);
|
||||
px4_usleep(200000);
|
||||
// shutdown
|
||||
shutdown_ret_val = px4_shutdown_request(false, false);
|
||||
#if defined(CONFIG_BOARDCTL_RESET)
|
||||
|
||||
} else if (((int)(cmd.param1)) == 3) {
|
||||
} else if ((param1 == 1) && shutdown_if_allowed() && (px4_reboot_request(false, 400_ms) == 0)) {
|
||||
// 1: Reboot autopilot
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub);
|
||||
px4_usleep(200000);
|
||||
// reboot to bootloader
|
||||
shutdown_ret_val = px4_shutdown_request(true, true);
|
||||
|
||||
while (1) { px4_usleep(1); }
|
||||
|
||||
#endif // CONFIG_BOARDCTL_RESET
|
||||
|
||||
#if defined(CONFIG_BOARDCTL_POWEROFF)
|
||||
|
||||
} else if ((param1 == 2) && shutdown_if_allowed() && (px4_shutdown_request(400_ms) == 0)) {
|
||||
// 2: Shutdown autopilot
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub);
|
||||
|
||||
while (1) { px4_usleep(1); }
|
||||
|
||||
#endif // CONFIG_BOARDCTL_POWEROFF
|
||||
|
||||
#if defined(CONFIG_BOARDCTL_RESET)
|
||||
|
||||
} else if ((param1 == 3) && shutdown_if_allowed() && (px4_reboot_request(true, 400_ms) == 0)) {
|
||||
// 3: Reboot autopilot and keep it in the bootloader until upgraded.
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub);
|
||||
|
||||
while (1) { px4_usleep(1); }
|
||||
|
||||
#endif // CONFIG_BOARDCTL_RESET
|
||||
|
||||
} else {
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED, command_ack_pub);
|
||||
break;
|
||||
}
|
||||
|
||||
if (shutdown_ret_val) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "System does not support shutdown");
|
||||
|
||||
} else {
|
||||
while (1) { px4_usleep(1); }
|
||||
}
|
||||
|
||||
} else {
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_DENIED, command_ack_pub);
|
||||
}
|
||||
|
||||
break;
|
||||
@@ -1219,6 +1215,7 @@ Commander::run()
|
||||
led_init();
|
||||
buzzer_init();
|
||||
|
||||
#if defined(BOARD_HAS_POWER_CONTROL)
|
||||
{
|
||||
// we need to do an initial publication to make sure uORB allocates the buffer, which cannot happen
|
||||
// in IRQ context.
|
||||
@@ -1234,6 +1231,7 @@ Commander::run()
|
||||
PX4_ERR("Failed to register power notification callback");
|
||||
}
|
||||
|
||||
#endif // BOARD_HAS_POWER_CONTROL
|
||||
|
||||
get_circuit_breaker_params();
|
||||
|
||||
@@ -1409,17 +1407,27 @@ Commander::run()
|
||||
/* Update OA parameter */
|
||||
status_flags.avoidance_system_required = _param_com_obs_avoid.get();
|
||||
|
||||
#if defined(BOARD_HAS_POWER_CONTROL)
|
||||
|
||||
/* handle power button state */
|
||||
if (_power_button_state_sub.updated()) {
|
||||
power_button_state_s button_state;
|
||||
|
||||
if (_power_button_state_sub.copy(&button_state)) {
|
||||
if (button_state.event == power_button_state_s::PWR_BUTTON_STATE_REQUEST_SHUTDOWN) {
|
||||
px4_shutdown_request(false, false);
|
||||
#if defined(CONFIG_BOARDCTL_POWEROFF)
|
||||
|
||||
if (shutdown_if_allowed() && (px4_shutdown_request() == 0)) {
|
||||
while (1) { px4_usleep(1); }
|
||||
}
|
||||
|
||||
#endif // CONFIG_BOARDCTL_POWEROFF
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif // BOARD_HAS_POWER_CONTROL
|
||||
|
||||
_sp_man_sub.update(&_sp_man);
|
||||
|
||||
offboard_control_update();
|
||||
@@ -1439,8 +1447,10 @@ Commander::run()
|
||||
status_flags.condition_power_input_valid = true;
|
||||
}
|
||||
|
||||
#if defined(CONFIG_BOARDCTL_RESET)
|
||||
|
||||
/* if the USB hardware connection went away, reboot */
|
||||
if (status_flags.usb_connected && !system_power.usb_connected && shutdown_if_allowed()) {
|
||||
if (status_flags.usb_connected && !system_power.usb_connected) {
|
||||
/*
|
||||
* Apparently the USB cable went away but we are still powered,
|
||||
* so we bring the system back to a nominal state for flight.
|
||||
@@ -1449,10 +1459,14 @@ Commander::run()
|
||||
* for flight and continuing to run it would add a software risk
|
||||
* without a need. The clean approach to unload it is to reboot.
|
||||
*/
|
||||
mavlink_log_critical(&mavlink_log_pub, "USB disconnected, rebooting for flight safety")
|
||||
px4_usleep(400000);
|
||||
px4_shutdown_request(true, false);
|
||||
if (shutdown_if_allowed() && (px4_reboot_request(400_ms) == 0)) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "USB disconnected, rebooting for flight safety");
|
||||
|
||||
while (1) { px4_usleep(1); }
|
||||
}
|
||||
}
|
||||
|
||||
#endif // CONFIG_BOARDCTL_RESET
|
||||
}
|
||||
}
|
||||
|
||||
@@ -3471,12 +3485,6 @@ void *commander_low_prio_loop(void *arg)
|
||||
|
||||
} else if (((int)(cmd.param1)) == 1) {
|
||||
|
||||
#ifdef __PX4_QURT
|
||||
// TODO FIXME: on snapdragon the save happens too early when the params
|
||||
// are not set yet. We therefore need to wait some time first.
|
||||
px4_usleep(1000000);
|
||||
#endif
|
||||
|
||||
int ret = param_save_default();
|
||||
|
||||
if (ret == OK) {
|
||||
@@ -3883,18 +3891,19 @@ void Commander::battery_status_check()
|
||||
// Handle shutdown request from emergency battery action
|
||||
if (update_internal_battery_state) {
|
||||
|
||||
if ((_battery_warning == battery_status_s::BATTERY_WARNING_EMERGENCY) && shutdown_if_allowed()) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "Dangerously low battery! Shutting system down");
|
||||
px4_usleep(200000);
|
||||
if (_battery_warning == battery_status_s::BATTERY_WARNING_EMERGENCY) {
|
||||
#if defined(CONFIG_BOARDCTL_POWEROFF)
|
||||
|
||||
int ret_val = px4_shutdown_request(false, false);
|
||||
if (shutdown_if_allowed() && (px4_shutdown_request(400_ms) == 0)) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "Dangerously low battery! Shutting system down");
|
||||
|
||||
if (ret_val) {
|
||||
mavlink_log_critical(&mavlink_log_pub, "System does not support shutdown");
|
||||
while (1) { px4_usleep(1); }
|
||||
|
||||
} else {
|
||||
while (1) { px4_usleep(1); }
|
||||
mavlink_log_critical(&mavlink_log_pub, "System does not support shutdown");
|
||||
}
|
||||
|
||||
#endif // CONFIG_BOARDCTL_POWEROFF
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -398,7 +398,6 @@ private:
|
||||
uORB::Subscription _iridiumsbd_status_sub{ORB_ID(iridiumsbd_status)};
|
||||
uORB::Subscription _land_detector_sub{ORB_ID(vehicle_land_detected)};
|
||||
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
|
||||
uORB::Subscription _power_button_state_sub{ORB_ID(power_button_state)};
|
||||
uORB::Subscription _safety_sub{ORB_ID(safety)};
|
||||
uORB::Subscription _sp_man_sub{ORB_ID(manual_control_setpoint)};
|
||||
uORB::Subscription _subsys_sub{ORB_ID(subsystem_info)};
|
||||
@@ -407,6 +406,10 @@ private:
|
||||
uORB::Subscription _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)};
|
||||
uORB::Subscription _vtol_vehicle_status_sub{ORB_ID(vtol_vehicle_status)};
|
||||
|
||||
#if defined(BOARD_HAS_POWER_CONTROL)
|
||||
uORB::Subscription _power_button_state_sub {ORB_ID(power_button_state)};
|
||||
#endif // BOARD_HAS_POWER_CONTROL
|
||||
|
||||
uORB::SubscriptionData<airspeed_s> _airspeed_sub{ORB_ID(airspeed)};
|
||||
uORB::SubscriptionData<estimator_status_s> _estimator_status_sub{ORB_ID(estimator_status)};
|
||||
uORB::SubscriptionData<mission_result_s> _mission_result_sub{ORB_ID(mission_result)};
|
||||
|
||||
@@ -852,7 +852,7 @@ Replay::run()
|
||||
|
||||
//TODO: add parameter -q?
|
||||
replay_file.close();
|
||||
px4_shutdown_request(false, false);
|
||||
px4_shutdown_request();
|
||||
}
|
||||
|
||||
onExitMainLoop();
|
||||
|
||||
@@ -35,7 +35,8 @@ px4_add_module(
|
||||
MAIN reboot
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
reboot.c
|
||||
reboot.cpp
|
||||
DEPENDS
|
||||
px4_platform
|
||||
)
|
||||
|
||||
|
||||
@@ -45,9 +45,7 @@
|
||||
#include <px4_platform_common/shutdown.h>
|
||||
#include <string.h>
|
||||
|
||||
__EXPORT int reboot_main(int argc, char *argv[]);
|
||||
|
||||
static void print_usage(void)
|
||||
static void print_usage()
|
||||
{
|
||||
PRINT_MODULE_DESCRIPTION("Reboot the system");
|
||||
|
||||
@@ -57,13 +55,13 @@ static void print_usage(void)
|
||||
PRINT_MODULE_USAGE_ARG("lock|unlock", "Take/release the shutdown lock (for testing)", true);
|
||||
}
|
||||
|
||||
int reboot_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int reboot_main(int argc, char *argv[])
|
||||
{
|
||||
int ch;
|
||||
bool to_bootloader = false;
|
||||
|
||||
int myoptind = 1;
|
||||
const char *myoptarg = NULL;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "b", &myoptind, &myoptarg)) != -1) {
|
||||
switch (ch) {
|
||||
@@ -100,7 +98,7 @@ int reboot_main(int argc, char *argv[])
|
||||
return ret;
|
||||
}
|
||||
|
||||
int ret = px4_shutdown_request(true, to_bootloader);
|
||||
int ret = px4_reboot_request(to_bootloader);
|
||||
|
||||
if (ret < 0) {
|
||||
PX4_ERR("reboot failed (%i)", ret);
|
||||
@@ -33,7 +33,6 @@
|
||||
px4_add_module(
|
||||
MODULE systemcmds__shutdown
|
||||
MAIN shutdown
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
shutdown.c
|
||||
shutdown.cpp
|
||||
)
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2016-2020 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
|
||||
@@ -35,16 +35,10 @@
|
||||
* @file shutdown.c
|
||||
* Tool similar to UNIX shutdown command.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/shutdown.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
|
||||
__EXPORT int shutdown_main(int argc, char *argv[]);
|
||||
|
||||
int shutdown_main(int argc, char *argv[])
|
||||
extern "C" __EXPORT int shutdown_main(int argc, char *argv[])
|
||||
{
|
||||
(void)argc;
|
||||
(void)argv;
|
||||
|
||||
const bool to_bootloader = false;
|
||||
px4_systemreset(to_bootloader);
|
||||
return px4_shutdown_request();
|
||||
}
|
||||
@@ -58,7 +58,6 @@ set(srcs
|
||||
test_microbench_matrix.cpp
|
||||
test_microbench_uorb.cpp
|
||||
test_mixer.cpp
|
||||
test_mount.c
|
||||
test_param.c
|
||||
test_parameters.cpp
|
||||
test_perf.c
|
||||
@@ -80,6 +79,7 @@ set(srcs
|
||||
|
||||
if(${PX4_PLATFORM} STREQUAL "nuttx")
|
||||
list(APPEND srcs
|
||||
test_mount.cpp
|
||||
test_time.c
|
||||
test_uart_break.c
|
||||
)
|
||||
|
||||
@@ -40,6 +40,7 @@
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
#include <px4_platform_common/shutdown.h>
|
||||
|
||||
#include <sys/stat.h>
|
||||
#include <dirent.h>
|
||||
@@ -56,8 +57,7 @@
|
||||
const int fsync_tries = 1;
|
||||
const int abort_tries = 10;
|
||||
|
||||
int
|
||||
test_mount(int argc, char *argv[])
|
||||
int test_mount(int argc, char *argv[])
|
||||
{
|
||||
const unsigned iterations = 2000;
|
||||
const unsigned alignments = 10;
|
||||
@@ -289,7 +289,7 @@ test_mount(int argc, char *argv[])
|
||||
fsync(fileno(stdout));
|
||||
fsync(fileno(stderr));
|
||||
px4_usleep(50000);
|
||||
px4_systemreset(false);
|
||||
px4_reboot_request();
|
||||
|
||||
/* never going to get here */
|
||||
return 0;
|
||||
@@ -69,6 +69,7 @@ const struct {
|
||||
#ifdef __PX4_NUTTX
|
||||
{"file", test_file, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"led", test_led, 0},
|
||||
{"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"time", test_time, OPT_NOJIGTEST},
|
||||
{"uart_baudchange", test_uart_baudchange, OPT_NOJIGTEST},
|
||||
{"uart_break", test_uart_break, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
@@ -102,7 +103,6 @@ const struct {
|
||||
{"microbench_uorb", test_microbench_uorb, 0},
|
||||
{"mixer", test_mixer, OPT_NOJIGTEST},
|
||||
{"mixer", test_mixer, OPT_NOJIGTEST},
|
||||
{"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"param", test_param, 0},
|
||||
{"parameters", test_parameters, 0},
|
||||
{"perf", test_perf, OPT_NOJIGTEST},
|
||||
|
||||
Reference in New Issue
Block a user