Firmware
px4_tasks.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
43 #pragma once
44 
45 #include <stdbool.h>
46 
47 #if defined(__PX4_NUTTX)
48 typedef int px4_task_t;
49 
50 #include <sys/prctl.h>
51 #define px4_prctl prctl
52 
54 #if CONFIG_RR_INTERVAL > 0
55 # define SCHED_DEFAULT SCHED_RR
56 #else
57 # define SCHED_DEFAULT SCHED_FIFO
58 #endif
59 
60 #define px4_task_exit(x) _exit(x)
61 
62 #elif defined(__PX4_POSIX) || defined(__PX4_QURT)
63 
64 #include <pthread.h>
65 #include <sched.h>
66 
68 #define SCHED_DEFAULT SCHED_FIFO
69 
70 #if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
71 
72 #define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)
73 #define SCHED_PRIORITY_MIN sched_get_priority_min(SCHED_FIFO)
74 #define SCHED_PRIORITY_DEFAULT (((sched_get_priority_max(SCHED_FIFO) - sched_get_priority_min(SCHED_FIFO)) / 2) + sched_get_priority_min(SCHED_FIFO))
75 
76 #elif defined(__PX4_QURT)
77 
78 #define SCHED_PRIORITY_MAX 255
79 #define SCHED_PRIORITY_MIN 0
80 #define SCHED_PRIORITY_DEFAULT 20
81 
82 #else
83 #error "No target OS defined"
84 #endif
85 
86 #if defined (__PX4_LINUX)
87 #include <sys/prctl.h>
88 #else
89 #define PR_SET_NAME 1
90 #endif
91 
92 typedef int px4_task_t;
93 
94 typedef struct {
95  int argc;
96  char **argv;
97 } px4_task_args_t;
98 
99 #else
100 #error "No target OS defined"
101 #endif
102 
103 // Fast drivers - they need to run as quickly as possible to minimize control
104 // latency.
105 #define SCHED_PRIORITY_FAST_DRIVER (SCHED_PRIORITY_MAX - 0)
106 
107 // Attitude controllers typically are in a blocking wait on driver data
108 // they should be the first to run on an update, using the current sensor
109 // data and the *previous* attitude reference from the position controller
110 // which typically runs at a slower rate
111 #define SCHED_PRIORITY_ATTITUDE_CONTROL (SCHED_PRIORITY_MAX - 4)
112 
113 // Actuator outputs should run as soon as the rate controller publishes
114 // the actuator controls topic
115 #define SCHED_PRIORITY_ACTUATOR_OUTPUTS (SCHED_PRIORITY_MAX - 3)
116 
117 // Position controllers typically are in a blocking wait on estimator data
118 // so when new sensor data is available they will run last. Keeping them
119 // on a high priority ensures that they are the first process to be run
120 // when the estimator updates.
121 #define SCHED_PRIORITY_POSITION_CONTROL (SCHED_PRIORITY_MAX - 5)
122 
123 // Estimators should run after the attitude controller but before anything
124 // else in the system. They wait on sensor data which is either coming
125 // from the sensor hub or from a driver. Keeping this class at a higher
126 // priority ensures that the estimator runs first if it can, but will
127 // wait for the sensor hub if its data is coming from it.
128 #define SCHED_PRIORITY_ESTIMATOR (SCHED_PRIORITY_MAX - 5)
129 
130 // The sensor hub conditions sensor data. It is not the fastest component
131 // in the controller chain, but provides easy-to-use data to the more
132 // complex downstream consumers
133 #define SCHED_PRIORITY_SENSOR_HUB (SCHED_PRIORITY_MAX - 6)
134 
135 // The log capture (which stores log data into RAM) should run faster
136 // than other components, but should not run before the control pipeline
137 #define SCHED_PRIORITY_LOG_CAPTURE (SCHED_PRIORITY_MAX - 10)
138 
139 // Slow drivers should run at a rate where they do not impact the overall
140 // system execution
141 #define SCHED_PRIORITY_SLOW_DRIVER (SCHED_PRIORITY_MAX - 35)
142 
143 // The navigation system needs to execute regularly but has no realtime needs
144 #define SCHED_PRIORITY_NAVIGATION (SCHED_PRIORITY_DEFAULT + 5)
145 // SCHED_PRIORITY_DEFAULT
146 #define SCHED_PRIORITY_LOG_WRITER (SCHED_PRIORITY_DEFAULT - 10)
147 #define SCHED_PRIORITY_PARAMS (SCHED_PRIORITY_DEFAULT - 15)
148 // SCHED_PRIORITY_IDLE
149 
150 typedef int (*px4_main_t)(int argc, char *argv[]);
151 
152 __BEGIN_DECLS
153 
156 __EXPORT void px4_systemreset(bool to_bootloader) noreturn_function;
157 
159 __EXPORT px4_task_t px4_task_spawn_cmd(const char *name,
160  int scheduler,
161  int priority,
162  int stack_size,
163  px4_main_t entry,
164  char *const argv[]);
165 
167 __EXPORT int px4_task_delete(px4_task_t pid);
168 
170 __EXPORT int px4_task_kill(px4_task_t pid, int sig);
171 
173 __EXPORT void px4_task_exit(int ret);
174 
176 __EXPORT void px4_show_tasks(void);
177 
179 __EXPORT bool px4_task_is_running(const char *taskname);
180 
181 #ifdef __PX4_POSIX
182 
183 __EXPORT int px4_prctl(int option, const char *arg2, px4_task_t pid);
184 #endif
185 
187 __EXPORT const char *px4_get_taskname(void);
188 
189 __END_DECLS
190 
__EXPORT void px4_show_tasks(void)
Show a list of running tasks.
Definition: px4_posix_tasks.cpp:362
__EXPORT int px4_task_delete(px4_task_t pid)
Deletes a task - does not do resource cleanup.
Definition: px4_posix_tasks.cpp:283
__BEGIN_DECLS __EXPORT void px4_systemreset(bool to_bootloader) noreturn_function
Reboots the board (without waiting for clean shutdown).
Definition: px4_nuttx_tasks.c:58
__EXPORT const char * px4_get_taskname(void)
return the name of the current task
Definition: px4_nuttx_tasks.c:106
__EXPORT void px4_task_exit(int ret)
Exit current task with return value.
Definition: px4_posix_tasks.cpp:315
Definition: I2C.hpp:51
__EXPORT px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry, char *const argv[])
Starts a task and performs any specific accounting, scheduler setup, etc.
Definition: px4_posix_tasks.cpp:121
__EXPORT bool px4_task_is_running(const char *taskname)
See if a task is running.
Definition: px4_posix_tasks.cpp:382
__EXPORT int px4_task_kill(px4_task_t pid, int sig)
Send a signal to a task.
Definition: px4_posix_tasks.cpp:341