38 #include "std_msgs/String.h" 39 #include "std_msgs/Int32.h" 42 #include <gtest/gtest.h> 53 std_msgs::Int32::Ptr
s = msg->instantiate<std_msgs::Int32>();
63 std_msgs::String::Ptr
s = msg->instantiate<std_msgs::String>();
64 if (s->data ==
"chatter")
75 std_msgs::String::Ptr
s = msg->instantiate<std_msgs::String>();
76 printf(
"Got data: %s", s->data.c_str());
77 if (s->data ==
"abc123")
81 printf(
"Instantiate failed!\n");
165 int main(
int argc,
char **argv){
166 ros::init(argc, argv,
"test_shapeshifter");
168 testing::InitGoogleTest(&argc, argv);
169 return RUN_ALL_TESTS();
void messageCallbackString(const topic_tools::ShapeShifter::ConstPtr &msg)
TEST_F(ShapeShifterSubscriber, testInstantiateString)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void messageCallbackLoopback(const topic_tools::ShapeShifter::ConstPtr &msg)
void messageCallbackInt(const topic_tools::ShapeShifter::ConstPtr &msg)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spinOnce()