queue_core.h
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------
00002  *---------------------           RT-WMP              --------------------
00003  *------------------------------------------------------------------------
00004  *                                                         V7.0B  11/05/10
00005  *
00006  *
00007  *  File: ./src/plugins/long_messages/long_messages.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 LONG_MESSAGES_H_
00038 #define LONG_MESSAGES_H_
00039 //#include "compiler.h"
00040 
00041 //#define USE_LONG_MESSAGE_COMPRESS
00042 
00043 #define WMP_LM_DEBUG(output,...)
00044 //fprintf(output,__VA_ARGS__)//printk(KERN_ERR __VA_ARGS__)
00045 
00046 typedef struct {
00047         unsigned char src;
00048         unsigned int dest;
00049         signed char priority;
00050         unsigned int size;
00051         unsigned int port;
00052         long long ts;
00053         unsigned int type;
00054         int done;
00055         int msg_part_size;
00056         unsigned short hash;
00057         unsigned short burst_hash;
00058         short num_parts, part_id;
00059         unsigned short received_parts;
00060         char * received_part;
00061         unsigned short max_message_parts;
00062         int allocated_size;
00063         int rescheduled;
00064         int this_part_size;
00065         int parts_pointer;
00066         char * pointer;
00067         char * data;
00068 } longMsg_t;
00069 
00070 typedef struct {
00071         longMsg_t ** longMsg;
00072         //longMsg_t lastPopped;
00073         char * received_part;
00074         int force_burst;
00075         int max_msg_size, hash_idx;
00076         int max_msg_num;
00077         int message_part_size;
00078         int num_ports;
00079         int drop_next;
00080         int last_popped_id;
00081         MUTEX mtx, **mtxs, uniq_mtx;
00082         SEM_T ** sems, sem;
00083         int elem;
00084 } queue_t;
00085 
00086 void clear(queue_t * q, int idx);
00087 void exclusive_on(queue_t * q);
00088 void exclusive_off(queue_t * q);
00089 int queue_get_size(queue_t * q);
00090 int queue_get_elem_age(queue_t * q, int id);
00091 int queue_get_elem_dest(queue_t * q, int id);
00092 int queue_get_elem_priority(queue_t * q, int id);
00093 int queue_get_elem_size(queue_t * q, int id);
00094 int queue_get_elem_source(queue_t * q, int id);
00095 char * queue_get_elem_data(queue_t * q, int id);
00096 int queue_get_elem_burst(queue_t * q, int id);
00097 unsigned int queue_get_elem_port(queue_t * q, int id);
00098 int queue_get_elem_rescheduled(queue_t * q, int id);
00099 
00100 /* RX Queue */
00101 int queue_push_part(queue_t * q,  longMsg_t * m);
00102 int queue_rx_get_mpm_size(queue_t * q, int port);
00103 int queue_rx_pop_data(queue_t * q, unsigned int delay, unsigned int port, char ** data, unsigned int * size, unsigned char * src, signed char * priority) ;
00104 void queue_rx_pop_data_done(queue_t * q, int maxPriId);
00105 void queue_rx_init(queue_t * q, int max_msg_size, int max_msg_num, int num_ports);
00106 int queue_rx_get_count(queue_t * q, int port);
00107 void queue_rx_free(queue_t * q);
00108 int queue_rx_wait_data(queue_t * q, int port, int delay);
00109 int queue_rx_push_loop_data(queue_t * q, unsigned int port, char * p, unsigned int size, unsigned int dest, signed char priority, unsigned char src);
00110 int queue_rx_get_room(queue_t * q);
00111 
00112 
00113 /* TX Queue */
00114 int queue_tx_remove_head(queue_t * q);
00115 void queue_tx_init(queue_t * q, int max_msg_size, int max_msg_num, int msg_part_size);
00116 int queue_tx_push_data(queue_t * q, unsigned int port, char * p, unsigned int size, unsigned int dest, signed char priority) ;
00117 int queue_tx_pop_part(queue_t * q, longMsg_t ** p);
00118 void queue_tx_pop_part_done(queue_t * q, int maxPriId);
00119 int queue_tx_get_count(queue_t * q);
00120 int queue_tx_inspect_head(queue_t * q, longMsg_t ** p);
00121 int queue_tx_get_head_dest(queue_t * q);
00122 int queue_tx_get_head_age(queue_t * q);
00123 void queue_tx_free(queue_t * q);
00124 int queue_tx_get_head_id(queue_t * q);
00125 int queue_tx_reschedule(queue_t * q);
00126 int queue_tx_confirm(queue_t * q);
00127 void queue_tx_drop_elem(queue_t * q, int id);
00128 void queue_tx_get_last_popped_info(queue_t * q, int * age, int *port, int * priority);
00129 void queue_tx_drop_next(queue_t * q);
00130 void queue_tx_force_burst(queue_t * q, int port);
00131 
00132 #endif /* LONG_MESSAGES_H_ */


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