wmp_interface.h
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------
00002  *---------------------           RT-WMP              --------------------
00003  *------------------------------------------------------------------------
00004  *                                                         V7.0B  11/05/10
00005  *
00006  *
00007  *  File: ./src/core/interface/wmp_interface.h
00008  *  Authors: Danilo Tardioli
00009  *  ----------------------------------------------------------------------
00010  *  Copyright (C) 2000-2010, Universidad de Zaragoza, SPAIN
00011  *
00012  *  Contact Addresses: Danilo Tardioli                   dantard@unizar.es
00013  *
00014  *  RT-WMP is free software; you can  redistribute it and/or  modify it
00015  *  under the terms of the GNU General Public License  as published by the
00016  *  Free Software Foundation;  either  version 2, or (at  your option) any
00017  *  later version.
00018  *
00019  *  RT-WMP  is distributed  in the  hope  that  it will be   useful, but
00020  *  WITHOUT  ANY  WARRANTY;     without  even the   implied   warranty  of
00021  *  MERCHANTABILITY  or  FITNESS FOR A  PARTICULAR PURPOSE.    See the GNU
00022  *  General Public License for more details.
00023  *
00024  *  You should have received  a  copy of  the  GNU General Public  License
00025  *  distributed with RT-WMP;  see file COPYING.   If not,  write to the
00026  *  Free Software  Foundation,  59 Temple Place  -  Suite 330,  Boston, MA
00027  *  02111-1307, USA.
00028  *
00029  *  As a  special exception, if you  link this  unit  with other  files to
00030  *  produce an   executable,   this unit  does  not  by  itself cause  the
00031  *  resulting executable to be covered by the  GNU General Public License.
00032  *  This exception does  not however invalidate  any other reasons why the
00033  *  executable file might be covered by the GNU Public License.
00034  *
00035  *----------------------------------------------------------------------*/
00036 
00037 #ifndef WMPINTERFACE__H
00038 #define WMPINTERFACE__H
00039 
00040 #include <stdarg.h>
00041 #include "wmp_config.h"
00042 #include "Msg.h"
00043 
00044 
00045 
00046 /* Queues*/
00051 int          wmpPush(Msg *p);
00052 
00057 unsigned int wmpPop(Msg * p); 
00058 
00066 int          wmpTimedPop(Msg * p, int timeout_ms);
00067 
00074 int          wmpNonBlockingPop(Msg * p);
00075 
00076 #ifdef USE_MESSAGE_COMPRESSION
00077 
00078 int wmpZPush(Msg * m);
00079 
00080 #endif
00081 
00084 char wmpGetNodeId(void);
00085 
00089 char wmpGetNumOfNodes(void);
00090 
00107 int  wmpGetLatestLQM(char * lqm);
00108 
00113 int  wmpIsNetworkConnected(void);
00114 
00120 int  wmpIsNetworkConnectedBlocking(int timeout_ms);
00121 
00125 int  wmp_queue_tx_remove_head(void);
00126 
00131 void wmpSetCpuDelay(int val);
00132 
00137 int wmpGetCpuDelay(void);
00138 
00142 void wmpSetTimeout(int val);
00143 
00147 int wmpGetTimeout(void);
00148 
00153 void wmpSetWCMult(int val);
00154 
00159 int wmpGetWCMult(void);
00160 
00164 void wmpSetRate(int val);
00165 
00169 int wmpGetRate(void);
00170 
00171 /* USER */
00172 
00173 
00177 int wmp_queue_tx_get_room(void);
00178 
00182 int wmpGetNumOfElementsInTXQueue(void);
00183 
00187 int wmpGetNumOfElementsInRXQueue(int port);
00188 
00195 int  wmpSetup(char node_id, char active_nodes);
00196 int wmpSetupList(int _node_id, int _num_nodes, int nparam, ...);
00197 
00199 void wmpRun(void);
00200 
00202 void wmpRunBG(void);
00203 
00205 void wmpExit(void);
00206 
00208 void wmpInmediateExit(void);
00209 
00211 void wmpSetQuiet(void);
00212 
00213 #ifndef __KERNEL__
00214 
00215 void wmpEnableIntControl(void);
00216 #endif
00217 
00221 int wmpGetNetIT(void);
00222 
00226 unsigned int wmpGetMTU(void);
00227 
00228 
00232 void wmpSetActiveSearch(int val);
00233 
00238 int wmpGetActiveSearch(void);
00239 
00240 void wmpSetInstanceId(short iid);
00241 void wmpSetPrimBasedRouting(int val);
00242 
00243 void wmpSetMessageReschedule(int val);
00244 
00245 void wmpSetFlowControl(int val);
00246 
00247 short wmpGetInstanceId(void);
00248 int wmpGetPrimBasedRouting(void);
00249 
00250 int wmpGetMessageReschedule(void);
00251 
00252 int wmpGetFlowControl(void);
00253 
00254 unsigned int wmpGetSerial(void);
00255 unsigned int wmpGetLoopId(void);
00256 
00257 int wmpPushData           (unsigned int port, char  * p, unsigned int   size, unsigned int   dest, signed char priority);
00258 int wmpPopData            (unsigned int port, char ** p, unsigned int * size, unsigned char * src, signed char * priority);
00259 int wmpPopDataTimeout     (unsigned int port, char ** p, unsigned int * size, unsigned char * src, signed char * priority, int to);
00260 int wmpPopDataCopy        (unsigned int port, char  * p, unsigned int * size, unsigned char * src, signed char * priority);
00261 int wmpPopDataTimeoutCopy (unsigned int port, char  * p, unsigned int * size, unsigned char * src, signed char * priority, int to);
00262 void wmpPopDataDone       (int id);
00263 int wmpWaitData(unsigned int port, int to);
00264 void wmpForceTopology(char * name, int parameter);
00265 void wmpSetRxError(char * name, int rate);
00266 int wmpSetTaskMinimumSeparation(int port, int period);
00267 int  wmpIsKernelSpace(void);
00268 void wmpForceBurst(int port);
00269 int  wmpGetLatestDistances(char * dist);
00270 
00271 char lqm_get_val(int i, int j);
00272 #endif
00273 


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