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 #include "test_roscpp/TestEmpty.h"
00045
00046
00047 struct ConstHelper
00048 {
00049 void callback(const test_roscpp::TestEmptyConstPtr& msg)
00050 {
00051 message_ = msg;
00052 }
00053
00054 test_roscpp::TestEmptyConstPtr message_;
00055 };
00056
00057 struct NonConstHelper
00058 {
00059 void callback(const test_roscpp::TestEmptyPtr& msg)
00060 {
00061 message_ = msg;
00062 }
00063
00064 test_roscpp::TestEmptyPtr message_;
00065 };
00066
00067 TEST(NonConstSubscriptions, oneNonConstSubscriber)
00068 {
00069 NonConstHelper h;
00070 ros::NodeHandle nh;
00071 ros::Subscriber sub = nh.subscribe("test", 0, &NonConstHelper::callback, &h);
00072 ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test", 0);
00073
00074 test_roscpp::TestEmptyPtr msg(new test_roscpp::TestEmpty);
00075 pub.publish(msg);
00076 ros::spinOnce();
00077
00078 ASSERT_TRUE(h.message_);
00079 EXPECT_EQ(h.message_, msg);
00080 }
00081
00082 TEST(NonConstSubscriptions, oneConstOneNonConst)
00083 {
00084 NonConstHelper h;
00085 ConstHelper h2;
00086 ros::NodeHandle nh;
00087 ros::Subscriber sub = nh.subscribe("test", 0, &NonConstHelper::callback, &h);
00088 ros::Subscriber sub2 = nh.subscribe("test", 0, &ConstHelper::callback, &h2);
00089 ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test", 0);
00090
00091 test_roscpp::TestEmptyPtr msg(new test_roscpp::TestEmpty);
00092 pub.publish(msg);
00093 ros::spinOnce();
00094
00095 ASSERT_TRUE(h.message_);
00096 EXPECT_NE(h.message_, msg);
00097 EXPECT_EQ(h2.message_, msg);
00098 }
00099
00100 TEST(NonConstSubscriptions, twoNonConst)
00101 {
00102 NonConstHelper h;
00103 NonConstHelper h2;
00104 ros::NodeHandle nh;
00105 ros::Subscriber sub = nh.subscribe("test", 0, &NonConstHelper::callback, &h);
00106 ros::Subscriber sub2 = nh.subscribe("test", 0, &NonConstHelper::callback, &h2);
00107 ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test", 0);
00108
00109 test_roscpp::TestEmptyPtr msg(new test_roscpp::TestEmpty);
00110 pub.publish(msg);
00111 ros::spinOnce();
00112
00113 ASSERT_TRUE(h.message_);
00114 EXPECT_NE(h.message_, msg);
00115 }
00116
00117 TEST(NonConstSubscriptions, twoConst)
00118 {
00119 ConstHelper h;
00120 ConstHelper h2;
00121 ros::NodeHandle nh;
00122 ros::Subscriber sub = nh.subscribe("test", 0, &ConstHelper::callback, &h);
00123 ros::Subscriber sub2 = nh.subscribe("test", 0, &ConstHelper::callback, &h2);
00124 ros::Publisher pub = nh.advertise<test_roscpp::TestEmpty>("test", 0);
00125
00126 test_roscpp::TestEmptyPtr msg(new test_roscpp::TestEmpty);
00127 pub.publish(msg);
00128 ros::spinOnce();
00129
00130 ASSERT_TRUE(h.message_);
00131 EXPECT_EQ(h.message_, msg);
00132 EXPECT_EQ(h2.message_, msg);
00133 }
00134
00135 int main(int argc, char** argv)
00136 {
00137 testing::InitGoogleTest(&argc, argv);
00138 ros::init(argc, argv, "intraprocess_subscriptions");
00139
00140 ros::NodeHandle nh;
00141
00142 return RUN_ALL_TESTS();
00143 }
00144