$search
00001 00002 /* 00003 * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * * Redistributions of source code must retain the above copyright notice, 00008 * this list of conditions and the following disclaimer. 00009 * * Redistributions in binary form must reproduce the above copyright 00010 * notice, this list of conditions and the following disclaimer in the 00011 * documentation and/or other materials provided with the distribution. 00012 * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its 00013 * contributors may be used to endorse or promote products derived from 00014 * this software without specific prior written permission. 00015 * 00016 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00017 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00018 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00019 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00020 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00021 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00022 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00023 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00024 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00025 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00026 * POSSIBILITY OF SUCH DAMAGE. 00027 */ 00028 00033 /* 00034 * Test compilation of all the different subscription callback types 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 void constCallback(std_msgs::String::Ptr msg) const 00140 { 00141 ROS_INFO("A I heard(7): [%s] and I'm const", msg->data.c_str()); 00142 } 00143 00144 }; 00145 00146 TEST(SubscriptionCallbackTypes, compile) 00147 { 00148 ros::NodeHandle n; 00149 00150 std::vector<ros::Subscriber> subs; 00151 subs.push_back(n.subscribe("chatter", 1000, chatterCallback)); 00152 subs.push_back(n.subscribe<std_msgs::String>("chatter", 1000, chatterCallback)); 00153 subs.push_back(n.subscribe("chatter", 1000, chatterCallback2)); 00154 subs.push_back(n.subscribe("chatter", 1000, chatterCallback3)); 00155 subs.push_back(n.subscribe("chatter", 1000, chatterCallback4)); 00156 subs.push_back(n.subscribe("chatter", 1000, chatterCallback5)); 00157 subs.push_back(n.subscribe("chatter", 1000, chatterCallback6)); 00158 subs.push_back(n.subscribe("chatter", 1000, chatterCallback7)); 00159 subs.push_back(n.subscribe("chatter", 1000, chatterCallback8)); 00160 00161 00162 A a; 00163 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback, &a)); 00164 subs.push_back(n.subscribe<std_msgs::String>("chatter", 1000, &A::chatterCallback, &a)); 00165 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback2, &a)); 00166 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback3, &a)); 00167 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback4, &a)); 00168 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback5, &a)); 00169 00170 subs.push_back(n.subscribe<std_msgs::String>("chatter", 1000, boost::bind(&A::chatterCallback6, &a, _1, std::string("hello")))); 00171 subs.push_back(n.subscribe<std_msgs::String, const std_msgs::String&>("chatter", 1000, boost::bind(&A::chatterCallback7, &a, _1, std::string("hello2")))); 00172 00173 00174 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback8, &a)); 00175 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback9, &a)); 00176 subs.push_back(n.subscribe("chatter", 1000, &A::chatterCallback10, &a)); 00177 00178 subs.push_back(n.subscribe("chatter", 1000, &A::constCallback, &a)); 00179 } 00180 00181 int main(int argc, char **argv) 00182 { 00183 testing::InitGoogleTest(&argc, argv); 00184 00185 ros::init( argc, argv, "subscription_callback_types" ); 00186 ros::NodeHandle nh; 00187 00188 return RUN_ALL_TESTS(); 00189 }