Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
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
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
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
00174
00175
00176
00177 }
00178 };
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
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