fosi.h
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Wed Jan 18 14:11:39 CET 2006  fosi.h
00003 
00004                         fosi.h -  description
00005                            -------------------
00006     begin                : Wed January 18 2006
00007     copyright            : (C) 2006 Peter Soetens
00008     email                : peter.soetens@mech.kuleuven.be
00009 
00010  ***************************************************************************
00011  *   This library is free software; you can redistribute it and/or         *
00012  *   modify it under the terms of the GNU General Public                   *
00013  *   License as published by the Free Software Foundation;                 *
00014  *   version 2 of the License.                                             *
00015  *                                                                         *
00016  *   As a special exception, you may use this file as part of a free       *
00017  *   software library without restriction.  Specifically, if other files   *
00018  *   instantiate templates or use macros or inline functions from this     *
00019  *   file, or you compile this file and link it with other files to        *
00020  *   produce an executable, this file does not by itself cause the         *
00021  *   resulting executable to be covered by the GNU General Public          *
00022  *   License.  This exception does not however invalidate any other        *
00023  *   reasons why the executable file might be covered by the GNU General   *
00024  *   Public License.                                                       *
00025  *                                                                         *
00026  *   This library is distributed in the hope that it will be useful,       *
00027  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00028  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU     *
00029  *   Lesser General Public License for more details.                       *
00030  *                                                                         *
00031  *   You should have received a copy of the GNU General Public             *
00032  *   License along with this library; if not, write to the Free Software   *
00033  *   Foundation, Inc., 59 Temple Place,                                    *
00034  *   Suite 330, Boston, MA  02111-1307  USA                                *
00035  *                                                                         *
00036  ***************************************************************************/
00037 
00038 
00039 #ifndef _XENO_FOSI_H
00040 #define _XENO_FOSI_H
00041 
00042 #ifndef _XOPEN_SOURCE
00043 #define _XOPEN_SOURCE 600   // use all Posix features.
00044 #endif
00045 
00046 #define HAVE_FOSI_API
00047 
00048 #ifdef __cplusplus
00049 extern "C" {
00050 #endif
00051 
00052 #include "../../rtt-config.h"
00053 
00054         //Xenomai headers
00055         //#include <linux/types.h>
00056         // xenomai assumes presence of u_long
00057 #ifndef _GNU_SOURCE
00058 #define _GNU_SOURCE
00059 #endif
00060 #include <sys/mman.h>
00061 #include <sys/time.h>
00062 #include <unistd.h>
00063 #include <stdlib.h>
00064 #include <math.h>
00065 #include <stdio.h>
00066 #include <stdarg.h>
00067 #include <string.h>
00068 #include <signal.h>
00069 #include <getopt.h>
00070 #include <time.h>
00071 #include <limits.h>
00072 #include <float.h>
00073 #include "../oro_limits.h"
00074 
00075 #include <xeno_config.h> // version number
00076 #include <native/task.h>
00077 #include <native/timer.h>
00078 #include <native/mutex.h>
00079 #include <native/sem.h>
00080 #include <native/cond.h>
00081 
00082 // BC: support Xenomai < 2.3.0
00083 #if ((CONFIG_XENO_VERSION_MAJOR*1000)+(CONFIG_XENO_VERSION_MINOR*100)+CONFIG_XENO_REVISION_LEVEL) < 2300
00084 #define rt_mutex_acquire rt_mutex_lock
00085 #define rt_mutex_release rt_mutex_unlock
00086 #endif
00087 // BC: support Xenomai < 2.5.0
00088 #if ((CONFIG_XENO_VERSION_MAJOR*1000)+(CONFIG_XENO_VERSION_MINOR*100)+CONFIG_XENO_REVISION_LEVEL) >= 2500
00089 #define ORO_XENO_HAS_ACQUIRE_UNTIL
00090 #endif
00091 
00092 
00093         typedef RT_MUTEX rt_mutex_t;
00094         typedef RT_MUTEX rt_rec_mutex_t;
00095         typedef RT_SEM rt_sem_t;
00096         typedef RT_COND rt_cond_t;
00097 
00098         // Time Related
00099         // 'S' -> Signed long long
00100         typedef SRTIME          NANO_TIME;
00101         typedef SRTIME          TICK_TIME;
00102         typedef struct timespec TIME_SPEC;
00103         typedef RT_TASK         RTOS_XENO_TASK;
00104 
00105     // Thread/Task related.
00106     typedef struct {
00107         char * name;
00108         RTOS_XENO_TASK xenotask;
00109         RTOS_XENO_TASK* xenoptr;
00110         int sched_type;
00111     } RTOS_TASK;
00112 
00113     static const TICK_TIME InfiniteTicks = LONG_LONG_MAX;
00114     static const NANO_TIME InfiniteNSecs = LONG_LONG_MAX;
00115     static const double    InfiniteSeconds = DBL_MAX;
00116 
00117 #define SCHED_XENOMAI_HARD 0 
00118 #define SCHED_XENOMAI_SOFT 1 
00119 #define ORO_SCHED_RT    0 
00120 #define ORO_SCHED_OTHER 1 
00122 #define ORO_WAIT_ABS 0 
00123 #define ORO_WAIT_REL 1 
00125         // hrt is in ticks
00126 static inline TIME_SPEC ticks2timespec(TICK_TIME hrt)
00127 {
00128         TIME_SPEC timevl;
00129         timevl.tv_sec = rt_timer_tsc2ns(hrt) / 1000000000LL;
00130         timevl.tv_nsec = rt_timer_tsc2ns(hrt) % 1000000000LL;
00131         return timevl;
00132 }
00133 
00134         // hrt is in ticks
00135 static inline TICK_TIME timespec2ticks(const TIME_SPEC* ts)
00136 {
00137         return  rt_timer_ns2tsc(ts->tv_nsec + ts->tv_sec*1000000000LL);
00138 }
00139 
00140 // turn this on to have maximum detection of valid system calls.
00141 #ifdef OROSEM_OS_XENO_CHECK
00142 #define CHK_XENO_CALL() do { if(rt_task_self() == 0) { \
00143         printf("RTT: XENO NOT INITIALISED IN THIS THREAD pid=%d,\n\
00144     BUT TRIES TO INVOKE XENO FUNCTION >>%s<< ANYWAY\n", getpid(), __FUNCTION__ );\
00145         assert( rt_task_self() != 0 ); }\
00146         } while(0)
00147 #define CHK_XENO_PTR(ptr) do { if(ptr == 0) { \
00148         printf("RTT: TRIED TO PASS NULL POINTER TO XENO IN THREAD pid=%d,\n\
00149     IN TRYING TO INVOKE XENO FUNCTION >>%s<<\n", getpid(), __FUNCTION__ );\
00150         assert( ptr != 0 ); }\
00151         } while(0)
00152 #else
00153 #define CHK_XENO_CALL()
00154 #define CHK_XENO_PTR( a )
00155 #endif
00156 
00157 static inline NANO_TIME rtos_get_time_ns(void) { return rt_timer_ticks2ns(rt_timer_read()); }
00158 
00159 static inline TICK_TIME rtos_get_time_ticks(void) { return rt_timer_tsc(); }
00160 
00161 static inline TICK_TIME ticksPerSec(void) { return rt_timer_ns2tsc( 1000 * 1000 * 1000 ); }
00162 
00163 // WARNING: Orocos 'ticks' are 'Xenomai tsc' and Xenomai `ticks' are not
00164 // used in the Orocos API. Thus Orocos uses `Xenomai tsc' and `Xenomai ns',
00165 // yet Xenomai requires `Xenomai ticks' at the interface
00166 // ==> do not use nano2ticks to convert to `Xenomai ticks' because it
00167 // converts to `Xenomai tsc'.
00168 static inline TICK_TIME nano2ticks(NANO_TIME t) { return rt_timer_ns2tsc(t); }
00169 static inline NANO_TIME ticks2nano(TICK_TIME t) { return rt_timer_tsc2ns(t); }
00170 
00171 static inline int rtos_nanosleep(const TIME_SPEC *rqtp, TIME_SPEC *rmtp)
00172         {
00173                 CHK_XENO_CALL();
00174                 RTIME ticks = rqtp->tv_sec * 1000000000LL + rqtp->tv_nsec;
00175                 rt_task_sleep( rt_timer_ns2ticks(ticks) );
00176                 return 0;
00177         }
00178 
00179     static inline int rtos_sem_init(rt_sem_t* m, int value )
00180     {
00181         CHK_XENO_CALL();
00182                 return rt_sem_create( m, 0, value, S_PRIO);
00183     }
00184 
00185     static inline int rtos_sem_destroy(rt_sem_t* m )
00186     {
00187         CHK_XENO_CALL();
00188         return rt_sem_delete( m );
00189     }
00190 
00191     static inline int rtos_sem_signal(rt_sem_t* m )
00192     {
00193         CHK_XENO_CALL();
00194         return rt_sem_v( m );
00195     }
00196 
00197     static inline int rtos_sem_wait(rt_sem_t* m )
00198     {
00199         CHK_XENO_CALL();
00200         return rt_sem_p( m, TM_INFINITE );
00201     }
00202 
00203     static inline int rtos_sem_trywait(rt_sem_t* m )
00204     {
00205         CHK_XENO_CALL();
00206         return rt_sem_p( m, TM_NONBLOCK);
00207     }
00208 
00209     static inline int rtos_sem_value(rt_sem_t* m )
00210     {
00211         CHK_XENO_CALL();
00212         RT_SEM_INFO sinfo;
00213         if (rt_sem_inquire(m, &sinfo) == 0 ) {
00214           return sinfo.count;
00215         }
00216         return -1;
00217     }
00218 
00219     static inline int rtos_sem_wait_timed(rt_sem_t* m, NANO_TIME delay )
00220     {
00221         CHK_XENO_CALL();
00222         return rt_sem_p(m, rt_timer_ns2ticks(delay) ) == 0 ? 0 : -1;
00223     }
00224 
00225     static inline int rtos_sem_wait_until(rt_sem_t* m, NANO_TIME when )
00226     {
00227         CHK_XENO_CALL();
00228         return rt_sem_p(m, rt_timer_ns2ticks(when) - rt_timer_read() ) == 0 ? 0 : -1;
00229     }
00230 
00231     static inline int rtos_mutex_init(rt_mutex_t* m)
00232     {
00233         CHK_XENO_CALL();
00234                 // a Xenomai mutex is always recursive
00235         return rt_mutex_create(m, 0);
00236     }
00237 
00238     static inline int rtos_mutex_destroy(rt_mutex_t* m )
00239     {
00240         CHK_XENO_CALL();
00241         return rt_mutex_delete(m);
00242     }
00243 
00244     static inline int rtos_mutex_rec_init(rt_mutex_t* m)
00245     {
00246         CHK_XENO_CALL();
00247                 // a Xenomai mutex is always recursive
00248         return rt_mutex_create(m, 0);
00249     }
00250 
00251     static inline int rtos_mutex_rec_destroy(rt_mutex_t* m )
00252     {
00253         CHK_XENO_CALL();
00254         return rt_mutex_delete(m);
00255     }
00256 
00257     static inline int rtos_mutex_lock( rt_mutex_t* m)
00258     {
00259         CHK_XENO_CALL();
00260         return rt_mutex_acquire(m, TM_INFINITE );
00261     }
00262 
00263     static inline int rtos_mutex_trylock( rt_mutex_t* m)
00264     {
00265         CHK_XENO_CALL();
00266         struct rt_mutex_info info;
00267         rt_mutex_inquire(m, &info );
00268 #if ((CONFIG_XENO_VERSION_MAJOR*1000)+(CONFIG_XENO_VERSION_MINOR*100)+CONFIG_XENO_REVISION_LEVEL) >= 2500
00269         if (info.locked)
00270             return 0;
00271 #else
00272         if (info.lockcnt)
00273             return 0;
00274 #endif
00275         // from here on: we're sure our thread didn't lock it
00276         // now check if any other thread locked it:
00277         return rt_mutex_acquire(m, TM_NONBLOCK);
00278     }
00279 
00280     static inline int rtos_mutex_lock_until( rt_mutex_t* m, NANO_TIME abs_time)
00281     {
00282         CHK_XENO_CALL();
00283 #if !defined(ORO_XENO_HAS_ACQUIRE_UNTIL) // see top of this file
00284         // calling the old style API
00285         return rt_mutex_acquire(m, rt_timer_ns2ticks(abs_time) - rt_timer_read()  );
00286 #else
00287         // new style API > 2.5.0
00288         return rt_mutex_acquire_until(m, rt_timer_ns2ticks(abs_time) );
00289 #endif
00290     }
00291 
00292     static inline int rtos_mutex_unlock( rt_mutex_t* m)
00293     {
00294         CHK_XENO_CALL();
00295         return rt_mutex_release(m);
00296     }
00297 
00298     static inline int rtos_mutex_rec_lock( rt_rec_mutex_t* m)
00299     {
00300         CHK_XENO_CALL();
00301         return rt_mutex_acquire(m, TM_INFINITE );
00302     }
00303 
00304     static inline int rtos_mutex_rec_trylock( rt_rec_mutex_t* m)
00305     {
00306         CHK_XENO_CALL();
00307         return rtos_mutex_trylock(m);
00308     }
00309 
00310     static inline int rtos_mutex_rec_lock_until( rt_rec_mutex_t* m, NANO_TIME abs_time)
00311     {
00312         CHK_XENO_CALL();
00313         return rtos_mutex_lock_until(m, abs_time);
00314     }
00315 
00316     static inline int rtos_mutex_rec_unlock( rt_rec_mutex_t* m)
00317     {
00318         CHK_XENO_CALL();
00319         return rt_mutex_release(m);
00320     }
00321 
00322     static inline void rtos_enable_rt_warning()
00323     {
00324         CHK_XENO_CALL();
00325         rt_task_set_mode(0, T_WARNSW, NULL);
00326     }
00327 
00328     static inline void rtos_disable_rt_warning()
00329     {
00330         CHK_XENO_CALL();
00331         rt_task_set_mode(T_WARNSW, 0, NULL);
00332     }
00333 
00334     static inline int rtos_cond_init(rt_cond_t *cond)
00335     {
00336         CHK_XENO_CALL();
00337         return rt_cond_create(cond, 0);
00338     }
00339 
00340     static inline int rtos_cond_destroy(rt_cond_t *cond)
00341     {
00342         CHK_XENO_CALL();
00343         return rt_cond_delete(cond);
00344     }
00345 
00346     static inline int rtos_cond_wait(rt_cond_t *cond, rt_mutex_t *mutex)
00347     {
00348         CHK_XENO_CALL();
00349         int ret = rt_cond_wait(cond, mutex, TM_INFINITE);
00350         if (ret == 0)
00351             return 0;
00352         return -1;
00353     }
00354 
00355     static inline int rtos_cond_timedwait(rt_cond_t *cond, rt_mutex_t *mutex, NANO_TIME abs_time)
00356     {
00357         CHK_XENO_CALL();
00358         // BC: support Xenomai < 2.5.0
00359 #if ((CONFIG_XENO_VERSION_MAJOR*1000)+(CONFIG_XENO_VERSION_MINOR*100)+CONFIG_XENO_REVISION_LEVEL) < 2500
00360         return rt_cond_wait(cond, mutex, rt_timer_ns2ticks(abs_time) - rt_timer_read() );
00361 #else
00362         return rt_cond_wait_until(cond, mutex, rt_timer_ns2ticks(abs_time) );
00363 #endif
00364     }
00365 
00366     static inline int rtos_cond_broadcast(rt_cond_t *cond)
00367     {
00368         CHK_XENO_CALL();
00369         return rt_cond_broadcast(cond);
00370     }
00371 
00372 
00373 #define rtos_printf printf
00374 
00375 #ifdef __cplusplus
00376 }
00377 #endif
00378 
00379 #endif


rtt
Author(s): RTT Developers
autogenerated on Sat Jun 8 2019 18:46:11