definitions.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/include/definitions.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 
00038 
00039 #ifndef DEFINITIONS__H
00040 #define DEFINITIONS__H
00041 
00042 #include "core/interface/Msg.h"
00043 
00044 #define CANT_ARRIVE 0
00045 #define FORCE_WC_LOOP 34
00046 
00047 /*FUNCTION RETURN CODE*/
00048 #define RECEIVE_OK  44
00049 #define ERROR           -99             /*generic error*/
00050 #define EXPIRED         -2
00051 #define UNDEF           ((signed char) -1)
00052 
00053 /*STATES*/
00054 #define EVALUATE                                        10
00055 #define EVALUATE_TOKEN                          12
00056 #define EVALUATE_AUTHORIZATION          13
00057 #define EVALUATE_MESSAGE                        14
00058 #define EVALUATE_DROP_TOKEN                     15
00059 #define EVALUATE_FOREIGN                        16
00060 
00061 #define TO_EXPIRED                                      20
00062 #define TO_DISCOVER_EXPIRED                     21
00063 #define TO_TOKEN_EXPIRED                        22
00064 #define TO_AUTHORIZATION_EXPIRED        23
00065 #define TO_MESSAGE_EXPIRED                      24
00066 
00067 #define NEW_TOKEN                                       32
00068 #define WAIT_ACK                                        33
00069 #define RETRY                                           35
00070 #define RECEIVE                                         36
00071 #define DUPLICATE_TOKEN                         37
00072 #define INTERPRET_RECEIVED                      39
00073 
00074 #define INTERPRET_ACK                                   40
00075 #define ENQUEUE_MESSAGE                                 41
00076 #define CREATE_AUTHORIZATION                    45
00077 #define CREATE_MESSAGE                                  46
00078 #define SEND_DROP_ON_ACK                                47
00079 #define SEND_DROP_ON_RECEIVE                    48
00080 #define DECODE_ROUTING_INFO_ON_RECEIVE  49
00081 #define DECODE_ROUTING_INFO_ON_WACK             50
00082 
00083 #define SEND_TOKEN                                              51
00084 #define SEND_MESSAGE                                    52
00085 #define SEND_AUTHORIZATION                              53
00086 
00087 #define UPDATE_RSSI_ON_RECEIVE                  54
00088 #define UPDATE_RSSI_ON_ACK                              55
00089 #define VIGILANT_SLEEP                                  56
00090 
00091 #define NET_INACTIVITY                                  65
00092 #define ABORT                                                   66
00093 #define ALL_STATES                                              127
00094 
00095 /* RT-WMP Extensions */
00096 #define NO_EXTESION                                     0
00097 #define NERUS                                           1
00098 #define PLUS                                            2
00099 
00100 
00101 
00102 /* PROGRAM STATUS*/
00103 typedef struct  {
00104 /* Node ID and working Parameters*/
00105         int id;
00106         char N_NODES;
00107         long timeout;
00108         int hold_time;
00109         int rx_queue_elements;
00110         int tx_queue_elements;
00111 /* Working Buffers*/
00112         char bufferA[MTU];
00113         char bufferB[MTU];
00114 /*Local Information*/
00115         unsigned long highestSerial;
00116         int lastSentType;
00117         int lastRecvdType;
00118         int lastRecvdFrom;
00119         signed char lastAckd;
00120         int retries;
00121 
00122         int maxPerNodeRetries;
00123         int maxTotalRetries;
00124         int waitRemaining;
00125         signed char acknow;
00126         char reincorporation_request;
00127 /*Configuration Parameters*/
00128         int TIMEOUT;
00129         int perHopDelay;
00130         int max_rssi;
00131         signed char lr;
00132         signed char emergency_lr;
00133         int cpu_delay;
00134         int quiet;
00135         int mobile_average_elements;
00136         unsigned int net_inactivity_timeout;
00137         int rx_type;
00138         int rssi_rising_factor;
00139         int rate;
00140         int reason;
00141         char status[32];
00142         int multiplier; /* Worst Case Multiplier */
00143         int wait_ack_from;
00144 
00145         unsigned short wait_ack_of_hash;
00146         short wait_ack_of_part;
00147         signed char wait_implicit_ack_from;
00148         char send_ack_to;
00149         int enable_flow_control;
00150         int enable_message_reschedule;
00151         unsigned int loop_id;
00152         unsigned int serial;
00153         unsigned char net_id;
00154         int use_ett;
00155         int use_prim;
00156         int use_prob;
00157         int use_prune;
00158         int MAXIMUM_DATA_SIZE;
00159         double x,y;
00160         int pow;
00161         int active_search;
00162         short instance_id;
00163         int w100;
00164         int w3;
00165         int w2;
00166         int w1;
00167         int power_save;
00168         int burst;
00169         int secure;
00170         int max_msg_size;
00171         int num_ports;
00172 
00173 }Status;
00174 
00175 
00176 //#define SV int states_vector=[][]{
00177 
00178 
00179 #endif
00180 


ros_rt_wmp
Author(s): Danilo Tardioli, dantard@unizar.es
autogenerated on Fri Jan 3 2014 12:07:54