send_images.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <string>
00031 #include "stdlib.h"
00032 #include "ros/ros.h"
00033 #include "sensor_msgs/Image.h"
00034 #include "sensor_msgs/image_encodings.h"
00035 #include "math.h"
00036 #include "image_transport/image_transport.h"
00037 
00038 int main( int argc, char **argv )
00039 {
00040   ros::init( argc, argv, "send_images" );
00041 
00042   if( argc != 2 )
00043   {
00044     printf( "USAGE: %s <image_format>\n"
00045             "  Where <image_format> is rgb8, 32FC1, or 16UC1.",
00046             argv[ 0 ] );
00047     exit( 1 );
00048   }
00049   const std::string image_format( argv[ 1 ]);
00050 
00051   ros::NodeHandle nh;
00052   image_transport::ImageTransport it( nh );
00053   image_transport::Publisher pub = it.advertise("images", 100);
00054   ros::Rate loop_rate( 100 );
00055 
00056   if( image_format == "rgb8" )
00057   {
00058     sensor_msgs::Image msg;
00059     int width = 100;
00060     int height = 1000;
00061     msg.data.resize( width * height * 3 );
00062     msg.header.frame_id = "base_link";
00063     msg.height = height;
00064     msg.width = width;
00065     msg.encoding = image_format;
00066     msg.step = width * 3;
00067 
00068     int count = 0;
00069     while( ros::ok() )
00070     {
00071       for( int x = 0; x < width; x++ )
00072       {
00073         for( int y = 0; y < height; y++ )
00074         {
00075           int index = (x + y * width) * 3;
00076           long int rand = random();
00077           msg.data[ index ] = rand & 0xff;
00078           index++;
00079           msg.data[ index ] = (rand >> 8) & 0xff;
00080           index++;
00081           msg.data[ index ] = (rand >> 16) & 0xff;
00082         }
00083       }
00084       msg.header.seq = count;
00085       msg.header.stamp = ros::Time::now();
00086 
00087       pub.publish( msg );
00088 
00089       ros::spinOnce();
00090       loop_rate.sleep();
00091       ++count;
00092     }
00093   }
00094   else if( image_format == "32FC1" )
00095   {
00096     sensor_msgs::Image msg;
00097     int width = 400;
00098     int height = 400;
00099     msg.data.resize( width * height * sizeof( float ));
00100     msg.header.frame_id = "base_link";
00101     msg.height = height;
00102     msg.width = width;
00103     msg.encoding = image_format;
00104     msg.step = width;
00105 
00106     int count = 0;
00107     while( ros::ok() )
00108     {
00109       for( int x = 0; x < width; x++ )
00110       {
00111         for( int y = 0; y < height; y++ )
00112         {
00113           int index = x + y * width;
00114           float* ptr = ((float*) &msg.data[ 0 ]) + index;
00115           *ptr = sinf( (x + count) / 10.0f ) * sinf( y / 10.0f ) * 20.0f - 10.0f;
00116         }
00117       }
00118       msg.header.seq = count;
00119       msg.header.stamp = ros::Time::now();
00120 
00121       pub.publish( msg );
00122 
00123       ros::spinOnce();
00124       loop_rate.sleep();
00125       ++count;
00126     }
00127   }
00128   else if( image_format == "16UC1" )
00129   {
00130     sensor_msgs::Image msg;
00131     int width = 400;
00132     int height = 400;
00133     msg.data.resize( width * height * sizeof( short ));
00134     msg.header.frame_id = "base_link";
00135     msg.height = height;
00136     msg.width = width;
00137     msg.encoding = image_format;
00138     msg.step = width;
00139 
00140     int count = 0;
00141     while( ros::ok() )
00142     {
00143       for( int x = 0; x < width; x++ )
00144       {
00145         for( int y = 0; y < height; y++ )
00146         {
00147           int index = x + y * width;
00148           short* ptr = ((short*) &msg.data[ 0 ]) + index;
00149           *ptr = (count + abs( x % 100 - 50 ) + abs( y % 100 - 50 )) % 50 * 65535 / 50;
00150         }
00151       }
00152       msg.header.seq = count;
00153       msg.header.stamp = ros::Time::now();
00154 
00155       pub.publish( msg );
00156 
00157       ros::spinOnce();
00158       loop_rate.sleep();
00159       ++count;
00160     }
00161   }
00162 }


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:16