Nav2 Navigation Stack - jazzy  jazzy
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 
40 static inline void mapToWorld3D(
41  const unsigned int mx,
42  const unsigned int my, const unsigned int mz,
43  const double origin_x, const double origin_y, const double origin_z,
44  const double x_resolution, const double y_resolution,
45  const double z_resolution,
46  double & wx, double & wy, double & wz)
47 {
48  // returns the center point of the cell
49  wx = origin_x + (mx + 0.5) * x_resolution;
50  wy = origin_y + (my + 0.5) * y_resolution;
51  wz = origin_z + (mz + 0.5) * z_resolution;
52 }
53 
54 struct Cell
55 {
56  double x;
57  double y;
58  double z;
59  nav2_voxel_grid::VoxelStatus status;
60 };
61 typedef std::vector<Cell> V_Cell;
62 
63 float g_colors_r[] = {0.0f, 0.0f, 1.0f};
64 float g_colors_g[] = {0.0f, 0.0f, 0.0f};
65 float g_colors_b[] = {0.0f, 1.0f, 0.0f};
66 float g_colors_a[] = {0.0f, 0.5f, 1.0f};
67 
68 V_Cell g_marked;
69 V_Cell g_unknown;
70 
71 rclcpp::Node::SharedPtr g_node;
72 
73 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_marked;
74 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_unknown;
75 
83 void pointCloud2Helper(
84  std::unique_ptr<sensor_msgs::msg::PointCloud2> & cloud,
85  uint32_t num_channels,
86  std_msgs::msg::Header header,
87  V_Cell & g_cells)
88 {
89  cloud->header = header;
90  cloud->width = num_channels;
91  cloud->height = 1;
92  cloud->is_dense = true;
93  cloud->is_bigendian = false;
94  sensor_msgs::PointCloud2Modifier modifier(*cloud);
95 
96  modifier.setPointCloud2Fields(
97  6, "x", 1, sensor_msgs::msg::PointField::FLOAT32,
98  "y", 1, sensor_msgs::msg::PointField::FLOAT32,
99  "z", 1, sensor_msgs::msg::PointField::FLOAT32,
100  "r", 1, sensor_msgs::msg::PointField::UINT8,
101  "g", 1, sensor_msgs::msg::PointField::UINT8,
102  "b", 1, sensor_msgs::msg::PointField::UINT8);
103 
104  sensor_msgs::PointCloud2Iterator<float> iter_x(*cloud, "x");
105  sensor_msgs::PointCloud2Iterator<float> iter_y(*cloud, "y");
106  sensor_msgs::PointCloud2Iterator<float> iter_z(*cloud, "z");
107 
108  sensor_msgs::PointCloud2Iterator<uint8_t> iter_r(*cloud, "r");
109  sensor_msgs::PointCloud2Iterator<uint8_t> iter_g(*cloud, "g");
110  sensor_msgs::PointCloud2Iterator<uint8_t> iter_b(*cloud, "b");
111 
112  for (uint32_t i = 0; i < num_channels; ++i) {
113  Cell & c = g_cells[i];
114  // assigning value to the point cloud2's iterator
115  *iter_x = c.x;
116  *iter_y = c.y;
117  *iter_z = c.z;
118  *iter_r = g_colors_r[c.status] * 255.0;
119  *iter_g = g_colors_g[c.status] * 255.0;
120  *iter_b = g_colors_b[c.status] * 255.0;
121 
122  ++iter_x;
123  ++iter_y;
124  ++iter_z;
125  ++iter_r;
126  ++iter_g;
127  ++iter_b;
128  }
129 }
130 
131 void voxelCallback(const nav2_msgs::msg::VoxelGrid::ConstSharedPtr grid)
132 {
133  if (grid->data.empty()) {
134  RCLCPP_ERROR(g_node->get_logger(), "Received empty voxel grid");
135  return;
136  }
137 
139  timer.start();
140 
141  RCLCPP_DEBUG(g_node->get_logger(), "Received voxel grid");
142  const std::string frame_id = grid->header.frame_id;
143  const rclcpp::Time stamp = grid->header.stamp;
144  const uint32_t * data = &grid->data.front();
145  const double x_origin = grid->origin.x;
146  const double y_origin = grid->origin.y;
147  const double z_origin = grid->origin.z;
148  const double x_res = grid->resolutions.x;
149  const double y_res = grid->resolutions.y;
150  const double z_res = grid->resolutions.z;
151  const uint32_t x_size = grid->size_x;
152  const uint32_t y_size = grid->size_y;
153  const uint32_t z_size = grid->size_z;
154 
155  g_marked.clear();
156  g_unknown.clear();
157  uint32_t num_marked = 0;
158  uint32_t num_unknown = 0;
159  for (uint32_t y_grid = 0; y_grid < y_size; ++y_grid) {
160  for (uint32_t x_grid = 0; x_grid < x_size; ++x_grid) {
161  for (uint32_t z_grid = 0; z_grid < z_size; ++z_grid) {
162  nav2_voxel_grid::VoxelStatus status =
163  nav2_voxel_grid::VoxelGrid::getVoxel(
164  x_grid, y_grid,
165  z_grid, x_size, y_size, z_size, data);
166  if (status == nav2_voxel_grid::UNKNOWN) {
167  Cell c;
168  c.status = status;
169  mapToWorld3D(
170  x_grid, y_grid, z_grid, x_origin, y_origin,
171  z_origin, x_res, y_res, z_res, c.x, c.y, c.z);
172 
173  g_unknown.push_back(c);
174 
175  ++num_unknown;
176  } else if (status == nav2_voxel_grid::MARKED) {
177  Cell c;
178  c.status = status;
179  mapToWorld3D(
180  x_grid, y_grid, z_grid, x_origin, y_origin,
181  z_origin, x_res, y_res, z_res, c.x, c.y, c.z);
182 
183  g_marked.push_back(c);
184 
185  ++num_marked;
186  }
187  }
188  }
189  }
190 
191  std_msgs::msg::Header pcl_header;
192  pcl_header.frame_id = frame_id;
193  pcl_header.stamp = stamp;
194 
195  {
196  auto cloud = std::make_unique<sensor_msgs::msg::PointCloud2>();
197  pointCloud2Helper(cloud, num_marked, pcl_header, g_marked);
198  pub_marked->publish(std::move(cloud));
199  }
200 
201  {
202  auto cloud = std::make_unique<sensor_msgs::msg::PointCloud2>();
203  pointCloud2Helper(cloud, num_unknown, pcl_header, g_unknown);
204  pub_unknown->publish(std::move(cloud));
205  }
206 
207  timer.end();
208  RCLCPP_DEBUG(
209  g_node->get_logger(), "Published %d points in %f seconds",
210  num_marked + num_unknown, timer.elapsed_time_in_seconds());
211 }
212 
213 int main(int argc, char ** argv)
214 {
215  rclcpp::init(argc, argv);
216  g_node = rclcpp::Node::make_shared("costmap_2d_cloud");
217 
218  RCLCPP_DEBUG(g_node->get_logger(), "Starting up costmap_2d_cloud");
219 
220  pub_marked = g_node->create_publisher<sensor_msgs::msg::PointCloud2>(
221  "voxel_marked_cloud", 1);
222  pub_unknown = g_node->create_publisher<sensor_msgs::msg::PointCloud2>(
223  "voxel_unknown_cloud", 1);
224  auto sub = g_node->create_subscription<nav2_msgs::msg::VoxelGrid>(
225  "voxel_grid", rclcpp::SystemDefaultsQoS(), voxelCallback);
226 
227  rclcpp::spin(g_node->get_node_base_interface());
228 
229  g_node.reset();
230  pub_marked.reset();
231  pub_unknown.reset();
232 
233  rclcpp::shutdown();
234 
235  return 0;
236 }
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.