Go to the documentation of this file. 47 #define __EXPORT __attribute__ ((visibility ("default"))) 52 #define __PRIVATE __attribute__ ((visibility ("hidden"))) 55 # define __BEGIN_DECLS extern "C" { 56 # define __END_DECLS } 58 # define __BEGIN_DECLS 66 #define system_exit exit 68 #if defined(ENABLE_LOCKSTEP_SCHEDULER) 73 #define system_usleep usleep 74 #pragma GCC poison usleep 75 #define system_sleep sleep 76 #pragma GCC poison sleep 78 #define system_clock_gettime clock_gettime 79 #define system_clock_settime clock_settime 82 #define system_pthread_cond_timedwait pthread_cond_timedwait 89 #pragma GCC poison exit 102 #else // defined(ENABLE_LOCKSTEP_SCHEDULER) 104 #define system_usleep usleep 105 #define system_sleep sleep 106 #define system_clock_gettime clock_gettime 107 #define system_clock_settime clock_settime 108 #define system_pthread_cond_timedwait pthread_cond_timedwait 113 #if defined(__PX4_NUTTX) 122 #pragma GCC poison getenv setenv putenv 123 #endif // defined(__PX4_NUTTX)