Go to the documentation of this file.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
00029
00030
00031
00032
00033
00034
00035
00036 #include <string>
00037
00038 #include <gtest/gtest.h>
00039
00040 #include <stdlib.h>
00041
00042 #include "ros/ros.h"
00043
00044 uint32_t g_msg_constructor = 0;
00045 uint32_t g_msg2_constructor = 0;
00046
00047 struct Msg
00048 {
00049 Msg()
00050 : serialized(false)
00051 , deserialized(false)
00052 {
00053 ++g_msg_constructor;
00054 }
00055
00056 mutable bool serialized;
00057 bool deserialized;
00058 };
00059 typedef boost::shared_ptr<Msg const> MsgConstPtr;
00060
00061 namespace ros
00062 {
00063 namespace message_traits
00064 {
00065 template<>
00066 struct MD5Sum<Msg>
00067 {
00068 static const char* value() { return "MsgMD5Sum"; }
00069 static const char* value(const Msg&) { return "MsgMD5Sum"; }
00070 };
00071
00072 template<>
00073 struct DataType<Msg>
00074 {
00075 static const char* value() { return "roscpp/MsgDataType"; }
00076 static const char* value(const Msg&) { return "roscpp/MsgDataType"; }
00077 };
00078
00079 template<>
00080 struct Definition<Msg>
00081 {
00082 static const char* value() { return ""; }
00083 static const char* value(const Msg&) { return ""; }
00084 };
00085 }
00086
00087 namespace serialization
00088 {
00089 template<>
00090 struct Serializer<Msg>
00091 {
00092 template<typename Stream>
00093 inline static void write(Stream&, const Msg& v)
00094 {
00095 v.serialized = true;
00096 }
00097
00098 template<typename Stream>
00099 inline static void read(Stream&, Msg& v)
00100 {
00101 v.deserialized = true;
00102 }
00103
00104 inline static uint32_t serializedLength(const Msg&)
00105 {
00106 return 0;
00107 }
00108 };
00109 }
00110 }
00111
00112 MsgConstPtr g_msg;
00113
00114 struct Msg2
00115 {
00116 Msg2()
00117 : serialized(false)
00118 , deserialized(false)
00119 {
00120 ++g_msg2_constructor;
00121 }
00122
00123 mutable bool serialized;
00124 bool deserialized;
00125 };
00126 typedef boost::shared_ptr<Msg2 const> Msg2ConstPtr;
00127
00128 namespace ros
00129 {
00130 namespace message_traits
00131 {
00132 template<>
00133 struct MD5Sum<Msg2>
00134 {
00135 static const char* value() { return "MsgMD5Sum"; }
00136 static const char* value(const Msg2&) { return "MsgMD5Sum"; }
00137 };
00138
00139 template<>
00140 struct DataType<Msg2>
00141 {
00142 static const char* value() { return "roscpp/MsgDataType"; }
00143 static const char* value(const Msg2&) { return "roscpp/MsgDataType"; }
00144 };
00145
00146 template<>
00147 struct Definition<Msg2>
00148 {
00149 static const char* value() { return ""; }
00150 static const char* value(const Msg2&) { return ""; }
00151 };
00152 }
00153
00154 namespace serialization
00155 {
00156 template<>
00157 struct Serializer<Msg2>
00158 {
00159 template<typename Stream>
00160 inline static void write(Stream&, const Msg2& v)
00161 {
00162 v.serialized = true;
00163 }
00164
00165 template<typename Stream>
00166 inline static void read(Stream&, Msg2& v)
00167 {
00168 v.deserialized = true;
00169 }
00170
00171 inline static uint32_t serializedLength(const Msg2&)
00172 {
00173 return 0;
00174 }
00175 };
00176 }
00177 }
00178
00179 void messageCallback(const MsgConstPtr& msg)
00180 {
00181 g_msg = msg;
00182 }
00183
00184 TEST(IntraprocessSubscriptions, noCopy)
00185 {
00186 g_msg.reset();
00187 g_msg_constructor = 0;
00188
00189 ros::NodeHandle nh;
00190 ros::Subscriber sub = nh.subscribe("test", 0, messageCallback);
00191 ros::Publisher pub = nh.advertise<Msg>("test", 0);
00192
00193 MsgConstPtr msg(boost::make_shared<Msg>());
00194
00195 while (pub.getNumSubscribers() == 0)
00196 {
00197 ros::Duration(0.01).sleep();
00198 }
00199
00200 pub.publish(msg);
00201
00202 while (!g_msg)
00203 {
00204 ros::spinOnce();
00205 ros::Duration(0.01).sleep();
00206 }
00207
00208 ASSERT_TRUE(g_msg);
00209 EXPECT_EQ(g_msg.get(), msg.get());
00210 EXPECT_FALSE(g_msg->serialized);
00211 EXPECT_FALSE(g_msg->deserialized);
00212 EXPECT_EQ(g_msg_constructor, 1ULL);
00213 }
00214
00215 TEST(IntraprocessSubscriptions, differentRTTI)
00216 {
00217 g_msg_constructor = 0;
00218 g_msg.reset();
00219
00220 ros::NodeHandle nh;
00221 ros::Subscriber sub = nh.subscribe("test", 0, messageCallback);
00222 ros::Publisher pub = nh.advertise<Msg2>("test", 0);
00223
00224 Msg2ConstPtr msg(boost::make_shared<Msg2>());
00225
00226 while (pub.getNumSubscribers() == 0)
00227 {
00228 ros::Duration(0.01).sleep();
00229 }
00230
00231 pub.publish(msg);
00232
00233 while (!g_msg)
00234 {
00235 ros::spinOnce();
00236 ros::Duration(0.01).sleep();
00237 }
00238
00239 ASSERT_TRUE(g_msg);
00240 EXPECT_NE((void*)g_msg.get(), (void*)msg.get());
00241 EXPECT_TRUE(msg->serialized);
00242 EXPECT_TRUE(g_msg->deserialized);
00243 EXPECT_EQ(g_msg_constructor, 1ULL);
00244 EXPECT_EQ(g_msg2_constructor, 1ULL);
00245 }
00246
00247 Msg2ConstPtr g_msg2;
00248 void messageCallback2(const Msg2ConstPtr& msg)
00249 {
00250 g_msg2 = msg;
00251 }
00252
00253 TEST(IntraprocessSubscriptions, noCopyAndDifferentRTTI)
00254 {
00255 g_msg.reset();
00256
00257 ros::NodeHandle nh;
00258 ros::Subscriber sub1 = nh.subscribe("test", 0, messageCallback);
00259 ros::Subscriber sub2 = nh.subscribe("test", 0, messageCallback2);
00260 ros::Publisher pub = nh.advertise<Msg2>("test", 0);
00261
00262 Msg2ConstPtr msg(boost::make_shared<Msg2>());
00263
00264 while (pub.getNumSubscribers() == 0)
00265 {
00266 ros::Duration(0.01).sleep();
00267 }
00268
00269 pub.publish(msg);
00270
00271 while (!g_msg || !g_msg2)
00272 {
00273 ros::spinOnce();
00274 ros::Duration(0.01).sleep();
00275 }
00276
00277 ASSERT_TRUE(g_msg);
00278 EXPECT_NE((void*)g_msg.get(), (void*)msg.get());
00279 EXPECT_TRUE(msg->serialized);
00280 EXPECT_TRUE(g_msg->deserialized);
00281
00282 ASSERT_TRUE(g_msg2);
00283 EXPECT_EQ(g_msg2.get(), msg.get());
00284 EXPECT_TRUE(g_msg2->serialized);
00285 EXPECT_FALSE(g_msg2->deserialized);
00286 }
00287
00288 int main(int argc, char** argv)
00289 {
00290 testing::InitGoogleTest(&argc, argv);
00291 ros::init(argc, argv, "intraprocess_subscriptions");
00292
00293 ros::NodeHandle nh;
00294
00295 return RUN_ALL_TESTS();
00296 }
00297