compiler.h
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------
00002  *---------------------           RT-WMP              --------------------
00003  *------------------------------------------------------------------------
00004  *                                                         
00005  *
00006  *
00007  *  File: ./src/platforms/linux_ks/config/compiler.h
00008  *  Authors: Rubén Durán
00009  *           Danilo Tardioli
00010  *  ----------------------------------------------------------------------
00011  *  Copyright (C) 2000-2011, Universidad de Zaragoza, SPAIN
00012  *
00013  *  Contact Addresses: Danilo Tardioli                   dantard@unizar.es
00014  *
00015  *  RT-WMP is free software; you can  redistribute it and/or  modify it
00016  *  under the terms of the GNU General Public License  as published by the
00017  *  Free Software Foundation;  either  version 2, or (at  your option) any
00018  *  later version.
00019  *
00020  *  RT-WMP  is distributed  in the  hope  that  it will be   useful, but
00021  *  WITHOUT  ANY  WARRANTY;     without  even the   implied   warranty  of
00022  *  MERCHANTABILITY  or  FITNESS FOR A  PARTICULAR PURPOSE.    See the GNU
00023  *  General Public License for more details.
00024  *
00025  *  You should have received  a  copy of  the  GNU General Public  License
00026  *  distributed with RT-WMP;  see file COPYING.   If not,  write to the
00027  *  Free Software  Foundation,  59 Temple Place  -  Suite 330,  Boston, MA
00028  *  02111-1307, USA.
00029  *
00030  *  As a  special exception, if you  link this  unit  with other  files to
00031  *  produce an   executable,   this unit  does  not  by  itself cause  the
00032  *  resulting executable to be covered by the  GNU General Public License.
00033  *  This exception does  not however invalidate  any other reasons why the
00034  *  executable file might be covered by the GNU Public License.
00035  *
00036  *----------------------------------------------------------------------*/
00037 
00038 #ifndef CONFIGURATION_H_
00039 #define CONFIGURATION_H_
00040 
00041 #include <linux/module.h>
00042 #include <linux/kernel.h>
00043 #include <linux/string.h>
00044 #include <linux/version.h>
00045 #include <linux/sched.h>
00046 #include <linux/slab.h>
00047 #include <linux/semaphore.h>
00048 #include <linux/mutex.h>
00049 #include <linux/fs.h>
00050 #include "wmp_config.h"
00051 #include <linux/kthread.h>
00052 #include <asm/div64.h>
00053 #include <linux/time.h>
00054 #include <linux/random.h>
00055 #include <linux/slab.h>
00056 #define MALLOC(size) kmalloc(size, GFP_KERNEL)
00057 #define FREE(p) kfree(p)
00058 
00059 //#define PRINTK(str, ...) printk(KERN_ERR "[%s:%d]: " str, __FILE__, __LINE__, __VA_ARGS__)
00060 #define PRINTK(str, ...)
00061 
00062 #define SEM_T struct semaphore
00063 #define SEM_INIT(p,q,r) sema_init(p,r)
00064 #define WAIT(nMutex) ({int res; PRINTK("WT %s\n", #nMutex); res = down_interruptible(&nMutex);})
00065 #define WAIT_TIMED(nMutex, time) ({PRINTK("WT %s\n", #nMutex); down_timeout(&nMutex, msecs_to_jiffies(time)); })
00066 #define SIGNAL(nMutex) ({PRINTK("S %s\n", #nMutex); up(&nMutex); })
00067 #define SEM_GET_COUNT(nMutex) (nMutex).count
00068 
00069 typedef struct {
00070         spinlock_t spin;
00071         unsigned long flags;
00072 } MUTEX;
00073 #define MUTEX_INIT(m) spin_lock_init(&(m)->spin);
00074 #define MUTEX_WAIT(m) ({PRINTK("MW %s\n", #m); spin_lock_irqsave(&(m).spin,(m).flags); })
00075 #define MUTEX_WAIT_SPIN(m) ({PRINTK("MWS %s\n", #m); spin_lock_irqsave(&(m).spin,(m).flags); })
00076 #define MUTEX_SIGNAL(m) ({PRINTK("MS %s\n", #m); spin_unlock_irqrestore(&(m).spin,(m).flags); })
00077 
00078 
00079 /*#define MUTEX_WAIT(m) spin_lock_irqsave(&(m).spin,(m).flags)
00080  #define MUTEX_WAIT_SPIN(m) spin_lock_irqsave(&(m).spin,(m).flags)
00081  #define MUTEX_SIGNAL(m) spin_unlock_irqrestore(&(m).spin,(m).flags)*/
00082 
00083 #define THREAD_T(name) struct task_struct * name = NULL
00084 #define THREAD_CREATE(th_var,th_fun,name) th_var = kthread_run(th_fun,NULL,name)
00085 #define THREAD_STOP(th_var) kthread_stop(th_var)
00086 
00087 #define THREAD_SEM_T struct semaphore
00088 #define THREAD_SEM_INIT_LOCKED(p) sema_init(p,0)
00089 #define THREAD_SEM_WAIT(p) ({int res; PRINTK("TSW %s\n", #p); res = down_interruptible(p); })
00090 #define THREAD_SEM_WAIT_TIMED(p, time) ({ PRINTK("TSWT %s\n", #p); down_timeout(&p, msecs_to_jiffies(time)); })
00091 #define THREAD_SEM_SIGNAL(p) ({ PRINTK("TSS %s\n", #p); up(p); })
00092 
00093 
00094 
00095 
00096 #define ASSERT(test) if(!(test)) printk(KERN_INFO "ASSERT: \"%s\" failed.\n", #test)
00097 
00098 #define GETNSTIMEOFDAY(p) getnstimeofday(p)
00099 
00100 #define DO_DIV64(n , b)                \
00101    ({                                     \
00102       unsigned long long __n = n;         \
00103       do_div(__n,b);                      \
00104       __n;                                \
00105    })
00106 
00107 #define EXIT(val) return val
00108 
00109 #define rand()                                              \
00110    ({                                                          \
00111       int __a;                                                 \
00112       get_random_bytes(&__a, sizeof(__a));                     \
00113       __a;                                                     \
00114    })
00115 
00116 #define floor(n) ((int)(n))
00117 
00118 #define atoi(s)                                             \
00119    ({                                                          \
00120       char *next;                                              \
00121       (int) simple_strtol(s,&next,10);                         \
00122    })
00123 
00124 void atof(const char *cadena, double *res);
00125 
00126 #define ATOF(src, dst) atof(src, dst)
00127 
00128 char * fgets(char *s, int size, struct file *f);
00129 
00130 #define usleep(usecs)   \
00131                         {unsigned long timeout = ((usecs * (msecs_to_jiffies(1) + 1)) / (int)1000);\
00132                          while (timeout) {\
00133                           timeout = schedule_timeout_uninterruptible(timeout);\
00134                         }};
00135 
00136 #ifdef USE_MESSAGE_COMPRESSION
00137 #define EXPORT_MESSAGE_COMPRESSION() EXPORT_SYMBOL(wmpZPush)
00138 #else
00139 #define EXPORT_MESSAGE_COMPRESSION()
00140 #endif
00141 struct proc_dir_entry * get_proc_root(void);
00142 
00143 #define EXPORT_SYMBOLS()   EXPORT_SYMBOL(wmpPush);\
00144                               EXPORT_SYMBOL(wmpPop);\
00145                               EXPORT_SYMBOL(wmpTimedPop);\
00146                               EXPORT_SYMBOL(wmpNonBlockingPop);\
00147                               EXPORT_MESSAGE_COMPRESSION()\
00148                               EXPORT_SYMBOL(wmpGetNodeId);\
00149                               EXPORT_SYMBOL(wmpGetNumOfNodes);\
00150                               EXPORT_SYMBOL(wmpGetLatestLQM);\
00151                               EXPORT_SYMBOL(wmpIsNetworkConnected);\
00152                               EXPORT_SYMBOL(wmpIsNetworkConnectedBlocking);\
00153                               EXPORT_SYMBOL(wmp_queue_tx_remove_head);\
00154                               EXPORT_SYMBOL(wmpSetCpuDelay);\
00155                               EXPORT_SYMBOL(wmpSetTimeout);\
00156                               EXPORT_SYMBOL(wmpSetWCMult);\
00157                               EXPORT_SYMBOL(wmpSetRate);\
00158                               EXPORT_SYMBOL(wmpGetCpuDelay);\
00159                               EXPORT_SYMBOL(wmpGetTimeout);\
00160                               EXPORT_SYMBOL(wmpGetWCMult);\
00161                               EXPORT_SYMBOL(wmpGetRate);\
00162                               \
00163                               EXPORT_SYMBOL(wmp_queue_tx_get_room);\
00164                               EXPORT_SYMBOL(wmpGetNumOfElementsInTXQueue);\
00165                               EXPORT_SYMBOL(wmpGetNumOfElementsInRXQueue);\
00166                               EXPORT_SYMBOL(wmpSetup);\
00167                               EXPORT_SYMBOL(wmpSetupList);\
00168                               EXPORT_SYMBOL(wmpRun);\
00169                               EXPORT_SYMBOL(wmpRunBG);\
00170                               EXPORT_SYMBOL(wmpExit);\
00171                               EXPORT_SYMBOL(wmpInmediateExit);\
00172                               EXPORT_SYMBOL(wmpSetQuiet);\
00173                               EXPORT_SYMBOL(wmpGetNetIT);\
00174                               EXPORT_SYMBOL(wmpGetMTU);\
00175                               EXPORT_SYMBOL(wmpSetActiveSearch);\
00176                               EXPORT_SYMBOL(wmpGetActiveSearch);\
00177                               EXPORT_SYMBOL(wmpSetInstanceId);\
00178                               EXPORT_SYMBOL(wmpSetPrimBasedRouting);\
00179                               EXPORT_SYMBOL(wmpSetMessageReschedule);\
00180                               EXPORT_SYMBOL(wmpSetFlowControl);\
00181                               EXPORT_SYMBOL(wmpGetInstanceId);\
00182                               EXPORT_SYMBOL(wmpGetPrimBasedRouting);\
00183                               EXPORT_SYMBOL(wmpGetMessageReschedule);\
00184                               EXPORT_SYMBOL(wmpGetFlowControl);\
00185                               EXPORT_SYMBOL(wmpGetSerial);\
00186                               EXPORT_SYMBOL(wmpGetLoopId);\
00187                                                           EXPORT_SYMBOL(wmpPushData);\
00188                               EXPORT_SYMBOL(wmpPopData);\
00189                               EXPORT_SYMBOL(wmpPopDataTimeout);\
00190                               EXPORT_SYMBOL(wmpPopDataDone);\
00191                                                           EXPORT_SYMBOL(wmpPopDataTimeoutCopy);\
00192                                                           EXPORT_SYMBOL(wmpPopDataCopy);\
00193                                                           EXPORT_SYMBOL(wmp_queue_rx_get_elem_size);\
00194                                                           EXPORT_SYMBOL(wmp_queue_rx_get_elem_priority);\
00195                                                           EXPORT_SYMBOL(wmp_queue_rx_get_elem_source);\
00196                                                           EXPORT_SYMBOL(wmp_queue_rx_get_elem_data);\
00197                                                           EXPORT_SYMBOL(wmpWaitData);\
00198                                                       EXPORT_SYMBOL(wmp_queue_rx_set_elem_done);\
00199                                                       EXPORT_SYMBOL(wmpForceTopology);\
00200                                                       EXPORT_SYMBOL(wmpSetTaskMinimumSeparation);\
00201                                                       EXPORT_SYMBOL(lqm_get_distance);\
00202                                                       EXPORT_SYMBOL(get_proc_root);\
00203                                                       EXPORT_SYMBOL(wmpForceBurst);
00204 
00205 
00206 #if WMP_DEBUG_LEVEL > 0
00207 #define DEBUG(p)  p
00208 #define WMP_DEBUG(output, ...)   printk(KERN_DEBUG __VA_ARGS__)
00209 #define WMP_DEBUG1(output, ...)  printk(KERN_DEBUG __VA_ARGS__)
00210 #define WMP_DBG(level,...) if (level & (WMP_DEBUG_LEVEL)) printk(KERN_DEBUG __VA_ARGS__)
00211 #else
00212 #define DEBUG(p)
00213 #define WMP_DEBUG(output, ...)
00214 #define WMP_DEBUG1(output, ...)
00215 #define WMP_DBG(output,...)
00216 #endif
00217 //#define WMP_MSG(output, ...) fprintf(output, __VA_ARGS__)
00218 #define WMP_MSG(output, ...) printk(KERN_INFO __VA_ARGS__)
00219 //#define WMP_ERROR(output, ...) textcolor(1,1,0); fprintf(output, __VA_ARGS__) ; textcolor(0,7,0);
00220 #define WMP_ERROR(output, ...) printk(KERN_ERR __VA_ARGS__)
00221 #endif
00222 /*CONFIGURATION_H_*/


ros_rt_wmp
Author(s): Danilo Tardioli, dantard@unizar.es
autogenerated on Mon Oct 6 2014 08:27:09