utest.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, Southwest Research Institute
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 are met:
00009  *
00010  *      * Redistributions of source code must retain the above copyright
00011  *      notice, this list of conditions and the following disclaimer.
00012  *      * Redistributions in binary form must reproduce the above copyright
00013  *      notice, this list of conditions and the following disclaimer in the
00014  *      documentation and/or other materials provided with the distribution.
00015  *      * Neither the name of the Southwest Research Institute, nor the names
00016  *      of its contributors may be used to endorse or promote products derived
00017  *      from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #include "simple_message/simple_message.h"
00033 #include "simple_message/byte_array.h"
00034 #include "simple_message/shared_types.h"
00035 #include "simple_message/smpl_msg_connection.h"
00036 #include "simple_message/socket/udp_client.h"
00037 #include "simple_message/socket/udp_server.h"
00038 #include "simple_message/socket/tcp_client.h"
00039 #include "simple_message/socket/tcp_server.h"
00040 #include "simple_message/ping_message.h"
00041 #include "simple_message/ping_handler.h"
00042 #include "simple_message/messages/joint_message.h"
00043 #include "simple_message/joint_data.h"
00044 #include "simple_message/message_manager.h"
00045 #include "simple_message/simple_comms_fault_handler.h"
00046 #include "simple_message/joint_traj_pt.h"
00047 #include "simple_message/messages/joint_traj_pt_message.h"
00048 #include "simple_message/typed_message.h"
00049 #include "simple_message/joint_traj.h"
00050 
00051 #include <gtest/gtest.h>
00052 // Use pthread instead of boost::thread so we can cancel the TCP/UDP server
00053 // threads 
00054 //#include <boost/thread/thread.hpp>
00055 #include <pthread.h>
00056 
00057 using namespace industrial::simple_message;
00058 using namespace industrial::byte_array;
00059 using namespace industrial::shared_types;
00060 using namespace industrial::smpl_msg_connection;
00061 using namespace industrial::udp_socket;
00062 using namespace industrial::udp_client;
00063 using namespace industrial::udp_server;
00064 using namespace industrial::tcp_socket;
00065 using namespace industrial::tcp_client;
00066 using namespace industrial::tcp_server;
00067 using namespace industrial::ping_message;
00068 using namespace industrial::ping_handler;
00069 using namespace industrial::joint_data;
00070 using namespace industrial::joint_message;
00071 using namespace industrial::message_manager;
00072 using namespace industrial::simple_comms_fault_handler;
00073 using namespace industrial::joint_traj_pt;
00074 using namespace industrial::joint_traj_pt_message;
00075 using namespace industrial::typed_message;
00076 using namespace industrial::joint_traj;
00077 
00078 // Multiple tests require TEST_PORT_BASE to be defined.  This is defined
00079 // by the make file at compile time.
00080 //#define TEST_PORT_BASE 11000
00081 
00082 TEST(ByteArraySuite, init)
00083 {
00084 
00085   const shared_int SIZE = 100;
00086 
00087   ByteArray bytes;
00088   shared_int TOO_BIG = bytes.getMaxBufferSize()+1;
00089 
00090   char bigBuffer[TOO_BIG];
00091   char buffer[SIZE];
00092 
00093   // Valid byte arrays
00094   EXPECT_TRUE(bytes.init(&buffer[0], SIZE));
00095   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00096 
00097   // Invalid init (too big)
00098   // Invalid buffers
00099   EXPECT_FALSE(bytes.init(&bigBuffer[0], TOO_BIG));
00100 }
00101 
00102 TEST(ByteArraySuite, loading)
00103 {
00104   const shared_int SIZE = 100;
00105   char buffer[SIZE];
00106 
00107   ByteArray bytes;
00108   ByteArray empty;
00109 
00110   ASSERT_TRUE(bytes.init(&buffer[0], SIZE));
00111 
00112   shared_bool bIN = true, bOUT = false;
00113   shared_int iIN = 999, iOUT = 0;
00114   shared_real rIN = 9999.9999, rOUT = 0;
00115 
00116   // Boolean loading
00117   EXPECT_TRUE(bytes.load(bIN));
00118   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_bool));
00119   EXPECT_TRUE(bytes.unload(bOUT));
00120   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00121   EXPECT_EQ(bOUT, bIN);
00122 
00123   // Integer loading
00124   EXPECT_TRUE(bytes.load(iIN));
00125   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_int));
00126   EXPECT_TRUE(bytes.unload(iOUT));
00127   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00128   EXPECT_EQ(iOUT, iIN);
00129 
00130   // Real loading
00131   EXPECT_TRUE(bytes.load(rIN));
00132   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_real));
00133   EXPECT_TRUE(bytes.unload(rOUT));
00134   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00135   EXPECT_EQ(rOUT, rIN);
00136 
00137   // Unloading a single member (down to an empty buffer size)
00138   EXPECT_TRUE(empty.load(bIN));
00139   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_bool));
00140   EXPECT_TRUE(empty.unload(bOUT));
00141   EXPECT_EQ((int)empty.getBufferSize(), 0);
00142   EXPECT_EQ(bOUT, bIN);
00143 
00144   // Loading two members (unloading the first) and then checking the value of the second
00145   rOUT = 0.0;
00146   iOUT = 0;
00147   EXPECT_TRUE(empty.load(rIN));
00148   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_real));
00149   EXPECT_TRUE(empty.load(iIN));
00150   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_real)+sizeof(shared_int));
00151   EXPECT_TRUE(empty.unloadFront(rOUT));
00152   EXPECT_EQ(rOUT, rIN);
00153   EXPECT_TRUE(empty.unload(iOUT));
00154   EXPECT_EQ((int)empty.getBufferSize(), 0);
00155   EXPECT_EQ(iOUT, iIN);
00156 }
00157 
00158 TEST(ByteArraySuite, byteSwapping)
00159 {
00160   if(ByteArray::isByteSwapEnabled())
00161   {
00162     ASSERT_TRUE(ByteArray::isByteSwapEnabled());
00163 
00164     ByteArray swapped;
00165     unsigned char buffer[] = {
00166         0x00, 0x00, 0x00, 0x38,   // be: 56
00167         0x00, 0x00, 0x00, 0x0a,   // be: 10
00168         0x00, 0x00, 0x00, 0x01,   // be:  1
00169 
00170         0x3e, 0x81, 0x32, 0x64,   // be:  0.25233757495880127
00171         0x3f, 0x30, 0x4b, 0x75,   // be:  0.68865138292312622
00172         0x3f, 0xa8, 0x9d, 0xd2,   // be:  1.3173162937164307
00173         0x3f, 0x85, 0x93, 0xdd,   // be:  1.0435749292373657
00174         0xbf, 0xf4, 0x8c, 0xc5,   // be: -1.9105459451675415
00175 
00176     };
00177     const unsigned int bufferLength = 32;
00178     shared_int tempInt;
00179     shared_real tempReal;
00180 
00181     swapped.init((const char*) buffer, bufferLength);
00182     ASSERT_EQ(swapped.getBufferSize(), bufferLength);
00183 
00184     ASSERT_TRUE(swapped.unload(tempReal));
00185     EXPECT_FLOAT_EQ(tempReal, -1.9105459451675415);
00186 
00187     ASSERT_TRUE(swapped.unload(tempReal));
00188     EXPECT_FLOAT_EQ(tempReal, 1.0435749292373657);
00189 
00190     ASSERT_TRUE(swapped.unload(tempReal));
00191     EXPECT_FLOAT_EQ(tempReal, 1.3173162937164307);
00192 
00193     ASSERT_TRUE(swapped.unload(tempReal));
00194     EXPECT_FLOAT_EQ(tempReal, 0.68865138292312622);
00195 
00196     ASSERT_TRUE(swapped.unload(tempReal));
00197     EXPECT_FLOAT_EQ(tempReal, 0.25233757495880127);
00198 
00199     ASSERT_TRUE(swapped.unload(tempInt));
00200     EXPECT_EQ(tempInt, 1);
00201 
00202     ASSERT_TRUE(swapped.unload(tempInt));
00203     EXPECT_EQ(tempInt, 10);
00204 
00205     ASSERT_TRUE(swapped.unload(tempInt));
00206     EXPECT_EQ(tempInt, 56);
00207 
00208     ASSERT_EQ(swapped.getBufferSize(), 0);
00209   }
00210 
00211 }
00212 
00213 TEST(ByteArraySuite, copy)
00214 {
00215 
00216   const shared_int SIZE = 100;
00217   char buffer[SIZE];
00218 
00219   // Copy
00220   ByteArray copyFrom;
00221   ByteArray copyTo;
00222   ByteArray tooBig;
00223 
00224 
00225   shared_int TOO_BIG = tooBig.getMaxBufferSize()-1;
00226   char bigBuffer[TOO_BIG];
00227 
00228   EXPECT_TRUE(copyFrom.init(&buffer[0], SIZE));
00229   EXPECT_TRUE(copyTo.load(copyFrom));
00230   EXPECT_EQ((shared_int)copyTo.getBufferSize(), SIZE);
00231   EXPECT_TRUE(copyTo.load(copyFrom));
00232   EXPECT_EQ((shared_int)copyTo.getBufferSize(), 2*SIZE);
00233 
00234   // Copy too large
00235   EXPECT_TRUE(tooBig.init(&bigBuffer[0], TOO_BIG));
00236   EXPECT_FALSE(copyTo.load(tooBig));
00237   // A failed load should not change the buffer.
00238   EXPECT_EQ((shared_int)copyTo.getBufferSize(), 2*SIZE);
00239 }
00240 
00241 // Need access to protected members for testing
00242 #ifndef UDP_TEST
00243 class TestClient : public TcpClient
00244 {
00245   public:
00246   bool sendBytes(ByteArray & buffer)
00247   {
00248     return TcpClient::sendBytes(buffer);
00249   };
00250 };
00251 class TestServer : public TcpServer
00252 {
00253   public:
00254   bool receiveBytes(ByteArray & buffer, shared_int num_bytes)
00255   {
00256     return TcpServer::receiveBytes(buffer, num_bytes);
00257   }
00258 };
00259 #else
00260 class TestClient : public UdpClient
00261 {
00262   public:
00263   bool sendBytes(ByteArray & buffer)
00264   {
00265     return UdpClient::sendBytes(buffer);
00266   };
00267 };
00268 class TestServer : public UdpServer
00269 {
00270   public:
00271   bool receiveBytes(ByteArray & buffer, shared_int num_bytes)
00272   {
00273     return UdpServer::receiveBytes(buffer, num_bytes);
00274   }
00275 };
00276 #endif
00277 
00278 void*
00279 connectServerFunc(void* arg)
00280 {
00281   TestServer* server = (TestServer*)arg;  
00282   server->makeConnect();
00283   return NULL;
00284 }
00285 
00286 TEST(SocketSuite, read)
00287 {
00288   const int port = TEST_PORT_BASE;
00289   char ipAddr[] = "127.0.0.1";
00290 
00291   TestClient client;
00292   TestServer server;
00293   ByteArray send, recv;
00294   shared_int DATA = 99;
00295   shared_int TWO_INTS = 2 * sizeof(shared_int);
00296   shared_int ONE_INTS = 1 * sizeof(shared_int);
00297 
00298   // Construct server
00299   ASSERT_TRUE(server.init(port));
00300 
00301   // Construct a client
00302   ASSERT_TRUE(client.init(&ipAddr[0], port));
00303   pthread_t serverConnectThrd;
00304   pthread_create(&serverConnectThrd, NULL, connectServerFunc, &server);
00305 
00306   ASSERT_TRUE(client.makeConnect());
00307   pthread_join(serverConnectThrd, NULL);
00308 
00309   ASSERT_TRUE(send.load(DATA));
00310 
00311   // Send just right amount
00312   ASSERT_TRUE(client.sendBytes(send));
00313   ASSERT_TRUE(client.sendBytes(send));
00314   sleep(2);
00315   ASSERT_TRUE(server.receiveBytes(recv, TWO_INTS));
00316   ASSERT_EQ(TWO_INTS, recv.getBufferSize());
00317 
00318   // Send too many bytes
00319   ASSERT_TRUE(client.sendBytes(send));
00320   ASSERT_TRUE(client.sendBytes(send));
00321   ASSERT_TRUE(client.sendBytes(send));
00322   ASSERT_TRUE(server.receiveBytes(recv, TWO_INTS));
00323   ASSERT_EQ(TWO_INTS, recv.getBufferSize());
00324   ASSERT_TRUE(server.receiveBytes(recv, ONE_INTS));
00325   ASSERT_EQ(ONE_INTS, recv.getBufferSize());
00326 }
00327 
00328 
00329 // Utility for running tcp client in sending loop
00330 void*
00331 spinSender(void* arg)
00332 {
00333   TestClient* client = (TestClient*)arg;  
00334   ByteArray send;
00335   const int DATA = 256;
00336 
00337   send.load(DATA);
00338 
00339   while(true)
00340   {
00341     client->sendBytes(send);
00342     sleep(0.1);
00343   }
00344 }
00345 
00346 TEST(SocketSuite, splitPackets)
00347 {
00348   const int port = TEST_PORT_BASE + 1;
00349   char ipAddr[] = "127.0.0.1";
00350   const int RECV_LENGTH = 64;
00351 
00352   TestClient client;
00353   TestServer server;
00354   ByteArray recv;
00355 // Construct server
00356   ASSERT_TRUE(server.init(port));
00357 
00358   // Construct a client
00359   ASSERT_TRUE(client.init(&ipAddr[0], port));
00360   pthread_t serverConnectThrd;
00361   pthread_create(&serverConnectThrd, NULL, connectServerFunc, &server);
00362 
00363   ASSERT_TRUE(client.makeConnect());
00364   pthread_join(serverConnectThrd, NULL);
00365 
00366   pthread_t senderThrd;
00367   pthread_create(&senderThrd, NULL, spinSender, &client);
00368 
00369   ASSERT_TRUE(server.receiveBytes(recv, RECV_LENGTH));
00370   ASSERT_EQ(RECV_LENGTH, recv.getBufferSize());
00371 
00372   pthread_cancel(senderThrd);
00373   pthread_join(senderThrd, NULL);
00374 }
00375 
00376 
00377 TEST(SimpleMessageSuite, init)
00378 {
00379   SimpleMessage msg;
00380   ByteArray bytes;
00381 
00382   // Valid messages
00383   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::TOPIC, ReplyTypes::INVALID, bytes));
00384   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::INVALID, bytes));
00385   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REPLY,ReplyTypes::SUCCESS, bytes));
00386   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REPLY,ReplyTypes::FAILURE, bytes));
00387 
00388   // Unused command
00389   EXPECT_FALSE(msg.init(StandardMsgTypes::INVALID, CommTypes::INVALID,ReplyTypes::INVALID, bytes));
00390 
00391   // Service request with a reply
00392   EXPECT_FALSE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::SUCCESS, bytes));
00393   EXPECT_FALSE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::FAILURE, bytes));
00394 }
00395 
00396 TEST(PingMessageSuite, init)
00397 {
00398   PingMessage ping;
00399   SimpleMessage msg;
00400 
00401   EXPECT_FALSE(ping.init(msg));
00402   ping.init();
00403   EXPECT_EQ(StandardMsgTypes::PING, ping.getMessageType());
00404 
00405   ping = PingMessage();
00406   ASSERT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST, ReplyTypes::INVALID));
00407   EXPECT_TRUE(ping.init(msg));
00408   EXPECT_EQ(StandardMsgTypes::PING, ping.getMessageType());
00409 }
00410 
00411 TEST(PingMessageSuite, toMessage)
00412 {
00413   PingMessage ping;
00414   SimpleMessage msg;
00415 
00416   ping.init();
00417 
00418   ASSERT_TRUE(ping.toReply(msg, ReplyTypes::SUCCESS));
00419   EXPECT_EQ(StandardMsgTypes::PING, msg.getMessageType());
00420   EXPECT_EQ(CommTypes::SERVICE_REPLY, msg.getCommType());
00421   EXPECT_EQ(ReplyTypes::SUCCESS, msg.getReplyCode());
00422 
00423   ASSERT_TRUE(ping.toRequest(msg));
00424   EXPECT_EQ(StandardMsgTypes::PING, msg.getMessageType());
00425   EXPECT_EQ(CommTypes::SERVICE_REQUEST, msg.getCommType());
00426   EXPECT_EQ(ReplyTypes::INVALID, msg.getReplyCode());
00427 
00428   EXPECT_FALSE(ping.toTopic(msg));
00429 
00430 }
00431 
00432 TEST(PingHandlerSuite, init)
00433 {
00434   PingHandler handler;
00435   TestClient client;
00436 
00437   ASSERT_TRUE(handler.init(&client));
00438   EXPECT_EQ(StandardMsgTypes::PING, handler.getMsgType());
00439 
00440   EXPECT_FALSE(handler.init(NULL));
00441 
00442 }
00443 
00444 TEST(MessageManagerSuite, init)
00445 {
00446   MessageManager manager;
00447   TestClient client;
00448 
00449   EXPECT_TRUE(manager.init(&client));
00450   EXPECT_FALSE(manager.init(NULL));
00451 
00452 }
00453 
00454 TEST(MessageManagerSuite, addHandler)
00455 {
00456   MessageManager manager;
00457   TestClient client;
00458   PingHandler handler;
00459 
00460   EXPECT_EQ(0, (int)manager.getNumHandlers());
00461 
00462   ASSERT_TRUE(manager.init(&client));
00463   EXPECT_EQ(1, (int)manager.getNumHandlers());
00464   EXPECT_FALSE(manager.add(NULL));
00465 
00466   ASSERT_TRUE(handler.init(&client));
00467   EXPECT_FALSE(manager.add(&handler));
00468 }
00469 
00470 // wrapper around MessageManager::spin() that can be passed to
00471 // pthread_create()
00472 void*
00473 spinFunc(void* arg)
00474 {
00475   MessageManager* mgr = (MessageManager*)arg;
00476   mgr->spin();
00477   return NULL;
00478 }
00479 
00480 TEST(DISABLED_MessageManagerSuite, tcp)
00481 {
00482   const int port = TEST_PORT_BASE + 201;
00483   char ipAddr[] = "127.0.0.1";
00484 
00485   TestClient* client = new TestClient();
00486   TestServer server;
00487   SimpleMessage pingRequest, pingReply;
00488   MessageManager msgManager;
00489 
00490   // MessageManager uses ros::ok, which needs ros spinner
00491   ros::AsyncSpinner spinner(0);
00492   spinner.start();
00493 
00494   ASSERT_TRUE(pingRequest.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST, ReplyTypes::INVALID));
00495 
00496   // TCP Socket testing
00497 
00498   // Construct server
00499   ASSERT_TRUE(server.init(port));
00500 
00501   // Construct a client
00502   ASSERT_TRUE(client->init(&ipAddr[0], port));
00503 
00504   // Connect server and client
00505   pthread_t serverConnectThrd;
00506   pthread_create(&serverConnectThrd, NULL, connectServerFunc, &server);
00507 
00508   ASSERT_TRUE(client->makeConnect());
00509   pthread_join(serverConnectThrd, NULL);
00510 
00511   // Listen for client connection, init manager and start thread
00512   ASSERT_TRUE(msgManager.init(&server));
00513 
00514   // TODO: The message manager is not thread safe (threads are used for testing,
00515   // but running the message manager in a thread results in errors when the
00516   // underlying connection is deconstructed before the manager
00517   //boost::thread spinSrvThrd(boost::bind(&MessageManager::spin, &msgManager));
00518   pthread_t spinSrvThrd;
00519   pthread_create(&spinSrvThrd, NULL, spinFunc, &msgManager);
00520 
00521   // Ping the server
00522   ASSERT_TRUE(client->sendMsg(pingRequest));
00523   ASSERT_TRUE(client->receiveMsg(pingReply));
00524   ASSERT_TRUE(client->sendAndReceiveMsg(pingRequest, pingReply));
00525 
00526   // Delete client and try to reconnect
00527 
00528   delete client;
00529   sleep(10); //Allow time for client to destruct and free up port
00530   client = new TestClient();
00531 
00532   ASSERT_TRUE(client->init(&ipAddr[0], port));
00533   ASSERT_TRUE(client->makeConnect());
00534   ASSERT_TRUE(client->sendAndReceiveMsg(pingRequest, pingReply));
00535 
00536   pthread_cancel(spinSrvThrd);
00537   pthread_join(spinSrvThrd, NULL);
00538 
00539   delete client;
00540 }
00541 
00542 // Run all the tests that were declared with TEST()
00543 int main(int argc, char **argv)
00544 {
00545   ros::init(argc, argv, "test");  // some tests need ROS framework
00546   testing::InitGoogleTest(&argc, argv);
00547   return RUN_ALL_TESTS();
00548 }
00549 


simple_message
Author(s): Shaun Edwards
autogenerated on Sat Jun 8 2019 20:43:23