aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp3
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp2
-rwxr-xr-xsrc/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp2
-rw-r--r--src/modules/commander/commander.c2
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_main.c2
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp3
-rw-r--r--src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c2
-rw-r--r--src/modules/mavlink/mavlink.c2
-rw-r--r--src/modules/mavlink_onboard/mavlink.c2
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c2
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c4
-rwxr-xr-xsrc/modules/position_estimator_mc/position_estimator_mc_main.c2
-rw-r--r--src/modules/px4iofirmware/adc.c2
-rw-r--r--src/modules/sdlog/sdlog.c4
-rw-r--r--src/modules/sdlog2/sdlog2.c2
-rw-r--r--src/modules/sensors/sensors.cpp2
-rw-r--r--src/modules/systemlib/cpuload.c54
-rw-r--r--src/modules/systemlib/cpuload.h6
-rw-r--r--src/modules/systemlib/err.c4
-rw-r--r--src/modules/systemlib/systemlib.c6
-rw-r--r--src/modules/systemlib/systemlib.h6
21 files changed, 56 insertions, 58 deletions
diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
index 10592ec7c..890184427 100644
--- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp
+++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
@@ -101,7 +101,8 @@ int att_pos_estimator_ekf_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("att_pos_estimator_ekf",
+
+ deamon_task = task_spawn_cmd("att_pos_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
4096,
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 8e18c3c9a..7e3eca085 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -123,7 +123,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
}
thread_should_exit = false;
- attitude_estimator_ekf_task = task_spawn("attitude_estimator_ekf",
+ attitude_estimator_ekf_task = task_spawn_cmd("attitude_estimator_ekf",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
12400,
diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
index 3cbc62ea1..3ca50fb39 100755
--- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
+++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp
@@ -117,7 +117,7 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[])
}
thread_should_exit = false;
- attitude_estimator_so3_comp_task = task_spawn("attitude_estimator_so3_comp",
+ attitude_estimator_so3_comp_task = task_spawn_cmd("attitude_estimator_so3_comp",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
12400,
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
index aab8f3e04..67f053e22 100644
--- a/src/modules/commander/commander.c
+++ b/src/modules/commander/commander.c
@@ -1200,7 +1200,7 @@ int commander_main(int argc, char *argv[])
}
thread_should_exit = false;
- daemon_task = task_spawn("commander",
+ daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
3000,
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
index 58477632b..6c9c137bb 100644
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
@@ -336,7 +336,7 @@ int fixedwing_att_control_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("fixedwing_att_control",
+ deamon_task = task_spawn_cmd("fixedwing_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,
diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index c3d57a85a..4803a526e 100644
--- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
+++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
@@ -108,7 +108,8 @@ int fixedwing_backside_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("fixedwing_backside",
+
+ deamon_task = task_spawn_cmd("fixedwing_backside",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
5120,
diff --git a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
index 71c78f5b8..48c0b9f9d 100644
--- a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
+++ b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
@@ -448,7 +448,7 @@ int fixedwing_pos_control_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("fixedwing_pos_control",
+ deamon_task = task_spawn_cmd("fixedwing_pos_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index de78cd139..c72a53fee 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -787,7 +787,7 @@ int mavlink_main(int argc, char *argv[])
errx(0, "mavlink already running\n");
thread_should_exit = false;
- mavlink_task = task_spawn("mavlink",
+ mavlink_task = task_spawn_cmd("mavlink",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
diff --git a/src/modules/mavlink_onboard/mavlink.c b/src/modules/mavlink_onboard/mavlink.c
index 5a2685560..cb6d6b16a 100644
--- a/src/modules/mavlink_onboard/mavlink.c
+++ b/src/modules/mavlink_onboard/mavlink.c
@@ -495,7 +495,7 @@ int mavlink_onboard_main(int argc, char *argv[])
errx(0, "mavlink already running\n");
thread_should_exit = false;
- mavlink_task = task_spawn("mavlink_onboard",
+ mavlink_task = task_spawn_cmd("mavlink_onboard",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c
index d94c0a69c..99f25cfe9 100644
--- a/src/modules/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
@@ -466,7 +466,7 @@ int multirotor_att_control_main(int argc, char *argv[])
if (!strcmp(argv[1 + optioncount], "start")) {
thread_should_exit = false;
- mc_task = task_spawn("multirotor_att_control",
+ mc_task = task_spawn_cmd("multirotor_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 15,
2048,
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index 7b8d83aa8..f39d11438 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c
@@ -94,7 +94,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to task_spawn().
+ * to task_spawn_cmd().
*/
int multirotor_pos_control_main(int argc, char *argv[])
{
@@ -110,7 +110,7 @@ int multirotor_pos_control_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("multirotor pos control",
+ deamon_task = task_spawn_cmd("multirotor pos control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 60,
4096,
diff --git a/src/modules/position_estimator_mc/position_estimator_mc_main.c b/src/modules/position_estimator_mc/position_estimator_mc_main.c
index 10dee3f22..984bd1329 100755
--- a/src/modules/position_estimator_mc/position_estimator_mc_main.c
+++ b/src/modules/position_estimator_mc/position_estimator_mc_main.c
@@ -123,7 +123,7 @@ int position_estimator_mc_main(int argc, char *argv[])
}
thread_should_exit = false;
- position_estimator_mc_task = task_spawn("position_estimator_mc",
+ position_estimator_mc_task = task_spawn_cmd("position_estimator_mc",
SCHED_RR,
SCHED_PRIORITY_MAX - 5,
4096,
diff --git a/src/modules/px4iofirmware/adc.c b/src/modules/px4iofirmware/adc.c
index f744698be..81566eb2a 100644
--- a/src/modules/px4iofirmware/adc.c
+++ b/src/modules/px4iofirmware/adc.c
@@ -41,7 +41,7 @@
#include <nuttx/arch.h>
#include <arch/stm32/chip.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <drivers/drv_hrt.h>
#include <systemlib/perf_counter.h>
diff --git a/src/modules/sdlog/sdlog.c b/src/modules/sdlog/sdlog.c
index 84a9eb6ac..c22523bf2 100644
--- a/src/modules/sdlog/sdlog.c
+++ b/src/modules/sdlog/sdlog.c
@@ -161,7 +161,7 @@ bool logging_enabled = true;
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to task_spawn().
+ * to task_spawn_cmd().
*/
int sdlog_main(int argc, char *argv[])
{
@@ -177,7 +177,7 @@ int sdlog_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("sdlog",
+ deamon_task = task_spawn_cmd("sdlog",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT - 30,
4096,
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index b5821098f..3a06cef65 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -235,7 +235,7 @@ int sdlog2_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("sdlog2",
+ deamon_task = task_spawn_cmd("sdlog2",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT - 30,
2048,
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 6b6aeedee..8bf5fdbd0 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -1445,7 +1445,7 @@ Sensors::start()
ASSERT(_sensors_task == -1);
/* start the task */
- _sensors_task = task_spawn("sensors_task",
+ _sensors_task = task_spawn_cmd("sensors_task",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2048,
diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c
index 20b711fa6..8fdff8ac0 100644
--- a/src/modules/systemlib/cpuload.c
+++ b/src/modules/systemlib/cpuload.c
@@ -1,9 +1,8 @@
/****************************************************************************
- * configs/px4fmu/src/up_leds.c
- * arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -15,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
+ * 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -34,18 +33,26 @@
*
****************************************************************************/
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
+/**
+ * @file cpuload.c
+ *
+ * Measurement of CPU load of each individual task.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
+ */
#include <nuttx/config.h>
+#include <nuttx/sched.h>
+#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
+
+#include <arch/arch.h>
+
#include <debug.h>
#include <sys/time.h>
-#include <sched.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
@@ -54,26 +61,13 @@
#ifdef CONFIG_SCHED_INSTRUMENTATION
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-__EXPORT void sched_note_start(FAR _TCB *tcb);
-__EXPORT void sched_note_stop(FAR _TCB *tcb);
-__EXPORT void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb);
-
-/****************************************************************************
- * Name:
- ****************************************************************************/
+__EXPORT void sched_note_start(FAR struct tcb_s *tcb);
+__EXPORT void sched_note_stop(FAR struct tcb_s *tcb);
+__EXPORT void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pToTcb);
__EXPORT struct system_load_s system_load;
-extern FAR _TCB *sched_gettcb(pid_t pid);
+extern FAR struct _TCB *sched_gettcb(pid_t pid);
void cpuload_initialize_once()
{
@@ -109,7 +103,7 @@ void cpuload_initialize_once()
// }
}
-void sched_note_start(FAR _TCB *tcb)
+void sched_note_start(FAR struct tcb_s *tcb)
{
/* search first free slot */
int i;
@@ -128,7 +122,7 @@ void sched_note_start(FAR _TCB *tcb)
}
}
-void sched_note_stop(FAR _TCB *tcb)
+void sched_note_stop(FAR struct tcb_s *tcb)
{
int i;
@@ -145,7 +139,7 @@ void sched_note_stop(FAR _TCB *tcb)
}
}
-void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb)
+void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pToTcb)
{
uint64_t new_time = hrt_absolute_time();
diff --git a/src/modules/systemlib/cpuload.h b/src/modules/systemlib/cpuload.h
index a97047ea8..c7aa18d3c 100644
--- a/src/modules/systemlib/cpuload.h
+++ b/src/modules/systemlib/cpuload.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013 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
@@ -43,7 +43,7 @@ struct system_load_taskinfo_s {
uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
uint64_t curr_start_time; ///< Start time of the current scheduling slot
uint64_t start_time; ///< FIRST start time of task
- FAR struct _TCB *tcb; ///<
+ FAR struct tcb_s *tcb; ///<
bool valid; ///< Task is currently active / valid
};
@@ -60,4 +60,6 @@ __EXPORT extern struct system_load_s system_load;
__EXPORT void cpuload_initialize_once(void);
+__END_DECLS
+
#endif
diff --git a/src/modules/systemlib/err.c b/src/modules/systemlib/err.c
index daf17ef8b..6c0e876d1 100644
--- a/src/modules/systemlib/err.c
+++ b/src/modules/systemlib/err.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013 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
@@ -61,7 +61,7 @@ const char *
getprogname(void)
{
#if CONFIG_TASK_NAME_SIZE > 0
- _TCB *thisproc = sched_self();
+ FAR struct tcb_s *thisproc = sched_self();
return thisproc->name;
#else
diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c
index afb7eca29..3283aad8a 100644
--- a/src/modules/systemlib/systemlib.c
+++ b/src/modules/systemlib/systemlib.c
@@ -50,7 +50,7 @@
#include "systemlib.h"
-static void kill_task(FAR _TCB *tcb, FAR void *arg);
+static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
void killall()
{
@@ -60,12 +60,12 @@ void killall()
sched_foreach(kill_task, NULL);
}
-static void kill_task(FAR _TCB *tcb, FAR void *arg)
+static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
{
kill(tcb->pid, SIGUSR1);
}
-int task_spawn(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[])
+int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[])
{
int pid;
diff --git a/src/modules/systemlib/systemlib.h b/src/modules/systemlib/systemlib.h
index 2c53c648b..0194b5e52 100644
--- a/src/modules/systemlib/systemlib.h
+++ b/src/modules/systemlib/systemlib.h
@@ -42,11 +42,11 @@
#include <float.h>
#include <stdint.h>
-__BEGIN_DECLS
-
/** Reboots the board */
extern void up_systemreset(void) noreturn_function;
+__BEGIN_DECLS
+
/** Sends SIGUSR1 to all processes */
__EXPORT void killall(void);
@@ -58,7 +58,7 @@ __EXPORT void killall(void);
#endif
/** Starts a task and performs any specific accounting, scheduler setup, etc. */
-__EXPORT int task_spawn(const char *name,
+__EXPORT int task_spawn_cmd(const char *name,
int priority,
int scheduler,
int stack_size,