Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_2d_markers.cpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  * Steve Macenski
38  *********************************************************************/
39 #include <string>
40 #include <vector>
41 #include <memory>
42 #include <utility>
43 
44 #include "rclcpp/rclcpp.hpp"
45 #include "visualization_msgs/msg/marker.hpp"
46 #include "nav2_msgs/msg/voxel_grid.hpp"
47 #include "nav2_voxel_grid/voxel_grid.hpp"
48 #include "nav2_util/execution_timer.hpp"
49 #include "nav2_ros_common/lifecycle_node.hpp"
50 
51 struct Cell
52 {
53  double x;
54  double y;
55  double z;
56  nav2_voxel_grid::VoxelStatus status;
57 };
58 typedef std::vector<Cell> V_Cell;
59 
60 float g_colors_r[] = {0.0f, 0.0f, 1.0f};
61 float g_colors_g[] = {0.0f, 0.0f, 0.0f};
62 float g_colors_b[] = {0.0f, 1.0f, 0.0f};
63 float g_colors_a[] = {0.0f, 0.5f, 1.0f};
64 
65 V_Cell g_cells;
66 rclcpp::Node::SharedPtr g_node;
67 rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr pub;
68 
69 void voxelCallback(const nav2_msgs::msg::VoxelGrid::ConstSharedPtr grid)
70 {
71  if (grid->data.empty()) {
72  RCLCPP_ERROR(g_node->get_logger(), "Received voxel grid");
73  return;
74  }
75 
77  timer.start();
78 
79  RCLCPP_DEBUG(g_node->get_logger(), "Received voxel grid");
80 
81  const std::string frame_id = grid->header.frame_id;
82  const rclcpp::Time stamp = grid->header.stamp;
83  const uint32_t * data = &grid->data.front();
84  const double x_origin = grid->origin.x;
85  const double y_origin = grid->origin.y;
86  const double z_origin = grid->origin.z;
87  const double x_res = grid->resolutions.x;
88  const double y_res = grid->resolutions.y;
89  const double z_res = grid->resolutions.z;
90  const uint32_t x_size = grid->size_x;
91  const uint32_t y_size = grid->size_y;
92  const uint32_t z_size = grid->size_z;
93 
94  g_cells.clear();
95  uint32_t num_markers = 0;
96  for (uint32_t y_grid = 0; y_grid < y_size; ++y_grid) {
97  for (uint32_t x_grid = 0; x_grid < x_size; ++x_grid) {
98  for (uint32_t z_grid = 0; z_grid < z_size; ++z_grid) {
99  nav2_voxel_grid::VoxelStatus status =
100  nav2_voxel_grid::VoxelGrid::getVoxel(
101  x_grid, y_grid,
102  z_grid, x_size, y_size, z_size, data);
103  if (status == nav2_voxel_grid::MARKED) {
104  Cell c;
105  c.status = status;
106  c.x = x_origin + (x_grid + 0.5) * x_res;
107  c.y = y_origin + (y_grid + 0.5) * y_res;
108  c.z = z_origin + (z_grid + 0.5) * z_res;
109  g_cells.push_back(c);
110 
111  ++num_markers;
112  }
113  }
114  }
115  }
116 
117  auto m = std::make_unique<visualization_msgs::msg::Marker>();
118  m->header.frame_id = frame_id;
119  m->header.stamp = stamp;
120  m->ns = g_node->get_namespace();
121  m->id = 0;
122  m->type = visualization_msgs::msg::Marker::CUBE_LIST;
123  m->action = visualization_msgs::msg::Marker::ADD;
124  m->pose.orientation.w = 1.0;
125  m->scale.x = x_res;
126  m->scale.y = y_res;
127  m->scale.z = z_res;
128  m->color.r = g_colors_r[nav2_voxel_grid::MARKED];
129  m->color.g = g_colors_g[nav2_voxel_grid::MARKED];
130  m->color.b = g_colors_b[nav2_voxel_grid::MARKED];
131  m->color.a = g_colors_a[nav2_voxel_grid::MARKED];
132  m->points.resize(num_markers);
133  for (uint32_t i = 0; i < num_markers; ++i) {
134  Cell & c = g_cells[i];
135  geometry_msgs::msg::Point & p = m->points[i];
136  p.x = c.x;
137  p.y = c.y;
138  p.z = c.z;
139  }
140 
141  pub->publish(std::move(m));
142 
143  timer.end();
144  RCLCPP_INFO(
145  g_node->get_logger(), "Published %d markers in %f seconds",
146  num_markers, timer.elapsed_time_in_seconds());
147 }
148 
149 int main(int argc, char ** argv)
150 {
151  rclcpp::init(argc, argv);
152  g_node = rclcpp::Node::make_shared("costmap_2d_marker");
153 
154  RCLCPP_DEBUG(g_node->get_logger(), "Starting costmap_2d_marker");
155 
156  pub = g_node->create_publisher<visualization_msgs::msg::Marker>(
157  "visualization_marker", nav2::qos::StandardTopicQoS());
158 
159  auto sub = g_node->create_subscription<nav2_msgs::msg::VoxelGrid>(
160  "voxel_grid", nav2::qos::StandardTopicQoS(), voxelCallback);
161 
162  rclcpp::spin(g_node->get_node_base_interface());
163 }
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.