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 #include <limits>
00057 
00058 using namespace industrial::simple_message;
00059 using namespace industrial::byte_array;
00060 using namespace industrial::shared_types;
00061 using namespace industrial::smpl_msg_connection;
00062 using namespace industrial::udp_socket;
00063 using namespace industrial::udp_client;
00064 using namespace industrial::udp_server;
00065 using namespace industrial::tcp_socket;
00066 using namespace industrial::tcp_client;
00067 using namespace industrial::tcp_server;
00068 using namespace industrial::ping_message;
00069 using namespace industrial::ping_handler;
00070 using namespace industrial::joint_data;
00071 using namespace industrial::joint_message;
00072 using namespace industrial::message_manager;
00073 using namespace industrial::simple_comms_fault_handler;
00074 using namespace industrial::joint_traj_pt;
00075 using namespace industrial::joint_traj_pt_message;
00076 using namespace industrial::typed_message;
00077 using namespace industrial::joint_traj;
00078 
00079 // Multiple tests require TEST_PORT_BASE to be defined.  This is defined
00080 // by the make file at compile time.
00081 //#define TEST_PORT_BASE 11000
00082 
00083 TEST(ByteArraySuite, init)
00084 {
00085 
00086   const shared_int SIZE = 100;
00087 
00088   ByteArray bytes;
00089   char buffer[SIZE];
00090 
00091   // Valid byte arrays
00092   EXPECT_TRUE(bytes.init(&buffer[0], SIZE));
00093   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00094 
00095   // Invalid init (too big)
00096   if (bytes.getMaxBufferSize() < std::numeric_limits<shared_int>::max())
00097   {
00098       shared_int TOO_BIG = bytes.getMaxBufferSize()+1;
00099       char bigBuffer[TOO_BIG];
00100       EXPECT_FALSE(bytes.init(&bigBuffer[0], TOO_BIG));
00101   }
00102   else
00103       std::cout << std::string(15, ' ')
00104                 << "ByteArray.MaxSize==INT_MAX.  Skipping TOO_BIG tests" << std::endl;
00105 
00106 }
00107 
00108 TEST(ByteArraySuite, loading)
00109 {
00110   const shared_int SIZE = 100;
00111   char buffer[SIZE];
00112 
00113   ByteArray bytes;
00114   ByteArray empty;
00115 
00116   ASSERT_TRUE(bytes.init(&buffer[0], SIZE));
00117 
00118   shared_bool bIN = true, bOUT = false;
00119   shared_int iIN = 999, iOUT = 0;
00120   shared_real rIN = 9999.9999, rOUT = 0;
00121 
00122   // Boolean loading
00123   EXPECT_TRUE(bytes.load(bIN));
00124   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_bool));
00125   EXPECT_TRUE(bytes.unload(bOUT));
00126   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00127   EXPECT_EQ(bOUT, bIN);
00128 
00129   // Integer loading
00130   EXPECT_TRUE(bytes.load(iIN));
00131   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_int));
00132   EXPECT_TRUE(bytes.unload(iOUT));
00133   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00134   EXPECT_EQ(iOUT, iIN);
00135 
00136   // Real loading
00137   EXPECT_TRUE(bytes.load(rIN));
00138   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_real));
00139   EXPECT_TRUE(bytes.unload(rOUT));
00140   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00141   EXPECT_EQ(rOUT, rIN);
00142 
00143   // Unloading a single member (down to an empty buffer size)
00144   EXPECT_TRUE(empty.load(bIN));
00145   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_bool));
00146   EXPECT_TRUE(empty.unload(bOUT));
00147   EXPECT_EQ((int)empty.getBufferSize(), 0);
00148   EXPECT_EQ(bOUT, bIN);
00149 
00150   // Loading two members (unloading the first) and then checking the value of the second
00151   rOUT = 0.0;
00152   iOUT = 0;
00153   EXPECT_TRUE(empty.load(rIN));
00154   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_real));
00155   EXPECT_TRUE(empty.load(iIN));
00156   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_real)+sizeof(shared_int));
00157   EXPECT_TRUE(empty.unloadFront(rOUT));
00158   EXPECT_EQ(rOUT, rIN);
00159   EXPECT_TRUE(empty.unload(iOUT));
00160   EXPECT_EQ((int)empty.getBufferSize(), 0);
00161   EXPECT_EQ(iOUT, iIN);
00162 }
00163 
00164 TEST(ByteArraySuite, byteSwapping)
00165 {
00166   if(ByteArray::isByteSwapEnabled())
00167   {
00168     ASSERT_TRUE(ByteArray::isByteSwapEnabled());
00169 
00170     ByteArray swapped;
00171     unsigned char buffer[] = {
00172         0x00, 0x00, 0x00, 0x38,   // be: 56
00173         0x00, 0x00, 0x00, 0x0a,   // be: 10
00174         0x00, 0x00, 0x00, 0x01,   // be:  1
00175 
00176         0x3e, 0x81, 0x32, 0x64,   // be:  0.25233757495880127
00177         0x3f, 0x30, 0x4b, 0x75,   // be:  0.68865138292312622
00178         0x3f, 0xa8, 0x9d, 0xd2,   // be:  1.3173162937164307
00179         0x3f, 0x85, 0x93, 0xdd,   // be:  1.0435749292373657
00180         0xbf, 0xf4, 0x8c, 0xc5,   // be: -1.9105459451675415
00181 
00182     };
00183     const unsigned int bufferLength = 32;
00184     shared_int tempInt;
00185     shared_real tempReal;
00186 
00187     swapped.init((const char*) buffer, bufferLength);
00188     ASSERT_EQ(swapped.getBufferSize(), bufferLength);
00189 
00190     ASSERT_TRUE(swapped.unload(tempReal));
00191     EXPECT_FLOAT_EQ(tempReal, -1.9105459451675415);
00192 
00193     ASSERT_TRUE(swapped.unload(tempReal));
00194     EXPECT_FLOAT_EQ(tempReal, 1.0435749292373657);
00195 
00196     ASSERT_TRUE(swapped.unload(tempReal));
00197     EXPECT_FLOAT_EQ(tempReal, 1.3173162937164307);
00198 
00199     ASSERT_TRUE(swapped.unload(tempReal));
00200     EXPECT_FLOAT_EQ(tempReal, 0.68865138292312622);
00201 
00202     ASSERT_TRUE(swapped.unload(tempReal));
00203     EXPECT_FLOAT_EQ(tempReal, 0.25233757495880127);
00204 
00205     ASSERT_TRUE(swapped.unload(tempInt));
00206     EXPECT_EQ(tempInt, 1);
00207 
00208     ASSERT_TRUE(swapped.unload(tempInt));
00209     EXPECT_EQ(tempInt, 10);
00210 
00211     ASSERT_TRUE(swapped.unload(tempInt));
00212     EXPECT_EQ(tempInt, 56);
00213 
00214     ASSERT_EQ(swapped.getBufferSize(), 0);
00215   }
00216 
00217 }
00218 
00219 TEST(ByteArraySuite, copy)
00220 {
00221 
00222   const shared_int SIZE = 100;
00223   char buffer[SIZE];
00224 
00225   // Copy
00226   ByteArray copyFrom;
00227   ByteArray copyTo;
00228 
00229   EXPECT_TRUE(copyFrom.init(&buffer[0], SIZE));
00230   EXPECT_TRUE(copyTo.load(copyFrom));
00231   EXPECT_EQ((shared_int)copyTo.getBufferSize(), SIZE);
00232   EXPECT_TRUE(copyTo.load(copyFrom));
00233   EXPECT_EQ((shared_int)copyTo.getBufferSize(), 2*SIZE);
00234 
00235   // Copy too large
00236   ByteArray tooBig;
00237   if (tooBig.getMaxBufferSize()-1 <= std::numeric_limits<shared_int>::max())
00238   {
00239       shared_int TOO_BIG = tooBig.getMaxBufferSize()-1;
00240       char bigBuffer[TOO_BIG];
00241 
00242       EXPECT_TRUE(tooBig.init(&bigBuffer[0], TOO_BIG));
00243       EXPECT_FALSE(copyTo.load(tooBig));
00244       // A failed load should not change the buffer.
00245       EXPECT_EQ((shared_int)copyTo.getBufferSize(), 2*SIZE);
00246   }
00247   else
00248       std::cout << std::string(15, ' ')
00249                 << "ByteArray.MaxSize==INT_MAX.  Skipping TOO_BIG tests" << std::endl;
00250 }
00251 
00252 // Need access to protected members for testing
00253 #ifndef UDP_TEST
00254 class TestClient : public TcpClient
00255 {
00256   public:
00257   bool sendBytes(ByteArray & buffer)
00258   {
00259     return TcpClient::sendBytes(buffer);
00260   };
00261 };
00262 class TestServer : public TcpServer
00263 {
00264   public:
00265   bool receiveBytes(ByteArray & buffer, shared_int num_bytes)
00266   {
00267     return TcpServer::receiveBytes(buffer, num_bytes);
00268   }
00269 };
00270 #else
00271 class TestClient : public UdpClient
00272 {
00273   public:
00274   bool sendBytes(ByteArray & buffer)
00275   {
00276     return UdpClient::sendBytes(buffer);
00277   };
00278 };
00279 class TestServer : public UdpServer
00280 {
00281   public:
00282   bool receiveBytes(ByteArray & buffer, shared_int num_bytes)
00283   {
00284     return UdpServer::receiveBytes(buffer, num_bytes);
00285   }
00286 };
00287 #endif
00288 
00289 void*
00290 connectServerFunc(void* arg)
00291 {
00292   TestServer* server = (TestServer*)arg;  
00293   server->makeConnect();
00294   return NULL;
00295 }
00296 
00297 TEST(SocketSuite, read)
00298 {
00299   const int port = TEST_PORT_BASE;
00300   char ipAddr[] = "127.0.0.1";
00301 
00302   TestClient client;
00303   TestServer server;
00304   ByteArray send, recv;
00305   shared_int DATA = 99;
00306   shared_int TWO_INTS = 2 * sizeof(shared_int);
00307   shared_int ONE_INTS = 1 * sizeof(shared_int);
00308 
00309   // Construct server
00310   ASSERT_TRUE(server.init(port));
00311 
00312   // Construct a client
00313   ASSERT_TRUE(client.init(&ipAddr[0], port));
00314   pthread_t serverConnectThrd;
00315   pthread_create(&serverConnectThrd, NULL, connectServerFunc, &server);
00316 
00317   ASSERT_TRUE(client.makeConnect());
00318   pthread_join(serverConnectThrd, NULL);
00319 
00320   ASSERT_TRUE(send.load(DATA));
00321 
00322   // Send just right amount
00323   ASSERT_TRUE(client.sendBytes(send));
00324   ASSERT_TRUE(client.sendBytes(send));
00325   sleep(2);
00326   ASSERT_TRUE(server.receiveBytes(recv, TWO_INTS));
00327   ASSERT_EQ(TWO_INTS, recv.getBufferSize());
00328 
00329   // Send too many bytes
00330   ASSERT_TRUE(client.sendBytes(send));
00331   ASSERT_TRUE(client.sendBytes(send));
00332   ASSERT_TRUE(client.sendBytes(send));
00333   ASSERT_TRUE(server.receiveBytes(recv, TWO_INTS));
00334   ASSERT_EQ(TWO_INTS, recv.getBufferSize());
00335   ASSERT_TRUE(server.receiveBytes(recv, ONE_INTS));
00336   ASSERT_EQ(ONE_INTS, recv.getBufferSize());
00337 }
00338 
00339 
00340 // Utility for running tcp client in sending loop
00341 void*
00342 spinSender(void* arg)
00343 {
00344   TestClient* client = (TestClient*)arg;  
00345   ByteArray send;
00346   const int DATA = 256;
00347 
00348   send.load(DATA);
00349 
00350   while(true)
00351   {
00352     client->sendBytes(send);
00353     sleep(0.1);
00354   }
00355 }
00356 
00357 TEST(SocketSuite, splitPackets)
00358 {
00359   const int port = TEST_PORT_BASE + 1;
00360   char ipAddr[] = "127.0.0.1";
00361   const int RECV_LENGTH = 64;
00362 
00363   TestClient client;
00364   TestServer server;
00365   ByteArray recv;
00366 // Construct server
00367   ASSERT_TRUE(server.init(port));
00368 
00369   // Construct a client
00370   ASSERT_TRUE(client.init(&ipAddr[0], port));
00371   pthread_t serverConnectThrd;
00372   pthread_create(&serverConnectThrd, NULL, connectServerFunc, &server);
00373 
00374   ASSERT_TRUE(client.makeConnect());
00375   pthread_join(serverConnectThrd, NULL);
00376 
00377   pthread_t senderThrd;
00378   pthread_create(&senderThrd, NULL, spinSender, &client);
00379 
00380   ASSERT_TRUE(server.receiveBytes(recv, RECV_LENGTH));
00381   ASSERT_EQ(RECV_LENGTH, recv.getBufferSize());
00382 
00383   pthread_cancel(senderThrd);
00384   pthread_join(senderThrd, NULL);
00385 }
00386 
00387 
00388 TEST(SimpleMessageSuite, init)
00389 {
00390   SimpleMessage msg;
00391   ByteArray bytes;
00392 
00393   // Valid messages
00394   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::TOPIC, ReplyTypes::INVALID, bytes));
00395   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::INVALID, bytes));
00396   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REPLY,ReplyTypes::SUCCESS, bytes));
00397   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REPLY,ReplyTypes::FAILURE, bytes));
00398 
00399   // Unused command
00400   EXPECT_FALSE(msg.init(StandardMsgTypes::INVALID, CommTypes::INVALID,ReplyTypes::INVALID, bytes));
00401 
00402   // Service request with a reply
00403   EXPECT_FALSE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::SUCCESS, bytes));
00404   EXPECT_FALSE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::FAILURE, bytes));
00405 }
00406 
00407 TEST(PingMessageSuite, init)
00408 {
00409   PingMessage ping;
00410   SimpleMessage msg;
00411 
00412   EXPECT_FALSE(ping.init(msg));
00413   ping.init();
00414   EXPECT_EQ(StandardMsgTypes::PING, ping.getMessageType());
00415 
00416   ping = PingMessage();
00417   ASSERT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST, ReplyTypes::INVALID));
00418   EXPECT_TRUE(ping.init(msg));
00419   EXPECT_EQ(StandardMsgTypes::PING, ping.getMessageType());
00420 }
00421 
00422 TEST(PingMessageSuite, toMessage)
00423 {
00424   PingMessage ping;
00425   SimpleMessage msg;
00426 
00427   ping.init();
00428 
00429   ASSERT_TRUE(ping.toReply(msg, ReplyTypes::SUCCESS));
00430   EXPECT_EQ(StandardMsgTypes::PING, msg.getMessageType());
00431   EXPECT_EQ(CommTypes::SERVICE_REPLY, msg.getCommType());
00432   EXPECT_EQ(ReplyTypes::SUCCESS, msg.getReplyCode());
00433 
00434   ASSERT_TRUE(ping.toRequest(msg));
00435   EXPECT_EQ(StandardMsgTypes::PING, msg.getMessageType());
00436   EXPECT_EQ(CommTypes::SERVICE_REQUEST, msg.getCommType());
00437   EXPECT_EQ(ReplyTypes::INVALID, msg.getReplyCode());
00438 
00439   EXPECT_FALSE(ping.toTopic(msg));
00440 
00441 }
00442 
00443 TEST(PingHandlerSuite, init)
00444 {
00445   PingHandler handler;
00446   TestClient client;
00447 
00448   ASSERT_TRUE(handler.init(&client));
00449   EXPECT_EQ(StandardMsgTypes::PING, handler.getMsgType());
00450 
00451   EXPECT_FALSE(handler.init(NULL));
00452 
00453 }
00454 
00455 TEST(MessageManagerSuite, init)
00456 {
00457   MessageManager manager;
00458   TestClient client;
00459 
00460   EXPECT_TRUE(manager.init(&client));
00461   EXPECT_FALSE(manager.init(NULL));
00462 
00463 }
00464 
00465 TEST(MessageManagerSuite, addHandler)
00466 {
00467   MessageManager manager;
00468   TestClient client;
00469   PingHandler handler;
00470 
00471   EXPECT_EQ(0, (int)manager.getNumHandlers());
00472 
00473   ASSERT_TRUE(manager.init(&client));
00474   EXPECT_EQ(1, (int)manager.getNumHandlers());
00475   EXPECT_FALSE(manager.add(NULL));
00476 
00477   ASSERT_TRUE(handler.init(&client));
00478   EXPECT_FALSE(manager.add(&handler));
00479 }
00480 
00481 // wrapper around MessageManager::spin() that can be passed to
00482 // pthread_create()
00483 void*
00484 spinFunc(void* arg)
00485 {
00486   MessageManager* mgr = (MessageManager*)arg;
00487   mgr->spin();
00488   return NULL;
00489 }
00490 
00491 /*  Commenting out this test because build shows "unstable" with disabled tests
00492 // See https://github.com/ros-industrial/industrial_core/issues/149 for details
00493 TEST(DISABLED_MessageManagerSuite, tcp)
00494 {
00495   const int port = TEST_PORT_BASE + 201;
00496   char ipAddr[] = "127.0.0.1";
00497 
00498   TestClient* client = new TestClient();
00499   TestServer server;
00500   SimpleMessage pingRequest, pingReply;
00501   MessageManager msgManager;
00502 
00503   // MessageManager uses ros::ok, which needs ros spinner
00504   ros::AsyncSpinner spinner(0);
00505   spinner.start();
00506 
00507   ASSERT_TRUE(pingRequest.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST, ReplyTypes::INVALID));
00508 
00509   // TCP Socket testing
00510 
00511   // Construct server
00512   ASSERT_TRUE(server.init(port));
00513 
00514   // Construct a client
00515   ASSERT_TRUE(client->init(&ipAddr[0], port));
00516 
00517   // Connect server and client
00518   pthread_t serverConnectThrd;
00519   pthread_create(&serverConnectThrd, NULL, connectServerFunc, &server);
00520 
00521   ASSERT_TRUE(client->makeConnect());
00522   pthread_join(serverConnectThrd, NULL);
00523 
00524   // Listen for client connection, init manager and start thread
00525   ASSERT_TRUE(msgManager.init(&server));
00526 
00527   // TODO: The message manager is not thread safe (threads are used for testing,
00528   // but running the message manager in a thread results in errors when the
00529   // underlying connection is deconstructed before the manager
00530   //boost::thread spinSrvThrd(boost::bind(&MessageManager::spin, &msgManager));
00531   pthread_t spinSrvThrd;
00532   pthread_create(&spinSrvThrd, NULL, spinFunc, &msgManager);
00533 
00534   // Ping the server
00535   ASSERT_TRUE(client->sendMsg(pingRequest));
00536   ASSERT_TRUE(client->receiveMsg(pingReply));
00537   ASSERT_TRUE(client->sendAndReceiveMsg(pingRequest, pingReply));
00538 
00539   // Delete client and try to reconnect
00540 
00541   delete client;
00542   sleep(10); //Allow time for client to destruct and free up port
00543   client = new TestClient();
00544 
00545   ASSERT_TRUE(client->init(&ipAddr[0], port));
00546   ASSERT_TRUE(client->makeConnect());
00547   ASSERT_TRUE(client->sendAndReceiveMsg(pingRequest, pingReply));
00548 
00549   pthread_cancel(spinSrvThrd);
00550   pthread_join(spinSrvThrd, NULL);
00551 
00552   delete client;
00553 }
00554 */
00555 
00556 // Run all the tests that were declared with TEST()
00557 int main(int argc, char **argv)
00558 {
00559   ros::init(argc, argv, "test");  // some tests need ROS framework
00560   testing::InitGoogleTest(&argc, argv);
00561   return RUN_ALL_TESTS();
00562 }
00563 


simple_message
Author(s): Shaun Edwards
autogenerated on Tue Jan 17 2017 21:10:02