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 #include <vector>
00033 #include <algorithm>
00034
00035
00036 #include "simple_message.h"
00037 #include "shared_types.h"
00038 #include "message_manager.h"
00039 #include "socket/tcp_server.h"
00040
00041 #include <gtest/gtest.h>
00042 #include <stdlib.h>
00043 #include <ctype.h>
00044
00045 int g_argc;
00046 char** g_argv;
00047 const unsigned int g_num_vals = 4;
00048
00049 TEST(MessageManagerSuite, tcp)
00050 {
00051
00052 ASSERT_GE(g_argc, 3);
00053 int port = atoi(g_argv[1]);
00054 std::vector<int> values;
00055 for(int i=2; i<g_argc; i++)
00056 {
00057 if(g_argv[i] && isdigit(g_argv[i][0]))
00058 values.push_back(atoi(g_argv[i]));
00059 }
00060 ASSERT_EQ(values.size(), g_num_vals);
00061
00062
00063 std::reverse(values.begin(), values.end());
00064
00065 industrial::tcp_server::TcpServer tcpServer;
00066 industrial::message_manager::MessageManager tcpManager;
00067
00068
00069 ASSERT_TRUE(tcpServer.init(port));
00070
00071
00072 ASSERT_TRUE(tcpServer.makeConnect());
00073 ASSERT_TRUE(tcpManager.init(&tcpServer));
00074
00075 industrial::simple_message::SimpleMessage msg;
00076 ASSERT_TRUE(tcpServer.receiveMsg(msg));
00077 ASSERT_EQ(msg.getMessageType(), industrial::simple_message::StandardMsgTypes::IO);
00078 ASSERT_EQ(msg.getCommType(), industrial::simple_message::CommTypes::TOPIC);
00079 ASSERT_EQ(msg.getReplyCode(), industrial::simple_message::ReplyTypes::INVALID);
00080 ASSERT_EQ(msg.getDataLength(), (int)(g_num_vals*4));
00081 industrial::byte_array::ByteArray buf = msg.getData();
00082 for(unsigned int i=0; i<g_num_vals; i++)
00083 {
00084 int val;
00085 buf.unload(val);
00086 ASSERT_EQ(val, values[i]);
00087 }
00088 }
00089
00090 int
00091 main(int argc, char** argv)
00092 {
00093 g_argc = argc;
00094 g_argv = argv;
00095
00096 testing::InitGoogleTest(&argc, argv);
00097 return RUN_ALL_TESTS();
00098 }