Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "stdlib.h"
00031 #include "ros/ros.h"
00032 #include "sensor_msgs/Image.h"
00033 #include "sensor_msgs/image_encodings.h"
00034 #include "math.h"
00035 #include "image_transport/image_transport.h"
00036
00037 int main( int argc, char **argv )
00038 {
00039 ros::init( argc, argv, "send_images" );
00040
00041 ros::NodeHandle nh;
00042 image_transport::ImageTransport it( nh );
00043 image_transport::Publisher pub = it.advertise("images", 100);
00044 ros::Rate loop_rate( 100 );
00045
00046 sensor_msgs::Image msg;
00047 int width = 100;
00048 int height = 1000;
00049 msg.data.resize( width * height * 3 );
00050 msg.header.frame_id = "base_link";
00051 msg.height = height;
00052 msg.width = width;
00053 msg.encoding = sensor_msgs::image_encodings::RGB8;
00054 msg.step = width * 3;
00055
00056 int count = 0;
00057 while( ros::ok() )
00058 {
00059 for( int x = 0; x < width; x++ )
00060 {
00061 for( int y = 0; y < height; y++ )
00062 {
00063 int index = (x + y * width) * 3;
00064 long int rand = random();
00065 msg.data[ index ] = rand & 0xff;
00066 index++;
00067 msg.data[ index ] = (rand >> 8) & 0xff;
00068 index++;
00069 msg.data[ index ] = (rand >> 16) & 0xff;
00070 }
00071 }
00072 msg.header.seq = count;
00073 msg.header.stamp = ros::Time::now();
00074
00075 pub.publish( msg );
00076
00077 ros::spinOnce();
00078 loop_rate.sleep();
00079 ++count;
00080 }
00081 }