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"
56 nav2_voxel_grid::VoxelStatus status;
58 typedef std::vector<Cell> V_Cell;
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};
66 rclcpp::Node::SharedPtr g_node;
67 rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr pub;
69 void voxelCallback(
const nav2_msgs::msg::VoxelGrid::ConstSharedPtr grid)
71 if (grid->data.empty()) {
72 RCLCPP_ERROR(g_node->get_logger(),
"Received voxel grid");
79 RCLCPP_DEBUG(g_node->get_logger(),
"Received voxel grid");
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;
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(
102 z_grid, x_size, y_size, z_size, data);
103 if (status == nav2_voxel_grid::MARKED) {
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);
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();
122 m->type = visualization_msgs::msg::Marker::CUBE_LIST;
123 m->action = visualization_msgs::msg::Marker::ADD;
124 m->pose.orientation.w = 1.0;
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];
141 pub->publish(std::move(m));
145 g_node->get_logger(),
"Published %d markers in %f seconds",
149 int main(
int argc,
char ** argv)
151 rclcpp::init(argc, argv);
152 g_node = rclcpp::Node::make_shared(
"costmap_2d_marker");
154 RCLCPP_DEBUG(g_node->get_logger(),
"Starting costmap_2d_marker");
156 pub = g_node->create_publisher<visualization_msgs::msg::Marker>(
159 auto sub = g_node->create_subscription<nav2_msgs::msg::VoxelGrid>(
162 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.