mtMessages.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 MTMESSAGES_HPP_
00039 #define MTMESSAGES_HPP_
00040 #include <labust/tritech/tritechfwd.hpp>
00041 #include <labust/preprocessor/mem_serialized_struct.hpp>
00042 
00043 #include <iostream>
00044 #include <sstream>
00045 #include <cstdint>
00046 
00047 namespace labust
00048 {
00049         namespace tritech
00050         {
00057                 struct HexHeader
00058                 {
00059                         enum {default_size=4};
00060 
00061                         static inline size_t length(uint8_t* data, std::size_t len = default_size)
00062                         {
00063                                 size_t retVal;
00064                                 std::stringstream in(std::string(reinterpret_cast<char*>(data),4));
00065                                 in>>std::hex>>retVal;
00066                                 return retVal;
00067                         }
00068                 };
00069 
00070                 struct MTMsg
00071                 {
00072                         enum {default_size=8};
00073                         enum {count_diff=5};
00074 
00075                         enum mtMessage
00076                         {
00078                                 mtNull = 0,
00080                                 mtHeadData = 2,
00082                                 mtAlive = 4,
00084                                 mtReboot = 16,
00086                                 mtHeadCmd = 19,
00088                                 mtSendData = 25,
00090                                 mtGPSData = 36,
00092                                 mtAMNavData = 52,
00094                                 mtAMNavRaw = 77,
00096                                 mtMiniModemCmd = 78,
00098                                 mtMiniModemData,
00100                                 mtMiniAttCmd,
00102                                 mtMiniAttData,
00104                                 mtAMNavDataV2 = 94
00105                         };
00106 
00107                         MTMsg():
00108                                 size(default_size),
00109                                 txNode(255),
00110                                 rxNode(255),
00111                                 byteCount(3),
00112                                 msgType(0),
00113                                 seq(128),
00114                                 node(255),
00115                                 data(new boost::asio::streambuf()){};
00116 
00120                         inline void setup()
00121                         {
00122                                 this->size = data->size()+ default_size;
00123                                 this->byteCount = this->size-count_diff;
00124                         }
00125 
00126                         uint16_t size;
00127                         uint8_t txNode, rxNode;
00128                         uint8_t byteCount;
00129                         uint8_t msgType;
00130                         uint8_t seq;
00131                         uint8_t node;
00132 
00133                         StreamPtr data;
00134                 };
00135         }
00136 }
00137 
00139 PP_LABUST_MAKE_BOOST_SERIALIZATOR_CLEAN(labust::tritech::MTMsg,
00140         (uint16_t, size)
00141         (uint8_t, txNode)
00142         (uint8_t, rxNode)
00143         (uint8_t, byteCount)
00144         (uint8_t, msgType)
00145         (uint8_t, seq)
00146         (uint8_t, node))
00147 
00148 /* MTMESSAGES_HPP_ */
00149 #endif


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