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 TEST(ByteArraySuite, init)
00079 {
00080 
00081   const shared_int SIZE = 100;
00082 
00083   ByteArray bytes;
00084   shared_int TOO_BIG = bytes.getMaxBufferSize()+1;
00085 
00086   char bigBuffer[TOO_BIG];
00087   char buffer[SIZE];
00088 
00089   // Valid byte arrays
00090   EXPECT_TRUE(bytes.init(&buffer[0], SIZE));
00091   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00092 
00093   // Invalid init (too big)
00094   // Invalid buffers
00095   EXPECT_FALSE(bytes.init(&bigBuffer[0], TOO_BIG));
00096 }
00097 
00098 TEST(ByteArraySuite, loading)
00099 {
00100   const shared_int SIZE = 100;
00101   char buffer[SIZE];
00102 
00103   ByteArray bytes;
00104   ByteArray empty;
00105 
00106   ASSERT_TRUE(bytes.init(&buffer[0], SIZE));
00107 
00108   shared_bool bIN = true, bOUT = false;
00109   shared_int iIN = 999, iOUT = 0;
00110   shared_real rIN = 9999.9999, rOUT = 0;
00111 
00112   // Boolean loading
00113   EXPECT_TRUE(bytes.load(bIN));
00114   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_bool));
00115   EXPECT_TRUE(bytes.unload(bOUT));
00116   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00117   EXPECT_EQ(bOUT, bIN);
00118 
00119   // Integer loading
00120   EXPECT_TRUE(bytes.load(iIN));
00121   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_int));
00122   EXPECT_TRUE(bytes.unload(iOUT));
00123   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00124   EXPECT_EQ(iOUT, iIN);
00125 
00126   // Real loading
00127   EXPECT_TRUE(bytes.load(rIN));
00128   EXPECT_EQ(bytes.getBufferSize(), SIZE+sizeof(shared_real));
00129   EXPECT_TRUE(bytes.unload(rOUT));
00130   EXPECT_EQ((shared_int)bytes.getBufferSize(), SIZE);
00131   EXPECT_EQ(rOUT, rIN);
00132 
00133   // Unloading a single member (down to an empty buffer size)
00134   EXPECT_TRUE(empty.load(bIN));
00135   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_bool));
00136   EXPECT_TRUE(empty.unload(bOUT));
00137   EXPECT_EQ((int)empty.getBufferSize(), 0);
00138   EXPECT_EQ(bOUT, bIN);
00139 
00140   // Loading two members (unloading the first) and then checking the value of the second
00141   rOUT = 0.0;
00142   iOUT = 0;
00143   EXPECT_TRUE(empty.load(rIN));
00144   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_real));
00145   EXPECT_TRUE(empty.load(iIN));
00146   EXPECT_EQ(empty.getBufferSize(), sizeof(shared_real)+sizeof(shared_int));
00147   EXPECT_TRUE(empty.unloadFront(rOUT));
00148   EXPECT_EQ(rOUT, rIN);
00149   EXPECT_TRUE(empty.unload(iOUT));
00150   EXPECT_EQ((int)empty.getBufferSize(), 0);
00151   EXPECT_EQ(iOUT, iIN);
00152 }
00153 
00154 TEST(ByteArraySuite, byteSwapping)
00155 {
00156   if(ByteArray::isByteSwapEnabled())
00157   {
00158     ASSERT_TRUE(ByteArray::isByteSwapEnabled());
00159 
00160     ByteArray swapped;
00161     unsigned char buffer[] = {
00162             0x00, 0x00, 0x00, 0x38,   // be: 56
00163             0x00, 0x00, 0x00, 0x0a,   // be: 10
00164             0x00, 0x00, 0x00, 0x01,   // be:  1
00165 
00166             0x3e, 0x81, 0x32, 0x64,   // be:  0.25233757495880127
00167             0x3f, 0x30, 0x4b, 0x75,   // be:  0.68865138292312622
00168             0x3f, 0xa8, 0x9d, 0xd2,   // be:  1.3173162937164307
00169             0x3f, 0x85, 0x93, 0xdd,   // be:  1.0435749292373657
00170             0xbf, 0xf4, 0x8c, 0xc5,   // be: -1.9105459451675415
00171 
00172     };
00173     const unsigned int bufferLength = 32;
00174     shared_int tempInt;
00175     shared_real tempReal;
00176 
00177     swapped.init((const char*) buffer, bufferLength);
00178     ASSERT_EQ(swapped.getBufferSize(), bufferLength);
00179 
00180     ASSERT_TRUE(swapped.unload(tempReal));
00181     EXPECT_FLOAT_EQ(tempReal, -1.9105459451675415);
00182 
00183     ASSERT_TRUE(swapped.unload(tempReal));
00184     EXPECT_FLOAT_EQ(tempReal, 1.0435749292373657);
00185 
00186     ASSERT_TRUE(swapped.unload(tempReal));
00187     EXPECT_FLOAT_EQ(tempReal, 1.3173162937164307);
00188 
00189     ASSERT_TRUE(swapped.unload(tempReal));
00190     EXPECT_FLOAT_EQ(tempReal, 0.68865138292312622);
00191 
00192     ASSERT_TRUE(swapped.unload(tempReal));
00193     EXPECT_FLOAT_EQ(tempReal, 0.25233757495880127);
00194 
00195     ASSERT_TRUE(swapped.unload(tempInt));
00196     EXPECT_EQ(tempInt, 1);
00197 
00198     ASSERT_TRUE(swapped.unload(tempInt));
00199     EXPECT_EQ(tempInt, 10);
00200 
00201     ASSERT_TRUE(swapped.unload(tempInt));
00202     EXPECT_EQ(tempInt, 56);
00203 
00204     ASSERT_EQ(swapped.getBufferSize(), 0);
00205   }
00206 
00207 }
00208 
00209 TEST(ByteArraySuite, copy)
00210 {
00211 
00212   const shared_int SIZE = 100;
00213   char buffer[SIZE];
00214 
00215   // Copy
00216   ByteArray copyFrom;
00217   ByteArray copyTo;
00218   ByteArray tooBig;
00219 
00220 
00221   shared_int TOO_BIG = tooBig.getMaxBufferSize()-1;
00222   char bigBuffer[TOO_BIG];
00223 
00224   EXPECT_TRUE(copyFrom.init(&buffer[0], SIZE));
00225   EXPECT_TRUE(copyTo.load(copyFrom));
00226   EXPECT_EQ((shared_int)copyTo.getBufferSize(), SIZE);
00227   EXPECT_TRUE(copyTo.load(copyFrom));
00228   EXPECT_EQ((shared_int)copyTo.getBufferSize(), 2*SIZE);
00229 
00230   // Copy too large
00231   EXPECT_TRUE(tooBig.init(&bigBuffer[0], TOO_BIG));
00232   EXPECT_FALSE(copyTo.load(tooBig));
00233   // A failed load should not change the buffer.
00234   EXPECT_EQ((shared_int)copyTo.getBufferSize(), 2*SIZE);
00235 }
00236 
00237 TEST(SimpleMessageSuite, init)
00238 {
00239   SimpleMessage msg;
00240   ByteArray bytes;
00241 
00242   // Valid messages
00243   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::TOPIC, ReplyTypes::INVALID, bytes));
00244   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::INVALID, bytes));
00245   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REPLY,ReplyTypes::SUCCESS, bytes));
00246   EXPECT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REPLY,ReplyTypes::FAILURE, bytes));
00247 
00248   // Unused command
00249   EXPECT_FALSE(msg.init(StandardMsgTypes::INVALID, CommTypes::INVALID,ReplyTypes::INVALID, bytes));
00250 
00251   // Service request with a reply
00252   EXPECT_FALSE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::SUCCESS, bytes));
00253   EXPECT_FALSE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST,ReplyTypes::FAILURE, bytes));
00254 }
00255 
00256 TEST(PingMessageSuite, init)
00257 {
00258   PingMessage ping;
00259   SimpleMessage msg;
00260 
00261   EXPECT_FALSE(ping.init(msg));
00262   ping.init();
00263   EXPECT_EQ(StandardMsgTypes::PING, ping.getMessageType());
00264 
00265   ping = PingMessage();
00266   ASSERT_TRUE(msg.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST, ReplyTypes::INVALID));
00267   EXPECT_TRUE(ping.init(msg));
00268   EXPECT_EQ(StandardMsgTypes::PING, ping.getMessageType());
00269 }
00270 
00271 TEST(PingMessageSuite, toMessage)
00272 {
00273   PingMessage ping;
00274   SimpleMessage msg;
00275 
00276   ping.init();
00277 
00278   ASSERT_TRUE(ping.toReply(msg, ReplyTypes::SUCCESS));
00279   EXPECT_EQ(StandardMsgTypes::PING, msg.getMessageType());
00280   EXPECT_EQ(CommTypes::SERVICE_REPLY, msg.getCommType());
00281   EXPECT_EQ(ReplyTypes::SUCCESS, msg.getReplyCode());
00282 
00283   ASSERT_TRUE(ping.toRequest(msg));
00284   EXPECT_EQ(StandardMsgTypes::PING, msg.getMessageType());
00285   EXPECT_EQ(CommTypes::SERVICE_REQUEST, msg.getCommType());
00286   EXPECT_EQ(ReplyTypes::INVALID, msg.getReplyCode());
00287 
00288   EXPECT_FALSE(ping.toTopic(msg));
00289 
00290 }
00291 
00292 TEST(PingHandlerSuite, init)
00293 {
00294   PingHandler handler;
00295   UdpClient udp;
00296 
00297   ASSERT_TRUE(handler.init(&udp));
00298   EXPECT_EQ(StandardMsgTypes::PING, handler.getMsgType());
00299 
00300   EXPECT_FALSE(handler.init(NULL));
00301 
00302 }
00303 
00304 TEST(MessageManagerSuite, init)
00305 {
00306   MessageManager manager;
00307   UdpClient udp;
00308 
00309   EXPECT_TRUE(manager.init(&udp));
00310   EXPECT_FALSE(manager.init(NULL));
00311 
00312 }
00313 
00314 TEST(MessageManagerSuite, addHandler)
00315 {
00316   MessageManager manager;
00317   UdpClient udp;
00318   PingHandler handler;
00319 
00320   EXPECT_EQ(0, (int)manager.getNumHandlers());
00321 
00322   ASSERT_TRUE(manager.init(&udp));
00323   EXPECT_EQ(1, (int)manager.getNumHandlers());
00324   EXPECT_FALSE(manager.add(NULL));
00325 
00326   ASSERT_TRUE(handler.init(&udp));
00327   EXPECT_FALSE(manager.add(&handler));
00328 }
00329 
00330 // wrapper around MessageManager::spin() that can be passed to
00331 // pthread_create()
00332 void*
00333 spinFunc(void* arg)
00334 {
00335   MessageManager* mgr = (MessageManager*)arg;
00336   mgr->spin();
00337   return NULL;
00338 }
00339 
00340 TEST(DISABLED_MessageManagerSuite, udp)
00341 {
00342   const int udpPort = 11000;
00343   char ipAddr[] = "127.0.0.1";
00344 
00345   UdpClient* udpClient = new UdpClient();
00346   UdpServer udpServer;
00347   SimpleMessage pingRequest, pingReply;
00348   MessageManager udpManager;
00349 
00350   ASSERT_TRUE(pingRequest.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST, ReplyTypes::INVALID));
00351 
00352   // UDP Socket testing
00353   // Construct server and start in a thread
00354   ASSERT_TRUE(udpServer.init(udpPort));
00355   ASSERT_TRUE(udpManager.init(&udpServer));
00356   //boost::thread udpSrvThrd(boost::bind(&MessageManager::spin, &udpManager));
00357   pthread_t udpSrvThrd;
00358   pthread_create(&udpSrvThrd, NULL, spinFunc, &udpManager);
00359 
00360   // Construct a client and try to ping the server
00361   ASSERT_TRUE(udpClient->init(&ipAddr[0], udpPort));
00362   ASSERT_TRUE(udpClient->makeConnect());
00363   ASSERT_TRUE(udpClient->sendMsg(pingRequest));
00364   ASSERT_TRUE(udpClient->receiveMsg(pingReply));
00365   ASSERT_TRUE(udpClient->sendAndReceiveMsg(pingRequest, pingReply));
00366 
00367   // Delete client and try to reconnect
00368   delete udpClient;
00369   udpClient = new UdpClient();
00370   ASSERT_TRUE(udpClient->init(&ipAddr[0], udpPort));
00371   ASSERT_TRUE(udpClient->makeConnect());
00372   ASSERT_TRUE(udpClient->sendAndReceiveMsg(pingRequest, pingReply));
00373 
00374   pthread_cancel(udpSrvThrd);
00375   pthread_join(udpSrvThrd, NULL);
00376 }
00377 
00378 TEST(DISABLED_MessageManagerSuite, tcp)
00379 {
00380   const int tcpPort = 11000;
00381   char ipAddr[] = "127.0.0.1";
00382 
00383   TcpClient* tcpClient = new TcpClient();
00384   TcpServer tcpServer;
00385   SimpleMessage pingRequest, pingReply;
00386   MessageManager tcpManager;
00387 
00388   // MessageManager uses ros::ok, which needs ros spinner
00389   ros::AsyncSpinner spinner(0);
00390   spinner.start();
00391 
00392   ASSERT_TRUE(pingRequest.init(StandardMsgTypes::PING, CommTypes::SERVICE_REQUEST, ReplyTypes::INVALID));
00393 
00394   // TCP Socket testing
00395 
00396   // Construct server
00397   ASSERT_TRUE(tcpServer.init(tcpPort));
00398 
00399   // Construct a client
00400   ASSERT_TRUE(tcpClient->init(&ipAddr[0], tcpPort));
00401   ASSERT_TRUE(tcpClient->makeConnect());
00402 
00403   // Listen for client connection, init manager and start thread
00404   ASSERT_TRUE(tcpServer.makeConnect());
00405   ASSERT_TRUE(tcpManager.init(&tcpServer));
00406 
00407   // TODO: The message manager is not thread safe (threads are used for testing,
00408   // but running the message manager in a thread results in errors when the
00409   // underlying connection is deconstructed before the manager
00410   //boost::thread tcpSrvThrd(boost::bind(&MessageManager::spin, &tcpManager));
00411   pthread_t tcpSrvThrd;
00412   pthread_create(&tcpSrvThrd, NULL, spinFunc, &tcpManager);
00413 
00414   // Ping the server
00415   ASSERT_TRUE(tcpClient->sendMsg(pingRequest));
00416   ASSERT_TRUE(tcpClient->receiveMsg(pingReply));
00417   ASSERT_TRUE(tcpClient->sendAndReceiveMsg(pingRequest, pingReply));
00418 
00419   // Delete client and try to reconnect
00420 
00421   delete tcpClient;
00422   sleep(10); //Allow time for client to destruct and free up port
00423   tcpClient = new TcpClient();
00424 
00425   ASSERT_TRUE(tcpClient->init(&ipAddr[0], tcpPort));
00426   ASSERT_TRUE(tcpClient->makeConnect());
00427   ASSERT_TRUE(tcpClient->sendAndReceiveMsg(pingRequest, pingReply));
00428 
00429   pthread_cancel(tcpSrvThrd);
00430   pthread_join(tcpSrvThrd, NULL);
00431 
00432   delete tcpClient;
00433 }
00434 
00435 // Run all the tests that were declared with TEST()
00436 int main(int argc, char **argv)
00437 {
00438   ros::init(argc, argv, "test");  // some tests need ROS framework
00439   testing::InitGoogleTest(&argc, argv);
00440   return RUN_ALL_TESTS();
00441 }
00442 


simple_message
Author(s): Shaun Edwards
autogenerated on Mon Oct 6 2014 00:54:18