Firmware
px4_posix.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2015 Mark Charlebois. 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 
40 #pragma once
41 
42 #include <px4_defines.h>
43 #include <px4_tasks.h>
44 #include <stdint.h>
45 #include <unistd.h>
46 #include <fcntl.h>
47 #include <poll.h>
48 #include <stdint.h>
49 
50 #if defined(__PX4_QURT)
51 #include <dspal_types.h>
52 #else
53 #include <sys/types.h>
54 #endif
55 
56 #include "px4_sem.h"
57 
58 #define PX4_F_RDONLY 1
59 #define PX4_F_WRONLY 2
60 
61 #ifdef __PX4_NUTTX
62 
63 typedef struct pollfd px4_pollfd_struct_t;
64 
65 #if defined(__cplusplus)
66 #define _GLOBAL ::
67 #else
68 #define _GLOBAL
69 #endif
70 #define px4_open _GLOBAL open
71 #define px4_close _GLOBAL close
72 #define px4_ioctl _GLOBAL ioctl
73 #define px4_write _GLOBAL write
74 #define px4_read _GLOBAL read
75 #define px4_poll _GLOBAL poll
76 #define px4_fsync _GLOBAL fsync
77 #define px4_access _GLOBAL access
78 #define px4_getpid _GLOBAL getpid
79 
80 #define PX4_STACK_OVERHEAD 0
81 
82 #elif defined(__PX4_POSIX)
83 
84 #define PX4_STACK_OVERHEAD 8192
85 
86 __BEGIN_DECLS
87 
88 typedef short pollevent_t;
89 
90 typedef struct {
91  /* This part of the struct is POSIX-like */
92  int fd; /* The descriptor being polled */
93  pollevent_t events; /* The input event flags */
94  pollevent_t revents; /* The output event flags */
95 
96  /* Required for PX4 compatibility */
97  px4_sem_t *sem; /* Pointer to semaphore used to post output event */
98  void *priv; /* For use by drivers */
99 } px4_pollfd_struct_t;
100 
101 __EXPORT int px4_open(const char *path, int flags, ...);
102 __EXPORT int px4_close(int fd);
103 __EXPORT ssize_t px4_read(int fd, void *buffer, size_t buflen);
104 __EXPORT ssize_t px4_write(int fd, const void *buffer, size_t buflen);
105 __EXPORT int px4_ioctl(int fd, int cmd, unsigned long arg);
106 __EXPORT int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout);
107 __EXPORT int px4_fsync(int fd);
108 __EXPORT int px4_access(const char *pathname, int mode);
109 __EXPORT px4_task_t px4_getpid(void);
110 
111 __END_DECLS
112 #else
113 #error "No TARGET OS Provided"
114 #endif
115 
116 
117 // The stack size is intended for 32-bit architectures; therefore
118 // we often run out of stack space when pointers are larger than 4 bytes.
119 // Double the stack size on posix when we're on a 64-bit architecture.
120 // Most full-scale OS use 1-4K of memory from the stack themselves
121 #define PX4_STACK_ADJUSTED(_s) (_s * (__SIZEOF_POINTER__ >> 2) + PX4_STACK_OVERHEAD)
122 
123 __BEGIN_DECLS
124 extern int px4_errno;
125 
126 __EXPORT void px4_show_devices(void);
127 __EXPORT void px4_show_files(void);
128 __EXPORT const char *px4_get_device_names(unsigned int *handle);
129 
130 __EXPORT void px4_show_topics(void);
131 __EXPORT const char *px4_get_topic_names(unsigned int *handle);
132 
133 #ifndef __PX4_QURT
134 /*
135  * The UNIX epoch system time following the system clock
136  */
137 __EXPORT uint64_t hrt_system_time(void);
138 
139 
140 #endif
141 
142 __END_DECLS
Synchronization primitive: Semaphore.
Generally used magic defines.
Definition: I2C.hpp:51
Definition: rc_loss_alarm.cpp:50
Definition: video_device.h:50