shm_talker.cpp
Go to the documentation of this file.
00001 #include "ros/ros.h"
00002 #include "std_msgs/String.h"
00003 #include <sstream>
00004 #include "shm_transport/shm_topic.hpp"
00005 
00006 #define MSGLEN (1920 * 1080 * 3)
00007 #define HZ (30)
00008 
00009 std::string str(MSGLEN, '-');
00010 char tmp[100];
00011 
00012 int main(int argc, char ** argv) {
00013   ros::init(argc, argv, "shm_talker", ros::init_options::AnonymousName);
00014   ros::NodeHandle n;
00015   shm_transport::Topic t(n);
00016   shm_transport::Publisher p = t.advertise< std_msgs::String >("shm_test_topic", HZ, 3 * MSGLEN);
00017 
00018   ros::Rate loop_rate(HZ);
00019   int count = 0;
00020   while (ros::ok()) {
00021     int len = snprintf(tmp, 100, "message # %d ...", count);
00022     memcpy(&str[0], tmp, len);
00023 
00024     std_msgs::String msg;
00025     msg.data = str;
00026 
00027     ROS_INFO("info: [%s]", tmp);
00028     p.publish(msg);
00029 
00030     ros::spinOnce();
00031     loop_rate.sleep();
00032     count++;
00033   }
00034   return 0;
00035 }
00036 


shm_transport
Author(s): Jrdevil-Wang , Wende Tan
autogenerated on Thu Jun 6 2019 18:47:43