29 #include <sensor_msgs/PointCloud.h> 30 #include <costmap_2d/VoxelGrid.h> 33 static inline void mapToWorld3D(
const unsigned int mx,
const unsigned int my,
const unsigned int mz,
34 const double origin_x,
const double origin_y,
const double origin_z,
35 const double x_resolution,
const double y_resolution,
const double z_resolution,
36 double& wx,
double& wy,
double& wz)
39 wx = origin_x + (mx + 0.5) * x_resolution;
40 wy = origin_y + (my + 0.5) * y_resolution;
41 wz = origin_z + (mz + 0.5) * z_resolution;
61 const costmap_2d::VoxelGridConstPtr& grid)
63 if (grid->data.empty())
72 const std::string frame_id = grid->header.frame_id;
73 const ros::Time stamp = grid->header.stamp;
74 const uint32_t* data = &grid->data.front();
75 const double x_origin = grid->origin.x;
76 const double y_origin = grid->origin.y;
77 const double z_origin = grid->origin.z;
78 const double x_res = grid->resolutions.x;
79 const double y_res = grid->resolutions.y;
80 const double z_res = grid->resolutions.z;
81 const uint32_t x_size = grid->size_x;
82 const uint32_t y_size = grid->size_y;
83 const uint32_t z_size = grid->size_z;
87 uint32_t num_marked = 0;
88 uint32_t num_unknown = 0;
89 for (uint32_t y_grid = 0; y_grid < y_size; ++y_grid)
91 for (uint32_t x_grid = 0; x_grid < x_size; ++x_grid)
93 for (uint32_t z_grid = 0; z_grid < z_size; ++z_grid)
102 mapToWorld3D(x_grid, y_grid, z_grid, x_origin, y_origin, z_origin, x_res, y_res,
103 z_res, c.
x, c.
y, c.
z);
113 mapToWorld3D(x_grid, y_grid, z_grid, x_origin, y_origin, z_origin, x_res, y_res,
114 z_res, c.
x, c.
y, c.
z);
125 sensor_msgs::PointCloud cloud;
126 cloud.points.resize(num_marked);
127 cloud.channels.resize(1);
128 cloud.channels[0].values.resize(num_marked);
129 cloud.channels[0].name =
"rgb";
130 cloud.header.frame_id = frame_id;
131 cloud.header.stamp = stamp;
133 sensor_msgs::ChannelFloat32& chan = cloud.channels[0];
134 for (uint32_t i = 0; i < num_marked; ++i)
136 geometry_msgs::Point32& p = cloud.points[i];
137 float& cval = chan.values[i];
149 uint32_t col = (r << 16) | (g << 8) | b;
150 cval = *
reinterpret_cast<float*
>(&col);
157 sensor_msgs::PointCloud cloud;
158 cloud.points.resize(num_unknown);
159 cloud.channels.resize(1);
160 cloud.channels[0].values.resize(num_unknown);
161 cloud.channels[0].name =
"rgb";
162 cloud.header.frame_id = frame_id;
163 cloud.header.stamp = stamp;
165 sensor_msgs::ChannelFloat32& chan = cloud.channels[0];
166 for (uint32_t i = 0; i < num_unknown; ++i)
168 geometry_msgs::Point32& p = cloud.points[i];
169 float& cval = chan.values[i];
181 uint32_t col = (r << 16) | (g << 8) | b;
182 cval = *
reinterpret_cast<float*
>(&col);
189 ROS_DEBUG(
"Published %d points in %f seconds", num_marked + num_unknown, (end - start).toSec());
192 int main(
int argc,
char** argv)
194 ros::init(argc, argv,
"costmap_2d_cloud");
202 > (
"voxel_grid", 1, boost::bind(
voxelCallback, pub_marked, pub_unknown, _1));
voxel_grid::VoxelStatus status
void voxelCallback(const ros::Publisher &pub_marked, const ros::Publisher &pub_unknown, const costmap_2d::VoxelGridConstPtr &grid)
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())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< Cell > V_Cell
VoxelStatus getVoxel(unsigned int x, unsigned int y, unsigned int z)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
static void mapToWorld3D(const unsigned int mx, const unsigned int my, const unsigned int mz, const double origin_x, const double origin_y, const double origin_z, const double x_resolution, const double y_resolution, const double z_resolution, double &wx, double &wy, double &wz)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)