40 #include <visualization_msgs/MarkerArray.h> 41 #include <costmap_2d/VoxelGrid.h> 62 if (grid->data.empty())
71 const std::string frame_id = grid->header.frame_id;
72 const ros::Time stamp = grid->header.stamp;
73 const uint32_t* data = &grid->data.front();
74 const double x_origin = grid->origin.x;
75 const double y_origin = grid->origin.y;
76 const double z_origin = grid->origin.z;
77 const double x_res = grid->resolutions.x;
78 const double y_res = grid->resolutions.y;
79 const double z_res = grid->resolutions.z;
80 const uint32_t x_size = grid->size_x;
81 const uint32_t y_size = grid->size_y;
82 const uint32_t z_size = grid->size_z;
85 uint32_t num_markers = 0;
86 for (uint32_t y_grid = 0; y_grid < y_size; ++y_grid)
88 for (uint32_t x_grid = 0; x_grid < x_size; ++x_grid)
90 for (uint32_t z_grid = 0; z_grid < z_size; ++z_grid)
99 c.
x = x_origin + (x_grid + 0.5) * x_res;
100 c.
y = y_origin + (y_grid + 0.5) * y_res;
101 c.
z = z_origin + (z_grid + 0.5) * z_res;
110 visualization_msgs::Marker m;
111 m.header.frame_id = frame_id;
112 m.header.stamp = stamp;
115 m.type = visualization_msgs::Marker::CUBE_LIST;
116 m.action = visualization_msgs::Marker::ADD;
117 m.pose.orientation.w = 1.0;
125 m.points.resize(num_markers);
126 for (uint32_t i = 0; i < num_markers; ++i)
129 geometry_msgs::Point& p = m.points[i];
138 ROS_DEBUG(
"Published %d markers in %f seconds", num_markers, (end - start).toSec());
141 int main(
int argc,
char** argv)
143 ros::init(argc, argv,
"costmap_2d_markers");
voxel_grid::VoxelStatus status
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< Cell > V_Cell
void voxelCallback(const ros::Publisher &pub, const costmap_2d::VoxelGridConstPtr &grid)
VoxelStatus getVoxel(unsigned int x, unsigned int y, unsigned int z)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< Cell > V_Cell