mmcMessages.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 /*********************************************************************
00035  * Author: Đula Nađ
00036  *   Date: 11.12.2012.
00037  *********************************************************************/
00038 #ifndef MMCMESSAGES_HPP_
00039 #define MMCMESSAGES_HPP_
00040 #include <labust/preprocessor/mem_serialized_struct.hpp>
00041 #include <boost/array.hpp>
00042 
00043 namespace labust
00044 {
00045         namespace tritech
00046         {
00050                 enum mmcMessage
00051                 {
00053                         mmcGetRangeSync = 1,
00055                         mmcRangeData,
00057                         mmcListenRangeSync = 21,
00059                         mmcGetRangeTxRxByte = 24,
00061                         mmcLsnRangeRxByte,
00063                         mmcRangeRxByte,
00065                         mmcSetRangeRepByte,
00067                         mmcRangedRepByte,
00069                         mmcRangedRcvByte,
00072                         mmcGetRangeTxRxBits24,
00074                         mmcLsnRangeRxBits,
00076                         mmcRangeRxBits,
00078                         mmcSetRepBits,
00080                         mmcRepBits24,
00082                         mmcRangedRcvBits,
00084                         mmcGetRangeTxRxBits32,
00086                         mmcRepBits32,
00088                         mmcGetRangeTxRxBits40,
00090                         mmcRepBits40,
00092                         mmcGetRangeTxRxBits48,
00094                         mmcRepBits48,
00095                         //mmcStatusMsg - ID:42 Sent on Error Detected or Fixed V4 < M1, [M3] Ranger,[Lsnr]
00096                         mmcStatusMsg,
00097                 };
00098 
00099                 typedef boost::array<uint8_t,16> vec16u;
00100                 struct MMCMsg
00101                 {
00102                         enum {ranged_payload_size=4,
00103                                 ranged_payload=5,
00104                                 payload_size=0,
00105                                 payload=1};
00106 
00107                         MMCMsg():
00108                          msgType(24),
00109                          tx(0),
00110                          rx(2),
00111                          rxTmo(60000){};
00112 
00113                         uint8_t msgType;
00114                         uint16_t tx,rx,rxTmo;
00115                         //For modem replay messages with the first 4 bytes of payload are usually the range.
00116                         vec16u data;
00117                 };
00118         }
00119 }
00120 
00121 BOOST_CLASS_IMPLEMENTATION(labust::tritech::vec16u , boost::serialization::primitive_type)
00123 PP_LABUST_MAKE_BOOST_SERIALIZATOR_CLEAN(labust::tritech::MMCMsg,
00124                 (uint8_t, msgType)
00125         (uint16_t, tx)
00126                 (uint16_t, rx)
00127                 (uint16_t, rxTmo)
00128                 (vec16u, data))
00129 
00130 /* MMCMESSAGES_HPP_ */
00131 #endif


tritech_sdk
Author(s): Gyula Nagy
autogenerated on Thu Jul 10 2014 10:34:19