00001 #include "ros/ros.h" 00002 #include "std_msgs/String.h" 00003 #include "shm_transport/shm_topic.hpp" 00004 00005 void chatterCallback(const std_msgs::String::ConstPtr & msg) { 00006 char str[21] = {'\0'}; 00007 strncpy(str, msg->data.c_str(), 20); 00008 ROS_INFO("I heard: [%s]", str); 00009 } 00010 00011 int main(int argc, char ** argv) { 00012 ros::init(argc, argv, "shm_listener", ros::init_options::AnonymousName); 00013 ros::NodeHandle n; 00014 shm_transport::Topic t(n); 00015 shm_transport::Subscriber< std_msgs::String > s = t.subscribe("shm_test_topic", 60, chatterCallback); 00016 ros::spin(); 00017 return 0; 00018 } 00019