send_images.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <string>
31 #include "stdlib.h"
32 #include "ros/ros.h"
33 #include "sensor_msgs/Image.h"
35 #include "math.h"
37 
38 int main( int argc, char **argv )
39 {
40  ros::init( argc, argv, "send_images" );
41 
42  if( argc != 2 )
43  {
44  printf( "USAGE: %s <image_format>\n"
45  " Where <image_format> is rgb8, 32FC1, or 16UC1.",
46  argv[ 0 ] );
47  exit( 1 );
48  }
49  const std::string image_format( argv[ 1 ]);
50 
51  ros::NodeHandle nh;
53  image_transport::Publisher pub = it.advertise("images", 100);
54  ros::Rate loop_rate( 100 );
55 
56  if( image_format == "rgb8" )
57  {
58  sensor_msgs::Image msg;
59  int width = 100;
60  int height = 1000;
61  msg.data.resize( width * height * 3 );
62  msg.header.frame_id = "base_link";
63  msg.height = height;
64  msg.width = width;
65  msg.encoding = image_format;
66  msg.step = width * 3;
67 
68  int count = 0;
69  while( ros::ok() )
70  {
71  for( int x = 0; x < width; x++ )
72  {
73  for( int y = 0; y < height; y++ )
74  {
75  int index = (x + y * width) * 3;
76  long int rand = random();
77  msg.data[ index ] = rand & 0xff;
78  index++;
79  msg.data[ index ] = (rand >> 8) & 0xff;
80  index++;
81  msg.data[ index ] = (rand >> 16) & 0xff;
82  }
83  }
84  msg.header.seq = count;
85  msg.header.stamp = ros::Time::now();
86 
87  pub.publish( msg );
88 
89  ros::spinOnce();
90  loop_rate.sleep();
91  ++count;
92  }
93  }
94  else if( image_format == "32FC1" )
95  {
96  sensor_msgs::Image msg;
97  int width = 400;
98  int height = 400;
99  msg.data.resize( width * height * sizeof( float ));
100  msg.header.frame_id = "base_link";
101  msg.height = height;
102  msg.width = width;
103  msg.encoding = image_format;
104  msg.step = width;
105 
106  int count = 0;
107  while( ros::ok() )
108  {
109  for( int x = 0; x < width; x++ )
110  {
111  for( int y = 0; y < height; y++ )
112  {
113  int index = x + y * width;
114  float* ptr = ((float*) &msg.data[ 0 ]) + index;
115  *ptr = sinf( (x + count) / 10.0f ) * sinf( y / 10.0f ) * 20.0f - 10.0f;
116  }
117  }
118  msg.header.seq = count;
119  msg.header.stamp = ros::Time::now();
120 
121  pub.publish( msg );
122 
123  ros::spinOnce();
124  loop_rate.sleep();
125  ++count;
126  }
127  }
128  else if( image_format == "16UC1" )
129  {
130  sensor_msgs::Image msg;
131  int width = 400;
132  int height = 400;
133  msg.data.resize( width * height * sizeof( short ));
134  msg.header.frame_id = "base_link";
135  msg.height = height;
136  msg.width = width;
137  msg.encoding = image_format;
138  msg.step = width;
139 
140  int count = 0;
141  while( ros::ok() )
142  {
143  for( int x = 0; x < width; x++ )
144  {
145  for( int y = 0; y < height; y++ )
146  {
147  int index = x + y * width;
148  short* ptr = ((short*) &msg.data[ 0 ]) + index;
149  *ptr = (count + abs( x % 100 - 50 ) + abs( y % 100 - 50 )) % 50 * 65535 / 50;
150  }
151  }
152  msg.header.seq = count;
153  msg.header.stamp = ros::Time::now();
154 
155  pub.publish( msg );
156 
157  ros::spinOnce();
158  loop_rate.sleep();
159  ++count;
160  }
161  }
162 }
f
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void publish(const sensor_msgs::Image &message) const
int main(int argc, char **argv)
Definition: send_images.cpp:38
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool sleep()
static Time now()
ROSCPP_DECL void spinOnce()


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51