41 #include <px4_platform_common/px4_config.h> 42 #include <px4_platform_common/getopt.h> 43 #include <px4_platform_common/log.h> 44 #include <px4_platform_common/module.h> 45 #include <px4_platform_common/shutdown.h> 52 PRINT_MODULE_DESCRIPTION(
"Reboot the system");
54 PRINT_MODULE_USAGE_NAME_SIMPLE(
"reboot",
"command");
55 PRINT_MODULE_USAGE_PARAM_FLAG(
'b',
"Reboot into bootloader",
true);
57 PRINT_MODULE_USAGE_ARG(
"lock|unlock",
"Take/release the shutdown lock (for testing)",
true);
63 bool to_bootloader =
false;
66 const char *myoptarg = NULL;
68 while ((ch = px4_getopt(argc, argv,
"b", &myoptind, &myoptarg)) != -1) {
81 if (myoptind >= 0 && myoptind < argc) {
84 if (strcmp(argv[myoptind],
"lock") == 0) {
85 ret = px4_shutdown_lock();
88 PX4_ERR(
"lock failed (%i)", ret);
92 if (strcmp(argv[myoptind],
"unlock") == 0) {
93 ret = px4_shutdown_unlock();
96 PX4_ERR(
"unlock failed (%i)", ret);
103 int ret = px4_shutdown_request(
true, to_bootloader);
106 PX4_ERR(
"reboot failed (%i)", ret);
110 while (1) { px4_usleep(1); }
static void print_usage(void)
__EXPORT int reboot_main(int argc, char *argv[])