34 #include "sensor_msgs/Image.h" 39 int main(
int argc,
char** argv)
45 printf(
"USAGE: %s <image_format>\n" 46 " Where <image_format> is rgb8, 32FC1, or 16UC1.",
50 const std::string image_format(argv[1]);
57 if (image_format ==
"rgb8")
59 sensor_msgs::Image msg;
62 msg.data.resize(width * height * 3);
63 msg.header.frame_id =
"camera_frame";
66 msg.encoding = image_format;
70 std::default_random_engine random_generator;
73 for (
int x = 0; x < width; x++)
75 for (
int y = 0; y < height; y++)
77 uint8_t
r = 0, g = 0, b = 0;
82 if (x >= 5 && x < width - 5 && y >= 5 && y < height - 5)
84 std::uniform_int_distribution<int> uniform(0, RAND_MAX);
85 auto rand = uniform(random_generator);
87 g = (rand >> 8) & 0xff;
88 b = (rand >> 16) & 0xff;
90 int index = (x + y * width) * 3;
98 msg.header.seq = count;
108 else if (image_format ==
"32FC1")
110 sensor_msgs::Image msg;
113 msg.data.resize(width * height *
sizeof(
float));
114 msg.header.frame_id =
"camera_frame";
117 msg.encoding = image_format;
123 for (
int x = 0; x < width; x++)
125 for (
int y = 0; y < height; y++)
127 int index = x + y * width;
128 float* ptr = ((
float*)&msg.data[0]) + index;
129 *ptr = sinf((x + count) / 10.0
f) * sinf(y / 10.0
f) * 20.0f - 10.0f;
132 msg.header.seq = count;
142 else if (image_format ==
"16UC1")
144 sensor_msgs::Image msg;
147 msg.data.resize(width * height *
sizeof(
short));
148 msg.header.frame_id =
"camera_frame";
151 msg.encoding = image_format;
157 for (
int x = 0; x < width; x++)
159 for (
int y = 0; y < height; y++)
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;
166 msg.header.seq = count;
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)
void publish(const sensor_msgs::Image &message) const
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
ROSCPP_DECL void spinOnce()