send_point_cloud_2.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 "ros/ros.h"
31 #include "sensor_msgs/PointCloud2.h"
32 #include "math.h"
33 
34 int main(int argc, char** argv)
35 {
36  ros::init(argc, argv, "send_points2");
37 
38  int rate = 1;
39  bool moving = true;
40  int size = 100;
41 
42  if (argc > 1)
43  {
44  rate = atoi(argv[1]);
45  }
46  if (argc > 2)
47  {
48  moving = bool(atoi(argv[2]));
49  }
50  if (argc > 3)
51  {
52  size = atoi(argv[3]);
53  }
54 
55  ros::NodeHandle nh;
56 
57  ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("points2", 10);
58  ros::Rate loop_rate(rate);
59 
60  sensor_msgs::PointCloud2 msg;
61  int width = size;
62  int height = 2 * size;
63  msg.header.frame_id = "base_link";
64  msg.is_dense = false;
65  msg.is_bigendian = false;
66 
67  msg.fields.resize(5);
68 
69  msg.fields[0].name = "x";
70  msg.fields[0].offset = 0;
71  msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
72  msg.fields[0].count = 1;
73 
74  msg.fields[1].name = "y";
75  msg.fields[1].offset = 4;
76  msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
77  msg.fields[1].count = 1;
78 
79  msg.fields[2].name = "z";
80  msg.fields[2].offset = 8;
81  msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
82  msg.fields[2].count = 1;
83 
84  msg.fields[3].name = "rgb";
85  msg.fields[3].offset = 12;
86  msg.fields[3].datatype = sensor_msgs::PointField::INT32;
87  msg.fields[3].count = 1;
88 
89  msg.fields[4].name = "joy";
90  msg.fields[4].offset = 16;
91  msg.fields[4].datatype = sensor_msgs::PointField::FLOAT32;
92  msg.fields[4].count = 1;
93 
94  msg.point_step = 20;
95 
96  int count = 0;
97  while (ros::ok())
98  {
99  width++;
100  int num_points = width * height;
101  msg.row_step = width * msg.point_step;
102  msg.height = height;
103  msg.width = width;
104  msg.data.resize(num_points * msg.point_step);
105  for (int x = 0; x < width; x++)
106  {
107  for (int y = 0; y < height; y++)
108  {
109  uint8_t* ptr = &msg.data[0] + (x + y * width) * msg.point_step;
110  *(float*)ptr = x / 100.0f;
111  ptr += 4;
112  *(float*)ptr = y / 100.0f;
113  ptr += 4;
114  *(float*)ptr = 0.1 * sinf(x / 10.0f) * sinf(y / 10.0f);
115  ptr += 4;
116  *ptr = (x + count) & 0xff;
117  ptr++;
118  *ptr = y & 0xff;
119  ptr++;
120  *ptr = (x + y) & 0xff;
121  ptr++;
122  ptr++;
123  *(float*)ptr = 127.0f + 127.0f * sinf((x - count) / 10.0f) * sinf(y / 10.0f);
124  // ptr += 4;
125  }
126  }
127  msg.header.seq = count;
128  msg.header.stamp = ros::Time::now();
129 
130  printf("publishing at %d hz, %s, %d x %d points.\n", rate, (moving ? "moving" : "static"), width,
131  height);
132 
133  pub.publish(msg);
134 
135  ros::spinOnce();
136  loop_rate.sleep();
137  if (moving)
138  {
139  ++count;
140  }
141  }
142 }
f
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
ROSCPP_DECL void spinOnce()


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