message_preprocess.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  Author: Dula Nad
00035  *  Created: 29.04.2013.
00036  *********************************************************************/
00037 #ifndef MESSAGE_PREPROCESS_HPP_
00038 #define MESSAGE_PREPROCESS_HPP_
00039 #include <boost/integer/integer_mask.hpp>
00040 #include <boost/preprocessor/seq/for_each.hpp>
00041 #include <boost/preprocessor/tuple/rem.hpp>
00042 
00043 #define PP_MSG_FILLER_0(X1,X2,X3,       X4,X5) \
00044         ((X1,X2,X3,     X4,X5)) PP_MSG_FILLER_1
00045 #define PP_MSG_FILLER_1(X1,X2,X3,       X4,X5) \
00046         ((X1,X2,X3,     X4,X5)) PP_MSG_FILLER_0
00047 #define PP_MSG_FILLER_0_END
00048 #define PP_MSG_FILLER_1_END
00049 
00050 #define DEFINE_TOPSIDE_MESSAGES(seq)\
00051                 BOOST_PP_SEQ_FOR_EACH_R(1, ADD_CADDY_MESSAGE2, \
00052                 3, BOOST_PP_CAT(PP_MSG_FILLER_0 seq, _END))\
00053                 void registerTopsideMessages() \
00054     { \
00055                         static bool inited(false); \
00056                         if (!inited) \
00057                         { \
00058                                 inited = true; \
00059                                 BOOST_PP_SEQ_FOR_EACH_R(1, ADD_TO_MAP, \
00060                                                 topsideMap, BOOST_PP_CAT(PP_MSG_FILLER_0 seq, _END))\
00061                         } \
00062     };
00063 
00064 #define DEFINE_DIVER_MESSAGES(seq)\
00065                 BOOST_PP_SEQ_FOR_EACH_R(1, ADD_CADDY_MESSAGE2, \
00066                 3, BOOST_PP_CAT(PP_MSG_FILLER_0 seq, _END))\
00067                 void registerDiverMessages() \
00068     { \
00069                         static bool inited(false); \
00070                         if (!inited) \
00071                         { \
00072                                 inited = true; \
00073                                 BOOST_PP_SEQ_FOR_EACH_R(1, ADD_TO_MAP, \
00074                                                 diverMap, BOOST_PP_CAT(PP_MSG_FILLER_0 seq, _END))\
00075                         } \
00076     };
00077 
00078 #define ADD_TO_MAP(r, data, elem) \
00079         data[BOOST_PP_TUPLE_ELEM(5,1,elem)] = boost::shared_ptr<BOOST_PP_TUPLE_ELEM(5,0,elem)>(new (BOOST_PP_TUPLE_ELEM(5,0,elem)));
00080 
00081 #define ADD_CADDY_MESSAGE2(r, data, elem) \
00082         ADD_CADDY_MESSAGE(BOOST_PP_TUPLE_ELEM(5,0,elem), \
00083                         BOOST_PP_TUPLE_ELEM(5,1,elem), \
00084                         BOOST_PP_TUPLE_ELEM(5,2,elem), \
00085                         BOOST_PP_TUPLE_ELEM(5,3,elem), \
00086                         BOOST_PP_TUPLE_ELEM(5,4,elem))
00087 
00088 #define ADD_CADDY_MESSAGE(NAME, CODE, DEPTHSIZE, \
00089                 LATLONSIZE, MSGSIZE) \
00090                 struct NAME : public virtual labust::tritech::Packer\
00091                 {\
00092                         enum{type=CODE};\
00093                         enum{depthSize=DEPTHSIZE,latlonSize=LATLONSIZE,msgSize=MSGSIZE};\
00094                         uint64_t pack(DiverMsg& msg) \
00095                         { \
00096                                 return msg.pack<NAME>(); \
00097                         } \
00098                         void unpack(uint64_t data, DiverMsg& msg) \
00099                         { \
00100                                 msg.unpack<NAME>(data); \
00101                         } \
00102      };\
00103 
00104 /* MESSAGE_PREPROCESS_HPP_ */
00105 #endif
00106 
00107 
00108 


usbl
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:29