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
00033
00034
00035
00036
00037 #include <gtest/gtest.h>
00038 #include "ros/ros.h"
00039 #include "std_msgs/String.h"
00040
00041 #include <vector>
00042
00047 void chatterCallback(const std_msgs::String::ConstPtr& msg)
00048 {
00049 ROS_INFO("I heard: [%s]", msg->data.c_str());
00050 }
00051
00052 void chatterCallback2(const std_msgs::String& msg)
00053 {
00054 ROS_INFO("I heard(2): [%s]", msg.data.c_str());
00055 }
00056
00057 void chatterCallback3(std_msgs::String::ConstPtr msg)
00058 {
00059 ROS_INFO("I heard(3): [%s]", msg->data.c_str());
00060 }
00061
00062 void chatterCallback4(const ros::MessageEvent<std_msgs::String const>& event)
00063 {
00064 ROS_INFO("I heard(4): [%s, %s]", event.getMessage()->data.c_str(), event.getConnectionHeader()["callerid"].c_str());
00065 }
00066
00067 void chatterCallback5(std_msgs::String msg)
00068 {
00069 ROS_INFO("I heard(5): [%s]", msg.data.c_str());
00070 }
00071
00072 void chatterCallback6(const std_msgs::String::Ptr& msg)
00073 {
00074 ROS_INFO("I heard(6): [%s]", msg->data.c_str());
00075 }
00076
00077 void chatterCallback7(std_msgs::String::Ptr msg)
00078 {
00079 ROS_INFO("I heard(7): [%s]", msg->data.c_str());
00080 }
00081
00082 void chatterCallback8(const ros::MessageEvent<std_msgs::String>& event)
00083 {
00084 ROS_INFO("I heard(8): [%s, %s]", event.getMessage()->data.c_str(), event.getConnectionHeader()["callerid"].c_str());
00085 }
00086
00087 struct A
00088 {
00089 void chatterCallback(const std_msgs::String::ConstPtr& msg)
00090 {
00091 ROS_INFO("A I heard: [%s]", msg->data.c_str());
00092 }
00093
00094 void chatterCallback2(const std_msgs::String& msg)
00095 {
00096 ROS_INFO("A I heard(2): [%s]", msg.data.c_str());
00097 }
00098
00099 void chatterCallback3(std_msgs::String::ConstPtr msg)
00100 {
00101 ROS_INFO("A I heard(3): [%s]", msg->data.c_str());
00102 }
00103
00104 void chatterCallback4(const ros::MessageEvent<std_msgs::String const>& event)
00105 {
00106 ROS_INFO("A I heard(4): [%s]", event.getMessage()->data.c_str());
00107 }
00108
00109 void chatterCallback5(std_msgs::String msg)
00110 {
00111 ROS_INFO("A I heard(5): [%s]", msg.data.c_str());
00112 }
00113
00114 void chatterCallback6(const std_msgs::String::ConstPtr& msg, const std::string& bound)
00115 {
00116 ROS_INFO("A I heard(6): [%s, %s]", msg->data.c_str(), bound.c_str());
00117 }
00118
00119 void chatterCallback7(const std_msgs::String& msg, const std::string& bound)
00120 {
00121 ROS_INFO("A I heard(7): [%s, %s]", msg.data.c_str(), bound.c_str());
00122 }
00123
00124 void chatterCallback8(const std_msgs::String::Ptr& msg)
00125 {
00126 ROS_INFO("A I heard(6): [%s]", msg->data.c_str());
00127 }
00128
00129 void chatterCallback9(std_msgs::String::Ptr msg)
00130 {
00131 ROS_INFO("A I heard(7): [%s]", msg->data.c_str());
00132 }
00133
00134 void chatterCallback10(const ros::MessageEvent<std_msgs::String>& event)
00135 {
00136 ROS_INFO("A I heard(8): [%s, %s]", event.getMessage()->data.c_str(), event.getConnectionHeader()["callerid"].c_str());
00137 }
00138 };
00139
00140 TEST(SubscriptionCallbackTypes, compile)
00141 {
00142 ros::NodeHandle n;
00143
00144 std::vector<ros::Subscriber> subs;
00145 subs.push_back(n.subscribe("chatter", 1000, chatterCallback));
00146 subs.push_back(n.subscribe<std_msgs::String>("chatter", 1000, chatterCallback));
00147 #if 01
00148 subs.push_back(n.subscribe("chatter", 1000, chatterCallback2));
00149 subs.push_back(n.subscribe("chatter", 1000, chatterCallback3));
00150 subs.push_back(n.subscribe("chatter", 1000, chatterCallback4));
00151 subs.push_back(n.subscribe("chatter", 1000, chatterCallback5));
00152 subs.push_back(n.subscribe("chatter", 1000, chatterCallback6));
00153 subs.push_back(n.subscribe("chatter", 1000, chatterCallback7));
00154 subs.push_back(n.subscribe("chatter", 1000, chatterCallback8));
00155 #endif
00156
00157 A a;
00158 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback, &a));
00159 subs.push_back(n.subscribe<std_msgs::String>("chatter", 1000, &A::chatterCallback, &a));
00160 #if 01
00161 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback2, &a));
00162 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback3, &a));
00163 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback4, &a));
00164 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback5, &a));
00165 #endif
00166
00167 #if 01
00168 subs.push_back(n.subscribe<std_msgs::String>("chatter", 1000, boost::bind(&A::chatterCallback6, &a, _1, std::string("hello"))));
00169 subs.push_back(n.subscribe<std_msgs::String, const std_msgs::String&>("chatter", 1000, boost::bind(&A::chatterCallback7, &a, _1, std::string("hello2"))));
00170 #endif
00171
00172 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback8, &a));
00173 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback9, &a));
00174 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback10, &a));
00175 }
00176
00177 int main(int argc, char **argv)
00178 {
00179 testing::InitGoogleTest(&argc, argv);
00180
00181 ros::init( argc, argv, "subscription_callback_types" );
00182 ros::NodeHandle nh;
00183
00184 return RUN_ALL_TESTS();
00185 }