aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-10-27 22:42:43 -0700
committerpx4dev <px4@purgatory.org>2012-10-27 22:42:43 -0700
commit98791bc6740bcbcbb355befd7c57ff22b9583bb5 (patch)
tree914489e23ada4e6cef04f426343c676fe6eec38d
parent22b0add293f7aa7f1331fab61f5141f647e0188f (diff)
downloadpx4-firmware-98791bc6740bcbcbb355befd7c57ff22b9583bb5.tar.gz
px4-firmware-98791bc6740bcbcbb355befd7c57ff22b9583bb5.tar.bz2
px4-firmware-98791bc6740bcbcbb355befd7c57ff22b9583bb5.zip
Remove reboot() API, replace with a prototype for up_systemreset() which is portable.
-rw-r--r--apps/commander/state_machine_helper.c2
-rw-r--r--apps/drivers/boards/px4fmu/px4fmu_internal.h8
-rw-r--r--apps/drivers/px4fmu/fmu.cpp2
-rw-r--r--apps/systemcmds/reboot/reboot.c5
-rw-r--r--apps/systemlib/systemlib.c35
-rw-r--r--apps/systemlib/systemlib.h2
6 files changed, 12 insertions, 42 deletions
diff --git a/apps/commander/state_machine_helper.c b/apps/commander/state_machine_helper.c
index 794fb679c..a64d99cd4 100644
--- a/apps/commander/state_machine_helper.c
+++ b/apps/commander/state_machine_helper.c
@@ -138,7 +138,7 @@ int do_state_update(int status_pub, struct vehicle_status_s *current_status, con
current_status->flag_system_armed = false;
mavlink_log_critical(mavlink_fd, "[commander] REBOOTING SYSTEM");
usleep(500000);
- reboot();
+ up_systemreset();
/* SPECIAL CASE: NEVER RETURNS FROM THIS FUNCTION CALL */
} else {
invalid_state = true;
diff --git a/apps/drivers/boards/px4fmu/px4fmu_internal.h b/apps/drivers/boards/px4fmu/px4fmu_internal.h
index 1ae9e4c29..6550fdf3d 100644
--- a/apps/drivers/boards/px4fmu/px4fmu_internal.h
+++ b/apps/drivers/boards/px4fmu/px4fmu_internal.h
@@ -47,7 +47,11 @@
#include <nuttx/compiler.h>
#include <stdint.h>
-#include "stm32_internal.h"
+__BEGIN_DECLS
+
+/* these headers are not C++ safe */
+#include <stm32_internal.h>
+
/****************************************************************************************************
* Definitions
@@ -153,3 +157,5 @@
extern void stm32_spiinitialize(void);
#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/apps/drivers/px4fmu/fmu.cpp b/apps/drivers/px4fmu/fmu.cpp
index fe3e51c08..fff713bb5 100644
--- a/apps/drivers/px4fmu/fmu.cpp
+++ b/apps/drivers/px4fmu/fmu.cpp
@@ -59,13 +59,13 @@
#include <drivers/drv_gpio.h>
#include <drivers/boards/px4fmu/px4fmu_internal.h>
+#include <systemlib/systemlib.h>
#include <systemlib/mixer/mixer.h>
#include <drivers/drv_mixer.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
-#include <systemlib/systemlib.h>
#include <systemlib/err.h>
class PX4FMU : public device::CDev
diff --git a/apps/systemcmds/reboot/reboot.c b/apps/systemcmds/reboot/reboot.c
index e8886139d..47d3cd948 100644
--- a/apps/systemcmds/reboot/reboot.c
+++ b/apps/systemcmds/reboot/reboot.c
@@ -41,14 +41,13 @@
#include <unistd.h>
#include <stdio.h>
-#include "systemlib/systemlib.h"
+#include <systemlib/systemlib.h>
__EXPORT int reboot_main(int argc, char *argv[]);
int reboot_main(int argc, char *argv[])
{
- reboot();
- return 0;
+ up_systemreset();
}
diff --git a/apps/systemlib/systemlib.c b/apps/systemlib/systemlib.c
index 50ac62464..750e783f5 100644
--- a/apps/systemlib/systemlib.c
+++ b/apps/systemlib/systemlib.c
@@ -73,41 +73,6 @@ const struct __multiport_info multiport_info = {
static void kill_task(FAR _TCB *tcb, FAR void *arg);
-/****************************************************************************
- * user_start
- ****************************************************************************/
-
-int reboot(void)
-{
- sched_lock();
- // print text
- printf("\r\nRebooting system - ending tasks and performing hard reset\r\n\r\n");
- fflush(stdout);
- //usleep(5000);
-
- /* Sending kill signal to other tasks */
- //killall();
-
- /* Waiting maximum time for all to exit */
- //usleep(5000);
- //sched_lock();
-
- /* Resetting CPU */
- // FIXME Need check for ARM architecture here
-#ifndef NVIC_AIRCR
-#define NVIC_AIRCR (*((uint32_t*)0xE000ED0C))
-#endif
-
- /* Set the SYSRESETREQ bit to force a reset */
- NVIC_AIRCR = 0x05fa0004;
-
- /* Spinning until the board is really reset */
- while (true);
-
- /* Should never reach here */
- return 0;
-}
-
void killall()
{
// printf("Sending SIGUSR1 to all processes now\n");
diff --git a/apps/systemlib/systemlib.h b/apps/systemlib/systemlib.h
index 997f40ded..f31c5cd1f 100644
--- a/apps/systemlib/systemlib.h
+++ b/apps/systemlib/systemlib.h
@@ -45,7 +45,7 @@
__BEGIN_DECLS
/** Reboots the board */
-__EXPORT int reboot(void);
+extern void up_systemreset(void) noreturn_function;
/** Sends SIGUSR1 to all processes */
__EXPORT void killall(void);