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 #include "ros/ros.h"
00029 #include "std_msgs/String.h"
00030 #include "std_msgs/Int16.h"
00031 #include "test_roslisp/ComplexMessage.h"
00032 #include <gtest/gtest.h>
00033 #include <ros/time.h>
00034 #include <ros/console.h>
00035
00036 using std::vector;
00037
00038 int num_messages_received=0;
00039 int service_client_status=0;
00040 int service_client_response=0;
00041
00042 using test_roslisp::ComplexMessage;
00043 using test_roslisp::Foo;
00044 using test_roslisp::Bar;
00045
00046 inline bool operator== (const Bar& b, const Bar& b2)
00047 {
00048 return ((b.y == b2.y) && (b.x==b2.x));
00049 }
00050
00051 inline bool operator== (const Foo& f, const Foo& f2)
00052 {
00053 return ((f.y==f2.y) && (f.z[0]==f2.z[0]) && (f.z[1]==f2.z[1]));
00054 }
00055
00056 inline
00057 bool operator== (const ComplexMessage& c, const ComplexMessage& c2)
00058 {
00059 unsigned i=0;
00060
00061 if (c.ind != c2.ind)
00062 return false;
00063
00064 for ( i=0; i<4; i++)
00065 if (!(c.x[i] == c2.x[i]))
00066 return false;
00067
00068 for ( i=0; i<c.y.size(); i++)
00069 if (!(c.y[i] == c2.y[i]))
00070 return false;
00071
00072 for ( i=0; i<c2.z.size(); i++)
00073 if (!(c.z[i] == c2.z[i]))
00074 return false;
00075
00076 for ( i=0; i<c.w.size(); i++)
00077 if (!(c.w[i].data == c2.w[i].data))
00078 return false;
00079
00080 if (c.qux != c2.qux)
00081 {
00082 ROS_INFO ("Qux 1 is %u and qux 2 is %u", c.qux, c2.qux);
00083 return false;
00084 }
00085
00086 return true;
00087 }
00088
00089 class ComplexTester
00090 {
00091 public:
00092 ComplexTester() : ok_(true), num_received_(0)
00093 {
00094 ping_sub_ = nh_.subscribe("ping", 1000, &ComplexTester::pingCallback, this);
00095 pong_pub_ = nh_.advertise<ComplexMessage>("pong", 1000);
00096 pang_sub_ = nh_.subscribe("pang", 1000, &ComplexTester::pangCallback, this);
00097 ros::Duration d(3);
00098 d.sleep();
00099 ping_vec_.resize(8);
00100 }
00101
00102 void pingCallback (const test_roslisp::ComplexMessage::ConstPtr& msg)
00103 {
00104 ping_vec_[msg->ind] = *msg;
00105 pong_pub_.publish(*msg);
00106 }
00107
00108 void pangCallback (const test_roslisp::ComplexMessage::ConstPtr& msg)
00109 {
00110 ok_ &= (ping_vec_[msg->ind] == *msg);
00111 num_received_++;
00112 }
00113
00114 bool done()
00115 {
00116 return (num_received_ >= 10);
00117 }
00118
00119 bool isOk()
00120 {
00121 return ok_;
00122 }
00123
00124 private:
00125
00126 vector<ComplexMessage> ping_vec_;
00127 bool ok_;
00128 unsigned num_received_;
00129 ros::Subscriber pang_sub_, ping_sub_;
00130 ros::Publisher pong_pub_;
00131 ros::NodeHandle nh_;
00132 };
00133
00134
00135
00136
00137 TEST(Roslisp, ComplexTalkerListener)
00138 {
00139 ros::Duration d(1);
00140 unsigned wait_max = 180;
00141
00142 ComplexTester t;
00143
00144 for (unsigned i=0; (i<wait_max) && (!t.done()); i++) {
00145 d.sleep();
00146 ros::spinOnce();
00147 }
00148
00149 EXPECT_TRUE(t.done());
00150 EXPECT_TRUE(t.isOk());
00151 }
00152
00153
00154
00159 void chatterCallback(const std_msgs::StringConstPtr& msg)
00160 {
00161 num_messages_received++;
00162 }
00163
00164
00165 TEST(Roslisp, TalkerListener)
00166 {
00167 ros::NodeHandle n;
00168 ros::Subscriber sub = n.subscribe("chatter_echo", 1000, chatterCallback);
00169 ros::Duration d(1);
00170
00171 int wait_max=180;
00172
00173 for (int i=0; i<wait_max && n.ok(); i++) {
00174 d.sleep();
00175 ros::spinOnce();
00176 ROS_INFO_STREAM ("Have waited " << i << " out of " << wait_max << " seconds to receive 5 messages from chatter_echo");
00177 if (num_messages_received>5)
00178 break;
00179 }
00180 EXPECT_TRUE(num_messages_received>5);
00181 ROS_INFO_STREAM ("Successfully received " << num_messages_received << " echoed messages");
00182 }
00183
00184 void clientStatusCallback (const std_msgs::Int16ConstPtr& msg)
00185 {
00186 service_client_response = msg->data;
00187 service_client_status = 1;
00188 }
00189
00190 TEST(Roslisp, Service)
00191 {
00192 ros::NodeHandle n;
00193 ros::Subscriber sub=n.subscribe("client_status", 1000, clientStatusCallback);
00194 ros::Duration d(1);
00195 unsigned wait_max=180;
00196 for (unsigned i=0; i<wait_max && n.ok(); i++) {
00197 d.sleep();
00198 ros::spinOnce();
00199 ROS_INFO_STREAM ("Have waited " << i << " out of " << wait_max << " seconds to receive confirmation from service client test");
00200 if (service_client_status)
00201 break;
00202 }
00203
00204 EXPECT_EQ (66, service_client_response);
00205 }
00206
00207
00208
00209 int main(int argc, char **argv)
00210 {
00211 testing::InitGoogleTest(&argc, argv);
00212 ros::init(argc, argv, "roslisp-tester");
00213 return RUN_ALL_TESTS();
00214 }