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 <random>
32 #include "stdlib.h"
33 #include "ros/ros.h"
34 #include "sensor_msgs/Image.h"
36 #include "math.h"
38 
39 int main(int argc, char** argv)
40 {
41  ros::init(argc, argv, "send_images");
42 
43  if (argc != 2)
44  {
45  printf("USAGE: %s <image_format>\n"
46  " Where <image_format> is rgb8, 32FC1, or 16UC1.",
47  argv[0]);
48  exit(1);
49  }
50  const std::string image_format(argv[1]);
51 
52  ros::NodeHandle nh;
54  image_transport::Publisher pub = it.advertise("images", 100);
55  ros::Rate loop_rate(100);
56 
57  if (image_format == "rgb8")
58  {
59  sensor_msgs::Image msg;
60  int width = 300;
61  int height = 200;
62  msg.data.resize(width * height * 3);
63  msg.header.frame_id = "camera_frame";
64  msg.height = height;
65  msg.width = width;
66  msg.encoding = image_format;
67  msg.step = width * 3;
68 
69  int count = 0;
70  std::default_random_engine random_generator;
71  while (ros::ok())
72  {
73  for (int x = 0; x < width; x++)
74  {
75  for (int y = 0; y < height; y++)
76  {
77  uint8_t r = 0, g = 0, b = 0;
78  if (x < 5)
79  r = 255;
80  if (y < 5)
81  r = g = 255;
82  if (x >= 5 && x < width - 5 && y >= 5 && y < height - 5)
83  {
84  std::uniform_int_distribution<int> uniform(0, RAND_MAX);
85  auto rand = uniform(random_generator);
86  r = rand & 0xff;
87  g = (rand >> 8) & 0xff;
88  b = (rand >> 16) & 0xff;
89  }
90  int index = (x + y * width) * 3;
91  msg.data[index] = r;
92  index++;
93  msg.data[index] = g;
94  index++;
95  msg.data[index] = b;
96  }
97  }
98  msg.header.seq = count;
99  msg.header.stamp = ros::Time::now();
100 
101  pub.publish(msg);
102 
103  ros::spinOnce();
104  loop_rate.sleep();
105  ++count;
106  }
107  }
108  else if (image_format == "32FC1")
109  {
110  sensor_msgs::Image msg;
111  int width = 400;
112  int height = 400;
113  msg.data.resize(width * height * sizeof(float));
114  msg.header.frame_id = "camera_frame";
115  msg.height = height;
116  msg.width = width;
117  msg.encoding = image_format;
118  msg.step = width;
119 
120  int count = 0;
121  while (ros::ok())
122  {
123  for (int x = 0; x < width; x++)
124  {
125  for (int y = 0; y < height; y++)
126  {
127  int index = x + y * width;
128  float* ptr = ((float*)&msg.data[0]) + index;
129  *ptr = sinf((x + count) / 10.0f) * sinf(y / 10.0f) * 20.0f - 10.0f;
130  }
131  }
132  msg.header.seq = count;
133  msg.header.stamp = ros::Time::now();
134 
135  pub.publish(msg);
136 
137  ros::spinOnce();
138  loop_rate.sleep();
139  ++count;
140  }
141  }
142  else if (image_format == "16UC1")
143  {
144  sensor_msgs::Image msg;
145  int width = 400;
146  int height = 400;
147  msg.data.resize(width * height * sizeof(short));
148  msg.header.frame_id = "camera_frame";
149  msg.height = height;
150  msg.width = width;
151  msg.encoding = image_format;
152  msg.step = width;
153 
154  int count = 0;
155  while (ros::ok())
156  {
157  for (int x = 0; x < width; x++)
158  {
159  for (int y = 0; y < height; y++)
160  {
161  int index = x + y * width;
162  short* ptr = ((short*)&msg.data[0]) + index;
163  *ptr = (count + abs(x % 100 - 50) + abs(y % 100 - 50)) % 50 * 65535 / 50;
164  }
165  }
166  msg.header.seq = count;
167  msg.header.stamp = ros::Time::now();
168 
169  pub.publish(msg);
170 
171  ros::spinOnce();
172  loop_rate.sleep();
173  ++count;
174  }
175  }
176 }
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)
int main(int argc, char **argv)
Definition: send_images.cpp:39
ROSCPP_DECL bool ok()
void publish(const sensor_msgs::Image &message) const
bool sleep()
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
static Time now()
ROSCPP_DECL void spinOnce()
r


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25