Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_2d_cloud.cpp
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #include <string>
29 #include <vector>
30 #include <memory>
31 #include <utility>
32 
33 #include "rclcpp/rclcpp.hpp"
34 #include "sensor_msgs/msg/point_cloud2.hpp"
35 #include "sensor_msgs/point_cloud2_iterator.hpp"
36 #include "nav2_voxel_grid/voxel_grid.hpp"
37 #include "nav2_msgs/msg/voxel_grid.hpp"
38 #include "nav2_util/execution_timer.hpp"
39 #include "nav2_ros_common/lifecycle_node.hpp"
40 
41 static inline void mapToWorld3D(
42  const unsigned int mx,
43  const unsigned int my, const unsigned int mz,
44  const double origin_x, const double origin_y, const double origin_z,
45  const double x_resolution, const double y_resolution,
46  const double z_resolution,
47  double & wx, double & wy, double & wz)
48 {
49  // returns the center point of the cell
50  wx = origin_x + (mx + 0.5) * x_resolution;
51  wy = origin_y + (my + 0.5) * y_resolution;
52  wz = origin_z + (mz + 0.5) * z_resolution;
53 }
54 
55 struct Cell
56 {
57  double x;
58  double y;
59  double z;
60  nav2_voxel_grid::VoxelStatus status;
61 };
62 typedef std::vector<Cell> V_Cell;
63 
64 float g_colors_r[] = {0.0f, 0.0f, 1.0f};
65 float g_colors_g[] = {0.0f, 0.0f, 0.0f};
66 float g_colors_b[] = {0.0f, 1.0f, 0.0f};
67 float g_colors_a[] = {0.0f, 0.5f, 1.0f};
68 
69 V_Cell g_marked;
70 V_Cell g_unknown;
71 
72 rclcpp::Node::SharedPtr g_node;
73 
74 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_marked;
75 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_unknown;
76 
84 void pointCloud2Helper(
85  std::unique_ptr<sensor_msgs::msg::PointCloud2> & cloud,
86  uint32_t num_channels,
87  std_msgs::msg::Header header,
88  V_Cell & g_cells)
89 {
90  cloud->header = header;
91  cloud->width = num_channels;
92  cloud->height = 1;
93  cloud->is_dense = true;
94  cloud->is_bigendian = false;
95  sensor_msgs::PointCloud2Modifier modifier(*cloud);
96 
97  modifier.setPointCloud2Fields(
98  6, "x", 1, sensor_msgs::msg::PointField::FLOAT32,
99  "y", 1, sensor_msgs::msg::PointField::FLOAT32,
100  "z", 1, sensor_msgs::msg::PointField::FLOAT32,
101  "r", 1, sensor_msgs::msg::PointField::UINT8,
102  "g", 1, sensor_msgs::msg::PointField::UINT8,
103  "b", 1, sensor_msgs::msg::PointField::UINT8);
104 
105  sensor_msgs::PointCloud2Iterator<float> iter_x(*cloud, "x");
106  sensor_msgs::PointCloud2Iterator<float> iter_y(*cloud, "y");
107  sensor_msgs::PointCloud2Iterator<float> iter_z(*cloud, "z");
108 
109  sensor_msgs::PointCloud2Iterator<uint8_t> iter_r(*cloud, "r");
110  sensor_msgs::PointCloud2Iterator<uint8_t> iter_g(*cloud, "g");
111  sensor_msgs::PointCloud2Iterator<uint8_t> iter_b(*cloud, "b");
112 
113  for (uint32_t i = 0; i < num_channels; ++i) {
114  Cell & c = g_cells[i];
115  // assigning value to the point cloud2's iterator
116  *iter_x = c.x;
117  *iter_y = c.y;
118  *iter_z = c.z;
119  *iter_r = g_colors_r[c.status] * 255.0;
120  *iter_g = g_colors_g[c.status] * 255.0;
121  *iter_b = g_colors_b[c.status] * 255.0;
122 
123  ++iter_x;
124  ++iter_y;
125  ++iter_z;
126  ++iter_r;
127  ++iter_g;
128  ++iter_b;
129  }
130 }
131 
132 void voxelCallback(const nav2_msgs::msg::VoxelGrid::ConstSharedPtr grid)
133 {
134  if (grid->data.empty()) {
135  RCLCPP_ERROR(g_node->get_logger(), "Received empty voxel grid");
136  return;
137  }
138 
140  timer.start();
141 
142  RCLCPP_DEBUG(g_node->get_logger(), "Received voxel grid");
143  const std::string frame_id = grid->header.frame_id;
144  const rclcpp::Time stamp = grid->header.stamp;
145  const uint32_t * data = &grid->data.front();
146  const double x_origin = grid->origin.x;
147  const double y_origin = grid->origin.y;
148  const double z_origin = grid->origin.z;
149  const double x_res = grid->resolutions.x;
150  const double y_res = grid->resolutions.y;
151  const double z_res = grid->resolutions.z;
152  const uint32_t x_size = grid->size_x;
153  const uint32_t y_size = grid->size_y;
154  const uint32_t z_size = grid->size_z;
155 
156  g_marked.clear();
157  g_unknown.clear();
158  uint32_t num_marked = 0;
159  uint32_t num_unknown = 0;
160  for (uint32_t y_grid = 0; y_grid < y_size; ++y_grid) {
161  for (uint32_t x_grid = 0; x_grid < x_size; ++x_grid) {
162  for (uint32_t z_grid = 0; z_grid < z_size; ++z_grid) {
163  nav2_voxel_grid::VoxelStatus status =
164  nav2_voxel_grid::VoxelGrid::getVoxel(
165  x_grid, y_grid,
166  z_grid, x_size, y_size, z_size, data);
167  if (status == nav2_voxel_grid::UNKNOWN) {
168  Cell c;
169  c.status = status;
170  mapToWorld3D(
171  x_grid, y_grid, z_grid, x_origin, y_origin,
172  z_origin, x_res, y_res, z_res, c.x, c.y, c.z);
173 
174  g_unknown.push_back(c);
175 
176  ++num_unknown;
177  } else if (status == nav2_voxel_grid::MARKED) {
178  Cell c;
179  c.status = status;
180  mapToWorld3D(
181  x_grid, y_grid, z_grid, x_origin, y_origin,
182  z_origin, x_res, y_res, z_res, c.x, c.y, c.z);
183 
184  g_marked.push_back(c);
185 
186  ++num_marked;
187  }
188  }
189  }
190  }
191 
192  std_msgs::msg::Header pcl_header;
193  pcl_header.frame_id = frame_id;
194  pcl_header.stamp = stamp;
195 
196  {
197  auto cloud = std::make_unique<sensor_msgs::msg::PointCloud2>();
198  pointCloud2Helper(cloud, num_marked, pcl_header, g_marked);
199  pub_marked->publish(std::move(cloud));
200  }
201 
202  {
203  auto cloud = std::make_unique<sensor_msgs::msg::PointCloud2>();
204  pointCloud2Helper(cloud, num_unknown, pcl_header, g_unknown);
205  pub_unknown->publish(std::move(cloud));
206  }
207 
208  timer.end();
209  RCLCPP_DEBUG(
210  g_node->get_logger(), "Published %d points in %f seconds",
211  num_marked + num_unknown, timer.elapsed_time_in_seconds());
212 }
213 
214 int main(int argc, char ** argv)
215 {
216  rclcpp::init(argc, argv);
217  g_node = rclcpp::Node::make_shared("costmap_2d_cloud");
218 
219  RCLCPP_DEBUG(g_node->get_logger(), "Starting up costmap_2d_cloud");
220 
221  pub_marked = g_node->create_publisher<sensor_msgs::msg::PointCloud2>(
222  "voxel_marked_cloud", nav2::qos::StandardTopicQoS());
223  pub_unknown = g_node->create_publisher<sensor_msgs::msg::PointCloud2>(
224  "voxel_unknown_cloud", nav2::qos::StandardTopicQoS());
225  auto sub = g_node->create_subscription<nav2_msgs::msg::VoxelGrid>(
226  "voxel_grid", nav2::qos::StandardTopicQoS(), voxelCallback);
227 
228  rclcpp::spin(g_node->get_node_base_interface());
229 
230  g_node.reset();
231  pub_marked.reset();
232  pub_unknown.reset();
233 
234  rclcpp::shutdown();
235 
236  return 0;
237 }
A QoS profile for standard reliable topics with a history of 10 messages.
Measures execution time of code between calls to start and end.
void start()
Call just prior to code you want to measure.
double elapsed_time_in_seconds()
Extract the measured time as a floating point number of seconds.
void end()
Call just after the code you want to measure.