modem_comms.cpp
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 #include <labust/tritech/MTDevice.hpp>
00039 #include <labust/tritech/TCPDevice.hpp>
00040 #include <labust/tritech/mtMessages.hpp>
00041 #include <labust/tritech/mmcMessages.hpp>
00042 
00043 #include <boost/archive/binary_oarchive.hpp>
00044 #include <boost/archive/binary_iarchive.hpp>
00045 
00046 #include <sstream>
00047 
00048 
00049 labust::tritech::MTMsgPtr setReplyBits(int i)
00050 {
00051         using namespace labust::tritech;
00052         MTMsgPtr msg(new MTMsg());
00053 
00054         msg->txNode = 255;
00055         msg->rxNode = 86;
00056         msg->msgType = MTMsg::mtMiniModemCmd;
00057         msg->node=86;
00058 
00059         MMCMsg mmsg;
00060         mmsg.msgType = labust::tritech::mmcSetRepBits;
00061         mmsg.data[0] = i;
00062         mmsg.data[1] = 51;
00063         mmsg.data[2] = 52;
00064         mmsg.data[3] = 51;
00065         mmsg.data[4] = 57;
00066         mmsg.data[5] = 55;
00067         mmsg.data[6] = 53;
00068 
00069         std::ostream out();
00070         boost::archive::binary_oarchive ar(*msg->data, boost::archive::no_header);
00071         ar<<mmsg;
00072 
00073         return msg;
00074 }
00075 
00076 labust::tritech::TCONMsgPtr sendUSBL(int i)
00077 {
00078         using namespace labust::tritech;
00079         TCONMsgPtr tmsg(new TCONMsg());
00080         tmsg->txNode = 255;
00081         tmsg->rxNode = 90;
00082         tmsg->node = 90;
00083         tmsg->msgType = MTMsg::mtMiniModemCmd;
00084         
00085         MMCMsg mmsg;
00086         
00087         switch (i)
00088         {
00089          case 24: mmsg.msgType = labust::tritech::mmcGetRangeTxRxBits24; break;
00090          case 32: mmsg.msgType = labust::tritech::mmcGetRangeTxRxBits32; break;
00091          case 40: mmsg.msgType = labust::tritech::mmcGetRangeTxRxBits40; break;
00092          case 48: mmsg.msgType = labust::tritech::mmcGetRangeTxRxBits48; break;
00093      default:break;
00094         }
00095 
00096         mmsg.data[0] = i;
00097         mmsg.data[1] = 50;
00098         mmsg.data[2] = 49;
00099         mmsg.data[3] = 48;
00100         mmsg.data[4] = 55;
00101         mmsg.data[5] = 56;
00102         mmsg.data[6] = 57;
00103 
00104         std::ostream out();
00105         boost::archive::binary_oarchive ar(*tmsg->data, boost::archive::no_header);
00106         ar<<mmsg;
00107 
00108         return tmsg;
00109 }
00110 
00111 int main(int argc, char* argv[])
00112 try
00113 {
00114         using namespace labust::tritech;
00115         MTDevice device(argv[1],57600);
00116 
00117         /*MTMsgPtr msg(new MTMsg());
00118 
00119         msg->txNode = 255;
00120         msg->rxNode = 86;
00121         msg->msgType = MTMsg::mtMiniModemCmd;
00122         msg->node=86;
00123 
00124         std::ostream out(msg->data.get());
00125 
00126         char mmsg[]={labust::tritech::mmc,2,0,0,0,0,4,64};
00127         out.write(mmsg,sizeof(mmsg));
00128         std::stringstream str2("");
00129         msg->setup();
00130         boost::archive::binary_oarchive ar3(str2, boost::archive::no_header);
00131         ar3<<*msg<<mmsg;
00132 
00133         for(int i=0; i<str2.str().size(); ++i)
00134         {
00135                 std::cout<<int(uint8_t(str2.str()[i]))<<",";
00136         }
00137 
00138         exit(0);
00139 
00140 
00141         //float TEST(a(2));
00142         
00143         TCONMsgPtr tmsg(new TCONMsg());
00144         tmsg->txNode = 255;
00145         tmsg->rxNode = 90;
00146         tmsg->node = 90;
00147         tmsg->msgType = MTMsg::mtMiniModemCmd;
00148         char mmsg2[]={mmcGetRangeTxRxByte,0,0,2,0,0,int8_t(226),64,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0};
00149         std::ostream tout(tmsg->data.get());
00150         tout.write(mmsg2,sizeof(mmsg2));
00151         */
00152         //TCPDevice tcpdevice("127.0.0.1",4000);
00153         device.send(setReplyBits(48));
00154 
00155         char c = 0;
00156         while (c != 'q')
00157         {
00158                 std::cin>>c;    
00159 
00160                 if (c=='s')
00161                 {
00162                         std::cin>>c;
00163 
00164                         if (c=='1') device.send(setReplyBits(24));
00165                         if (c=='2') device.send(setReplyBits(32));
00166                         if (c=='3') device.send(setReplyBits(40)); 
00167                         if (c=='4') device.send(setReplyBits(48));
00168                 }
00169                 if (c=='u') 
00170                 {
00171                         std::cin>>c;
00172 
00173                         //if (c=='1') tcpdevice.send(sendUSBL(24));
00174                         //if (c=='2') tcpdevice.send(sendUSBL(32));
00175                         //if (c=='3') tcpdevice.send(sendUSBL(40));
00176                         //if (c=='4') tcpdevice.send(sendUSBL(48));
00177                 }
00178         };
00179 
00180         //std::cin>>c;
00181 /*
00182         std::stringstream str("");
00183 
00184         labust::tritech::MTMsg msg2;
00185 
00186         msg2.size = 500;
00187         msg2.rxNode = 10;
00188         msg2.txNode = 20;
00189 
00190         boost::archive::binary_oarchive ar(str, boost::archive::no_header);
00191         ar<<msg2;
00192 
00193         for(int i=0; i<str.str().size(); ++i)
00194         {
00195                 std::cout<<int(uint8_t(str.str()[i]))<<",";
00196         }
00197         */
00198         return 0;
00199 }
00200 catch (std::exception& e)
00201 {
00202         std::cout<<"Closing gracefully due to following error: "<<e.what()<<std::endl;
00203 }
00204 
00205 
00206 


tritech_sdk
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:27