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"
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)
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;
60 nav2_voxel_grid::VoxelStatus status;
62 typedef std::vector<Cell> V_Cell;
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};
72 rclcpp::Node::SharedPtr g_node;
74 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_marked;
75 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_unknown;
84 void pointCloud2Helper(
85 std::unique_ptr<sensor_msgs::msg::PointCloud2> & cloud,
86 uint32_t num_channels,
87 std_msgs::msg::Header header,
90 cloud->header = header;
91 cloud->width = num_channels;
93 cloud->is_dense =
true;
94 cloud->is_bigendian =
false;
95 sensor_msgs::PointCloud2Modifier modifier(*cloud);
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);
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");
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");
113 for (uint32_t i = 0; i < num_channels; ++i) {
114 Cell & c = g_cells[i];
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;
132 void voxelCallback(
const nav2_msgs::msg::VoxelGrid::ConstSharedPtr grid)
134 if (grid->data.empty()) {
135 RCLCPP_ERROR(g_node->get_logger(),
"Received empty voxel grid");
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;
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(
166 z_grid, x_size, y_size, z_size, data);
167 if (status == nav2_voxel_grid::UNKNOWN) {
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);
174 g_unknown.push_back(c);
177 }
else if (status == nav2_voxel_grid::MARKED) {
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);
184 g_marked.push_back(c);
192 std_msgs::msg::Header pcl_header;
193 pcl_header.frame_id = frame_id;
194 pcl_header.stamp = stamp;
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));
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));
210 g_node->get_logger(),
"Published %d points in %f seconds",
214 int main(
int argc,
char ** argv)
216 rclcpp::init(argc, argv);
217 g_node = rclcpp::Node::make_shared(
"costmap_2d_cloud");
219 RCLCPP_DEBUG(g_node->get_logger(),
"Starting up costmap_2d_cloud");
221 pub_marked = g_node->create_publisher<sensor_msgs::msg::PointCloud2>(
223 pub_unknown = g_node->create_publisher<sensor_msgs::msg::PointCloud2>(
225 auto sub = g_node->create_subscription<nav2_msgs::msg::VoxelGrid>(
228 rclcpp::spin(g_node->get_node_base_interface());
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.