utest_message.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2012, 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/socket/tcp_client.h"
00034 #include "simple_message/socket/tcp_server.h"
00035 #include "simple_message/messages/joint_message.h"
00036 #include "simple_message/joint_data.h"
00037 #include "simple_message/joint_traj_pt.h"
00038 #include "simple_message/messages/joint_traj_pt_message.h"
00039 #include "simple_message/typed_message.h"
00040 #include "simple_message/joint_traj.h"
00041 #include "simple_message/robot_status.h"
00042 #include "simple_message/messages/robot_status_message.h"
00043 
00044 #include <gtest/gtest.h>
00045 
00046 using namespace industrial::simple_message;
00047 using namespace industrial::tcp_socket;
00048 using namespace industrial::tcp_client;
00049 using namespace industrial::tcp_server;
00050 using namespace industrial::joint_data;
00051 using namespace industrial::joint_message;
00052 using namespace industrial::joint_traj_pt;
00053 using namespace industrial::joint_traj_pt_message;
00054 using namespace industrial::typed_message;
00055 using namespace industrial::joint_traj;
00056 using namespace industrial::robot_status;
00057 using namespace industrial::robot_status_message;
00058 
00059 // Message passing routine, used to send and receive a typed message
00060 // Useful for checking the packing and unpacking of message data.
00061 void messagePassing(TypedMessage &send, TypedMessage &recv)
00062 {
00063   const int tcpPort = 11010;
00064   char ipAddr[] = "127.0.0.1";
00065 
00066   TcpClient tcpClient;
00067   TcpServer tcpServer;
00068   SimpleMessage msgSend, msgRecv;
00069 
00070   ASSERT_TRUE(send.toTopic(msgSend));
00071 
00072   // Construct server
00073 
00074   ASSERT_TRUE(tcpServer.init(tcpPort));
00075 
00076   // Construct a client
00077   ASSERT_TRUE(tcpClient.init(&ipAddr[0], tcpPort));
00078   ASSERT_TRUE(tcpClient.makeConnect());
00079 
00080   ASSERT_TRUE(tcpServer.makeConnect());
00081 
00082   ASSERT_TRUE(tcpClient.sendMsg(msgSend));
00083   ASSERT_TRUE(tcpServer.receiveMsg(msgRecv));
00084   ASSERT_TRUE(recv.init(msgRecv));
00085 }
00086 
00087 TEST(JointMessage, init)
00088 {
00089   JointData joint;
00090 
00091   joint.init();
00092   EXPECT_TRUE(joint.setJoint(0, 1.0));
00093   EXPECT_TRUE(joint.setJoint(1, 2.0));
00094   EXPECT_TRUE(joint.setJoint(2, 3.0));
00095   EXPECT_TRUE(joint.setJoint(3, 4.0));
00096   EXPECT_TRUE(joint.setJoint(4, 5.0));
00097   EXPECT_TRUE(joint.setJoint(5, 6.0));
00098   EXPECT_TRUE(joint.setJoint(6, 7.0));
00099   EXPECT_TRUE(joint.setJoint(7, 8.0));
00100   EXPECT_TRUE(joint.setJoint(8, 9.0));
00101   EXPECT_TRUE(joint.setJoint(9, 10.0));
00102 
00103   EXPECT_FALSE(joint.setJoint(10, 11.0));
00104 
00105 }
00106 
00107 TEST(JointMessage, equal)
00108 {
00109   JointData jointlhs, jointrhs;
00110 
00111   jointrhs.init();
00112   jointlhs.init();
00113   jointlhs.setJoint(0, -1.0);
00114   jointlhs.setJoint(9, 1.0);
00115 
00116   EXPECT_FALSE(jointlhs==jointrhs);
00117 
00118   jointrhs.setJoint(0, -1.0);
00119   jointrhs.setJoint(9, 1.0);
00120 
00121   EXPECT_TRUE(jointlhs==jointrhs);
00122 
00123 }
00124 
00125 TEST(JointMessage, toMessage)
00126 {
00127   JointData toMessage, fromMessage;
00128   JointMessage msg;
00129 
00130   toMessage.init();
00131   toMessage.setJoint(4, 44.44);
00132 
00133   msg.init(1, toMessage);
00134 
00135   fromMessage.copyFrom(msg.getJoints());
00136 
00137   EXPECT_TRUE(toMessage==fromMessage);
00138 
00139 }
00140 
00141 TEST(JointMessage, Comms)
00142 {
00143 
00144   JointMessage jointSend, jointRecv;
00145   JointData posSend, posRecv;
00146 
00147   posSend.init();
00148   posSend.setJoint(0, 1.0);
00149   posSend.setJoint(1, 2.0);
00150   posSend.setJoint(2, 3.0);
00151   posSend.setJoint(3, 4.0);
00152   posSend.setJoint(4, 5.0);
00153   posSend.setJoint(5, 6.0);
00154   posSend.setJoint(6, 7.0);
00155   posSend.setJoint(7, 8.0);
00156   posSend.setJoint(8, 9.0);
00157   posSend.setJoint(9, 10.0);
00158 
00159   jointSend.init(1, posSend);
00160 
00161   messagePassing(jointSend, jointRecv);
00162 
00163   posRecv.copyFrom(jointRecv.getJoints());
00164   ASSERT_TRUE(posRecv==posSend);
00165 }
00166 
00167 TEST(JointTrajPt, equal)
00168 {
00169   JointTrajPt lhs, rhs;
00170   JointData joint;
00171 
00172   joint.init();
00173   ASSERT_TRUE(joint.setJoint(0, 1.0));
00174   ASSERT_TRUE(joint.setJoint(1, 2.0));
00175   ASSERT_TRUE(joint.setJoint(2, 3.0));
00176   ASSERT_TRUE(joint.setJoint(3, 4.0));
00177   ASSERT_TRUE(joint.setJoint(4, 5.0));
00178   ASSERT_TRUE(joint.setJoint(5, 6.0));
00179   ASSERT_TRUE(joint.setJoint(6, 7.0));
00180   ASSERT_TRUE(joint.setJoint(7, 8.0));
00181   ASSERT_TRUE(joint.setJoint(8, 9.0));
00182   ASSERT_TRUE(joint.setJoint(9, 10.0));
00183 
00184   rhs.init(1.0, joint, 50.0, 100);
00185   EXPECT_FALSE(lhs==rhs);
00186 
00187   lhs.init(0, joint, 0, 0);
00188   EXPECT_FALSE(lhs==rhs);
00189 
00190   lhs.copyFrom(rhs);
00191   EXPECT_TRUE(lhs==rhs);
00192 
00193 }
00194 
00195 TEST(JointTrajPt, toMessage)
00196 {
00197   JointTrajPt toMessage, fromMessage;
00198   JointTrajPtMessage msg;
00199 
00200   toMessage.init();
00201   toMessage.setSequence(99);
00202   msg.init(toMessage);
00203 
00204   fromMessage.copyFrom(msg.point_);
00205 
00206   EXPECT_TRUE(toMessage==fromMessage);
00207 
00208 }
00209 
00210 TEST(JointTrajPt, Comms)
00211 {
00212 
00213   JointTrajPtMessage jointSend, jointRecv;
00214   JointData data;
00215   JointTrajPt posSend, posRecv;
00216 
00217   data.init();
00218   data.setJoint(0, 1.0);
00219   data.setJoint(1, 2.0);
00220   data.setJoint(2, 3.0);
00221   data.setJoint(3, 4.0);
00222   data.setJoint(4, 5.0);
00223   data.setJoint(5, 6.0);
00224   data.setJoint(6, 7.0);
00225   data.setJoint(7, 8.0);
00226   data.setJoint(8, 9.0);
00227   data.setJoint(9, 10.0);
00228   posSend.init(1, data, 99, 100);
00229 
00230   jointSend.init(posSend);
00231 
00232   messagePassing(jointSend, jointRecv);
00233 
00234   posRecv.copyFrom(jointRecv.point_);
00235   ASSERT_TRUE(posRecv==posSend);
00236 }
00237 
00238 TEST(JointTraj, equal)
00239 {
00240   JointTraj lhs, rhs;
00241   JointData joint;
00242   JointTrajPt point;
00243 
00244   joint.init();
00245   ASSERT_TRUE(joint.setJoint(0, 1.0));
00246   ASSERT_TRUE(joint.setJoint(1, 2.0));
00247   ASSERT_TRUE(joint.setJoint(2, 3.0));
00248   ASSERT_TRUE(joint.setJoint(3, 4.0));
00249   ASSERT_TRUE(joint.setJoint(4, 5.0));
00250   ASSERT_TRUE(joint.setJoint(5, 6.0));
00251   ASSERT_TRUE(joint.setJoint(6, 7.0));
00252   ASSERT_TRUE(joint.setJoint(7, 8.0));
00253   ASSERT_TRUE(joint.setJoint(8, 9.0));
00254   ASSERT_TRUE(joint.setJoint(9, 10.0));
00255 
00256   point.init(1.0, joint, 50.0, 100);
00257   rhs.addPoint(point);
00258   EXPECT_FALSE(lhs==rhs);
00259 
00260   lhs.addPoint(point);
00261   EXPECT_TRUE(lhs==rhs);
00262 
00263   lhs.addPoint(point);
00264   EXPECT_FALSE(lhs==rhs);
00265 
00266   lhs.copyFrom(rhs);
00267   EXPECT_TRUE(lhs==rhs);
00268 
00269 }
00270 
00271 TEST(RobotStatus, enumerations)
00272 {
00273   // Verifying the disabled state and aliases match
00274   EXPECT_EQ(TriStates::TS_DISABLED, TriStates::TS_FALSE);
00275   EXPECT_EQ(TriStates::TS_DISABLED, TriStates::TS_LOW);
00276   EXPECT_EQ(TriStates::TS_DISABLED, TriStates::TS_OFF);
00277 
00278   // Verifying the enabled state and aliases values match
00279   EXPECT_EQ(TriStates::TS_ENABLED, TriStates::TS_TRUE);
00280   EXPECT_EQ(TriStates::TS_ENABLED, TriStates::TS_HIGH);
00281   EXPECT_EQ(TriStates::TS_ENABLED, TriStates::TS_ON);
00282 
00283   // Verifying the unknown values match (this isn't reqd, but makes sense)
00284   EXPECT_EQ(TriStates::TS_UNKNOWN, RobotModes::UNKNOWN);
00285 }
00286 
00287 TEST(RobotStatus, init)
00288 {
00289   RobotStatus status;
00290   RobotStatus empty;
00291   status.init();
00292   // An empty (non-initted) status should be initialized in the constructor.
00293   EXPECT_TRUE(status==empty);
00294   EXPECT_EQ(status.getDrivesPowered(), TriStates::TS_UNKNOWN);
00295   EXPECT_EQ(status.getEStopped(), TriStates::TS_UNKNOWN);
00296   EXPECT_EQ(status.getErrorCode(), 0);
00297   EXPECT_EQ(status.getInError(), TriStates::TS_UNKNOWN);
00298   EXPECT_EQ(status.getInMotion(), TriStates::TS_UNKNOWN);
00299   EXPECT_EQ(status.getMode(), RobotModes::UNKNOWN);
00300   EXPECT_EQ(status.getMotionPossible(), TriStates::TS_UNKNOWN);
00301 }
00302 
00303 TEST(RobotStatus, equal)
00304 {
00305   RobotStatus lhs, rhs;
00306 
00307   EXPECT_TRUE(lhs==rhs);
00308   lhs.setDrivesPowered(TriStates::TS_ENABLED);
00309   EXPECT_FALSE(lhs==rhs);
00310   rhs.setDrivesPowered(TriStates::TS_ENABLED);
00311   EXPECT_TRUE(lhs==rhs);
00312 
00313   lhs.setEStopped(TriStates::TS_ENABLED);
00314   EXPECT_FALSE(lhs==rhs);
00315   rhs.setEStopped(TriStates::TS_ENABLED);
00316   EXPECT_TRUE(lhs==rhs);
00317 
00318   lhs.setErrorCode(99);
00319   EXPECT_FALSE(lhs==rhs);
00320   rhs.setErrorCode(99);
00321   EXPECT_TRUE(lhs==rhs);
00322 
00323   lhs.setInError(TriStates::TS_ENABLED);
00324   EXPECT_FALSE(lhs==rhs);
00325   rhs.setInError(TriStates::TS_ENABLED);
00326   EXPECT_TRUE(lhs==rhs);
00327 
00328   lhs.setInMotion(TriStates::TS_ENABLED);
00329   EXPECT_FALSE(lhs==rhs);
00330   rhs.setInMotion(TriStates::TS_ENABLED);
00331   EXPECT_TRUE(lhs==rhs);
00332 
00333   lhs.setMode(RobotModes::AUTO);
00334   EXPECT_FALSE(lhs==rhs);
00335   rhs.setMode(RobotModes::AUTO);
00336   EXPECT_TRUE(lhs==rhs);
00337 
00338   lhs.setMotionPossible(TriStates::TS_ENABLED);
00339   EXPECT_FALSE(lhs==rhs);
00340   rhs.setMotionPossible(TriStates::TS_ENABLED);
00341   EXPECT_TRUE(lhs==rhs);
00342 
00343 }
00344 
00345 TEST(RobotStatus, toMessage)
00346 {
00347   RobotStatus toMessage, fromMessage;
00348   RobotStatusMessage msg;
00349 
00350   toMessage.init(TriStates::TS_ENABLED, TriStates::TS_FALSE, 99, TriStates::TS_TRUE, TriStates::TS_TRUE, RobotModes::MANUAL,
00351                  TriStates::TS_DISABLED);
00352   msg.init(toMessage);
00353 
00354   fromMessage.copyFrom(msg.status_);
00355 
00356   EXPECT_TRUE(toMessage==fromMessage);
00357 
00358 }
00359 
00360 TEST(RobotStatus, Comms)
00361 {
00362   RobotStatusMessage statusMsgSend, statusMsgRecv;
00363   RobotStatus statusSend, statusRecv;
00364 
00365   statusSend.init(TriStates::TS_ENABLED, TriStates::TS_FALSE, 99, TriStates::TS_TRUE, TriStates::TS_TRUE, RobotModes::MANUAL,
00366                    TriStates::TS_DISABLED);
00367 
00368   statusMsgSend.init(statusSend);
00369 
00370   messagePassing(statusMsgSend, statusMsgRecv);
00371 
00372   statusRecv.copyFrom(statusMsgRecv.status_);
00373   ASSERT_TRUE(statusRecv==statusSend);
00374 }
00375 


simple_message
Author(s): Shaun Edwards
autogenerated on Fri Aug 28 2015 11:11:57