forked from Archive/PX4-Autopilot
POSIX: use px4_getpid()
The posix build only has one process so calling getpid() will not provide the expected result. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
cb231e89f6
commit
7bb70313da
|
@ -273,6 +273,21 @@ void px4_show_tasks()
|
||||||
}
|
}
|
||||||
|
|
||||||
__BEGIN_DECLS
|
__BEGIN_DECLS
|
||||||
|
|
||||||
|
int px4_getpid()
|
||||||
|
{
|
||||||
|
pthread_t pid = pthread_self();
|
||||||
|
|
||||||
|
// Get pthread ID from the opaque ID
|
||||||
|
for (int i=0; i<PX4_MAX_TASKS; ++i) {
|
||||||
|
if (taskmap[i].pid == pid) {
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
PX4_ERR("px4_getpid() called from non-thread context!");
|
||||||
|
return -EINVAL;
|
||||||
|
}
|
||||||
|
|
||||||
const char *getprogname();
|
const char *getprogname();
|
||||||
const char *getprogname()
|
const char *getprogname()
|
||||||
{
|
{
|
||||||
|
|
|
@ -99,12 +99,7 @@ __EXPORT int px4_ioctl(int fd, int cmd, unsigned long arg);
|
||||||
__EXPORT int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout);
|
__EXPORT int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout);
|
||||||
__EXPORT int px4_fsync(int fd);
|
__EXPORT int px4_fsync(int fd);
|
||||||
__EXPORT int px4_access(const char *pathname, int mode);
|
__EXPORT int px4_access(const char *pathname, int mode);
|
||||||
#ifdef __PX4_QURT
|
|
||||||
typedef int pid_t;
|
|
||||||
__EXPORT int px4_getpid(void);
|
__EXPORT int px4_getpid(void);
|
||||||
#else
|
|
||||||
#define px4_getpid getpid
|
|
||||||
#endif
|
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -245,20 +245,6 @@ int px4_task_kill(px4_task_t id, int sig)
|
||||||
return rv;
|
return rv;
|
||||||
}
|
}
|
||||||
|
|
||||||
pid_t px4_getpid()
|
|
||||||
{
|
|
||||||
pthread_t pid = pthread_self();
|
|
||||||
|
|
||||||
// Get pthread ID from the opaque ID
|
|
||||||
for (int i=0; i<PX4_MAX_TASKS; ++i) {
|
|
||||||
if (taskmap[i].pid == pid) {
|
|
||||||
return i;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
PX4_ERR("px4_getpid() called from non-thread context!");
|
|
||||||
return -EINVAL;
|
|
||||||
}
|
|
||||||
|
|
||||||
void px4_show_tasks()
|
void px4_show_tasks()
|
||||||
{
|
{
|
||||||
int idx;
|
int idx;
|
||||||
|
@ -276,3 +262,22 @@ void px4_show_tasks()
|
||||||
PX4_INFO(" No running tasks");
|
PX4_INFO(" No running tasks");
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
|
int px4_getpid()
|
||||||
|
{
|
||||||
|
pthread_t pid = pthread_self();
|
||||||
|
|
||||||
|
// Get pthread ID from the opaque ID
|
||||||
|
for (int i=0; i<PX4_MAX_TASKS; ++i) {
|
||||||
|
if (taskmap[i].pid == pid) {
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
PX4_ERR("px4_getpid() called from non-thread context!");
|
||||||
|
return -EINVAL;
|
||||||
|
}
|
||||||
|
|
||||||
|
__END_DECLS
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue