Go to the documentation of this file.
37 #include <gtest/gtest.h>
39 #include "std_msgs/String.h"
49 ROS_INFO(
"I heard: [%s]", msg->data.c_str());
54 ROS_INFO(
"I heard(2): [%s]", msg.data.c_str());
59 ROS_INFO(
"I heard(3): [%s]", msg->data.c_str());
69 ROS_INFO(
"I heard(5): [%s]", msg.data.c_str());
74 ROS_INFO(
"I heard(6): [%s]", msg->data.c_str());
79 ROS_INFO(
"I heard(7): [%s]", msg->data.c_str());
91 ROS_INFO(
"A I heard: [%s]", msg->data.c_str());
96 ROS_INFO(
"A I heard(2): [%s]", msg.data.c_str());
101 ROS_INFO(
"A I heard(3): [%s]", msg->data.c_str());
111 ROS_INFO(
"A I heard(5): [%s]", msg.data.c_str());
116 ROS_INFO(
"A I heard(6): [%s, %s]", msg->data.c_str(), bound.c_str());
121 ROS_INFO(
"A I heard(7): [%s, %s]", msg.data.c_str(), bound.c_str());
126 ROS_INFO(
"A I heard(6): [%s]", msg->data.c_str());
131 ROS_INFO(
"A I heard(7): [%s]", msg->data.c_str());
141 ROS_INFO(
"A I heard(7): [%s] and I'm const", msg->data.c_str());
146 TEST(SubscriptionCallbackTypes, compile)
150 std::vector<ros::Subscriber> subs;
170 subs.push_back(n.
subscribe<std_msgs::String>(
"chatter", 1000, boost::bind(&
A::chatterCallback6, &a, boost::placeholders::_1, std::string(
"hello"))));
171 subs.push_back(n.
subscribe<std_msgs::String,
const std_msgs::String&>(
"chatter", 1000, boost::bind(&
A::chatterCallback7, &a, boost::placeholders::_1, std::string(
"hello2"))));
181 int main(
int argc,
char **argv)
183 testing::InitGoogleTest(&argc, argv);
185 ros::init( argc, argv,
"subscription_callback_types" );
188 return RUN_ALL_TESTS();
void chatterCallback3(std_msgs::String::ConstPtr msg)
void chatterCallback6(const std_msgs::String::ConstPtr &msg, const std::string &bound)
void chatterCallback10(const ros::MessageEvent< std_msgs::String > &event)
void chatterCallback(const std_msgs::String::ConstPtr &msg)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void chatterCallback4(const ros::MessageEvent< std_msgs::String const > &event)
void constCallback(std_msgs::String::Ptr msg) const
void chatterCallback5(std_msgs::String msg)
void chatterCallback3(std_msgs::String::ConstPtr msg)
void chatterCallback5(std_msgs::String msg)
int main(int argc, char **argv)
void chatterCallback4(const ros::MessageEvent< std_msgs::String const > &event)
void chatterCallback2(const std_msgs::String &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void chatterCallback7(const std_msgs::String &msg, const std::string &bound)
void chatterCallback2(const std_msgs::String &msg)
void chatterCallback(const std_msgs::String::ConstPtr &msg)
void chatterCallback6(const std_msgs::String::Ptr &msg)
TEST(SubscriptionCallbackTypes, compile)
void chatterCallback8(const std_msgs::String::Ptr &msg)
void chatterCallback9(std_msgs::String::Ptr msg)
void chatterCallback7(std_msgs::String::Ptr msg)
void chatterCallback8(const ros::MessageEvent< std_msgs::String > &event)
boost::shared_ptr< M > getMessage() const
M_string & getConnectionHeader() const
test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
, Jacob Perron
autogenerated on Thu Nov 23 2023 04:02:02