|
46 | 46 | * |
47 | 47 | * This file provides two sets of utilities to modify and parse PointCloud2 |
48 | 48 | * The first set allows you to conveniently set the fields by hand: |
49 | | - * <PRE> |
| 49 | + * \verbatim |
50 | 50 | * #include <sensor_msgs/point_cloud_iterator.h> |
51 | 51 | * // Create a PointCloud2 |
52 | 52 | * sensor_msgs::msg::PointCloud2 cloud_msg; |
|
67 | 67 | * modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); |
68 | 68 | * // You can then reserve / resize as usual |
69 | 69 | * modifier.resize(100); |
70 | | - * </PRE> |
| 70 | + * \endverbatim |
71 | 71 | * |
72 | 72 | * The second set allow you to traverse your PointCloud using an iterator: |
73 | | - * <PRE> |
| 73 | + * \verbatim |
74 | 74 | * // Define some raw data we'll put in the PointCloud2 |
75 | 75 | * float point_data[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0}; |
76 | 76 | * uint8_t color_data[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120}; |
|
95 | 95 | * *iter_g = color_data[3*i+1]; |
96 | 96 | * *iter_b = color_data[3*i+2]; |
97 | 97 | * } |
98 | | - * </PRE> |
| 98 | + * \endverbatim |
99 | 99 | */ |
100 | 100 |
|
101 | 101 | namespace sensor_msgs |
@@ -140,12 +140,12 @@ class PointCloud2Modifier |
140 | 140 | * field, the datatype of the elements in the field |
141 | 141 | * |
142 | 142 | * E.g, you create your PointCloud2 message with XYZ/RGB as follows: |
143 | | - * <PRE> |
| 143 | + * \verbatim |
144 | 144 | * setPointCloud2Fields(cloud_msg, 4, "x", 1, sensor_msgs::msg::PointField::FLOAT32, |
145 | 145 | * "y", 1, sensor_msgs::msg::PointField::FLOAT32, |
146 | 146 | * "z", 1, sensor_msgs::msg::PointField::FLOAT32, |
147 | 147 | * "rgb", 1, sensor_msgs::msg::PointField::FLOAT32); |
148 | | - * </PRE> |
| 148 | + * \endverbatim |
149 | 149 | * WARNING: THIS DOES NOT TAKE INTO ACCOUNT ANY PADDING AS DONE UNTIL HYDRO |
150 | 150 | * For simple usual cases, the overloaded setPointCloud2FieldsByString is what you want. |
151 | 151 | */ |
@@ -261,22 +261,22 @@ class PointCloud2IteratorBase |
261 | 261 | * |
262 | 262 | * T type of the element being iterated upon |
263 | 263 | * E.g, you create your PointClou2 message as follows: |
264 | | - * <PRE> |
| 264 | + * \verbatim |
265 | 265 | * setPointCloud2FieldsByString(cloud_msg, 2, "xyz", "rgb"); |
266 | | - * </PRE> |
| 266 | + * \endverbatim |
267 | 267 | * |
268 | 268 | * For iterating over XYZ, you do : |
269 | | - * <PRE> |
| 269 | + * \verbatim |
270 | 270 | * sensor_msgs::msg::PointCloud2Iterator<float> iter_x(cloud_msg, "x"); |
271 | | - * </PRE> |
| 271 | + * \endverbatim |
272 | 272 | * and then access X through iter_x[0] or *iter_x |
273 | 273 | * You could create an iterator for Y and Z too but as they are consecutive, |
274 | 274 | * you can just use iter_x[1] and iter_x[2] |
275 | 275 | * |
276 | 276 | * For iterating over RGB, you do: |
277 | | - * <PRE> |
| 277 | + * \verbatim |
278 | 278 | * sensor_msgs::msg::PointCloud2Iterator<uint8_t> iter_rgb(cloud_msg, "rgb"); |
279 | | - * </PRE> |
| 279 | + * \endverbatim |
280 | 280 | * and then access R,G,B through iter_rgb[0], iter_rgb[1], iter_rgb[2] |
281 | 281 | */ |
282 | 282 | template<typename T> |
|
0 commit comments