$search
00001 #include <ros/ros.h> 00002 #include <roscpp/SetLoggerLevel.h> 00003 #include <message_transport/message_transport.h> 00004 #include <std_msgs/String.h> 00005 00006 std::string transport; 00007 unsigned int npoints = 0; 00008 00009 void callback(const std_msgs::StringConstPtr& text) 00010 { 00011 double tnow = ros::Time::now().toSec(); 00012 00013 00014 ROS_INFO("%d: Text '%s' received at %f", 00015 getpid(),text->data.c_str(),tnow); 00016 00017 } 00018 00019 void setDebugLevel(const std::string & logname) { 00020 log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(logname); 00021 logger->setLevel(log4cxx::Level::getDebug()); 00022 ros::console::notifyLoggerLevelsChanged(); 00023 } 00024 00025 00026 int main(int argc, char** argv) 00027 { 00028 ros::init(argc, argv, "test_receiver", ros::init_options::AnonymousName); 00029 ros::NodeHandle nh; 00030 00031 message_transport::MessageTransport<std_msgs::String> 00032 it(nh,"string_transport","std_msgs::String"); 00033 std::string pkgname("string_transport"); 00034 transport = std::string((argc > 1) ? argv[1] : "string_transport/raw_str"); 00035 if (transport.compare(0,pkgname.length(),pkgname)) { 00036 transport = pkgname + "/" + transport; 00037 } 00038 message_transport::Subscriber sub = it.subscribe("str_source", 1, callback, 00039 transport); 00040 ROS_INFO("test_receiver started"); 00041 00042 ros::spin(); 00043 } 00044