USBLMessages.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 USBLMESSAGES_HPP_
00039 #define USBLMESSAGES_HPP_
00040 #include <labust/tritech/mmcMessages.hpp>
00041 #include <labust/preprocessor/mem_serialized_struct.hpp>
00042 #include <boost/array.hpp>
00043 #include <cstdint>      
00044 
00045 namespace labust
00046 {
00047         namespace tritech
00048         {
00049                 typedef boost::array<float,5> vec5f;
00050                 typedef boost::array<float,4> vec4f;
00051                 typedef boost::array<float,3> vec3f;
00052                 typedef boost::array<double,3> vec3d;
00053                 typedef boost::array<int16_t,3> vec3int16;
00054         }
00055 }
00056 BOOST_CLASS_IMPLEMENTATION(labust::tritech::vec3f , boost::serialization::primitive_type)
00057 BOOST_CLASS_IMPLEMENTATION(labust::tritech::vec3d , boost::serialization::primitive_type)
00058 BOOST_CLASS_IMPLEMENTATION(labust::tritech::vec4f , boost::serialization::primitive_type)
00059 BOOST_CLASS_IMPLEMENTATION(labust::tritech::vec5f , boost::serialization::primitive_type)
00060 BOOST_CLASS_IMPLEMENTATION(labust::tritech::vec3int16 , boost::serialization::primitive_type)
00061 
00063 PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN((labust)(tritech),USBLData,
00064                         (size_t, time_ms)
00065                         (uint8_t,reply_validity)
00066                         (vec3f, doa)
00067                         (float, RMS)
00068                         (float, usblAngleQuality)
00069                         (float, usblRangeQuality)
00070                         (vec4f, reliability)
00071                         (vec3d, attitude)                       
00072                         (bool, isTransponder)
00073                         (uint16_t, unitID)
00074                         (vec3d, relativePos)
00075                         (vec5f, sigma)
00076                         (float, fixVOS)
00077                         (double, range)
00078                         (vec3d, attitudeCorrectedPos)
00079                         (vec3d, worldPos)
00080                         (double, time))
00081 
00082 PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN((labust)(tritech),AttSenData,
00083                  (uint8_t, cmd)
00084                  (uint32_t, time)
00085              (vec3int16, acc)
00086                  (vec3int16, mag)
00087                  (vec3int16, gyro)
00088                  (int16_t, pressure)
00089                  (int16_t, externalTemp)
00090                  (int16_t, internalTemp))
00091 
00092 PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN((labust)(tritech),USBLDataV2,
00093         (labust::tritech::USBLData, nav)
00094         (labust::tritech::MMCMsg, modem))
00095 
00096 /* USBLMESSAGES_HPP_ */
00097 #endif


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