costmap_2d_cloud.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, Willow Garage, Inc.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
00026  */
00027 
00028 #include <ros/ros.h>
00029 #include <sensor_msgs/PointCloud.h>
00030 #include <costmap_2d/VoxelGrid.h>
00031 #include <voxel_grid/voxel_grid.h>
00032 
00033 static inline void mapToWorld3D(const unsigned int mx, const unsigned int my, const unsigned int mz,
00034                                       const double origin_x, const double origin_y, const double origin_z,
00035                                       const double x_resolution, const double y_resolution, const double z_resolution,
00036                                       double& wx, double& wy, double& wz)
00037 {
00038   // returns the center point of the cell
00039   wx = origin_x + (mx + 0.5) * x_resolution;
00040   wy = origin_y + (my + 0.5) * y_resolution;
00041   wz = origin_z + (mz + 0.5) * z_resolution;
00042 }
00043 
00044 struct Cell
00045 {
00046   double x;
00047   double y;
00048   double z;
00049   voxel_grid::VoxelStatus status;
00050 };
00051 typedef std::vector<Cell> V_Cell;
00052 
00053 float g_colors_r[] = {0.0f, 0.0f, 1.0f};
00054 float g_colors_g[] = {0.0f, 0.0f, 0.0f};
00055 float g_colors_b[] = {0.0f, 1.0f, 0.0f};
00056 float g_colors_a[] = {0.0f, 0.5f, 1.0f};
00057 
00058 V_Cell g_marked;
00059 V_Cell g_unknown;
00060 void voxelCallback(const ros::Publisher& pub_marked, const ros::Publisher& pub_unknown,
00061                    const costmap_2d::VoxelGridConstPtr& grid)
00062 {
00063   if (grid->data.empty())
00064   {
00065     ROS_ERROR("Received empty voxel grid");
00066     return;
00067   }
00068 
00069   ros::WallTime start = ros::WallTime::now();
00070 
00071   ROS_DEBUG("Received voxel grid");
00072   const std::string frame_id = grid->header.frame_id;
00073   const ros::Time stamp = grid->header.stamp;
00074   const uint32_t* data = &grid->data.front();
00075   const double x_origin = grid->origin.x;
00076   const double y_origin = grid->origin.y;
00077   const double z_origin = grid->origin.z;
00078   const double x_res = grid->resolutions.x;
00079   const double y_res = grid->resolutions.y;
00080   const double z_res = grid->resolutions.z;
00081   const uint32_t x_size = grid->size_x;
00082   const uint32_t y_size = grid->size_y;
00083   const uint32_t z_size = grid->size_z;
00084 
00085   g_marked.clear();
00086   g_unknown.clear();
00087   uint32_t num_marked = 0;
00088   uint32_t num_unknown = 0;
00089   for (uint32_t y_grid = 0; y_grid < y_size; ++y_grid)
00090   {
00091     for (uint32_t x_grid = 0; x_grid < x_size; ++x_grid)
00092     {
00093       for (uint32_t z_grid = 0; z_grid < z_size; ++z_grid)
00094       {
00095         voxel_grid::VoxelStatus status = voxel_grid::VoxelGrid::getVoxel(x_grid, y_grid, z_grid, x_size, y_size, z_size,
00096                                                                          data);
00097 
00098         if (status == voxel_grid::UNKNOWN)
00099         {
00100           Cell c;
00101           c.status = status;
00102           mapToWorld3D(x_grid, y_grid, z_grid, x_origin, y_origin, z_origin, x_res, y_res,
00103                                                    z_res, c.x, c.y, c.z);
00104 
00105           g_unknown.push_back(c);
00106 
00107           ++num_unknown;
00108         }
00109         else if (status == voxel_grid::MARKED)
00110         {
00111           Cell c;
00112           c.status = status;
00113           mapToWorld3D(x_grid, y_grid, z_grid, x_origin, y_origin, z_origin, x_res, y_res,
00114                                                    z_res, c.x, c.y, c.z);
00115 
00116           g_marked.push_back(c);
00117 
00118           ++num_marked;
00119         }
00120       }
00121     }
00122   }
00123 
00124   {
00125     sensor_msgs::PointCloud cloud;
00126     cloud.points.resize(num_marked);
00127     cloud.channels.resize(1);
00128     cloud.channels[0].values.resize(num_marked);
00129     cloud.channels[0].name = "rgb";
00130     cloud.header.frame_id = frame_id;
00131     cloud.header.stamp = stamp;
00132 
00133     sensor_msgs::ChannelFloat32& chan = cloud.channels[0];
00134     for (uint32_t i = 0; i < num_marked; ++i)
00135     {
00136       geometry_msgs::Point32& p = cloud.points[i];
00137       float& cval = chan.values[i];
00138       Cell& c = g_marked[i];
00139 
00140       p.x = c.x;
00141       p.y = c.y;
00142       p.z = c.z;
00143 
00144       uint32_t r = g_colors_r[c.status] * 255.0;
00145       uint32_t g = g_colors_g[c.status] * 255.0;
00146       uint32_t b = g_colors_b[c.status] * 255.0;
00147       // uint32_t a = g_colors_a[c.status] * 255.0;
00148 
00149       uint32_t col = (r << 16) | (g << 8) | b;
00150       cval = *reinterpret_cast<float*>(&col);
00151     }
00152 
00153     pub_marked.publish(cloud);
00154   }
00155 
00156   {
00157     sensor_msgs::PointCloud cloud;
00158     cloud.points.resize(num_unknown);
00159     cloud.channels.resize(1);
00160     cloud.channels[0].values.resize(num_unknown);
00161     cloud.channels[0].name = "rgb";
00162     cloud.header.frame_id = frame_id;
00163     cloud.header.stamp = stamp;
00164 
00165     sensor_msgs::ChannelFloat32& chan = cloud.channels[0];
00166     for (uint32_t i = 0; i < num_unknown; ++i)
00167     {
00168       geometry_msgs::Point32& p = cloud.points[i];
00169       float& cval = chan.values[i];
00170       Cell& c = g_unknown[i];
00171 
00172       p.x = c.x;
00173       p.y = c.y;
00174       p.z = c.z;
00175 
00176       uint32_t r = g_colors_r[c.status] * 255.0;
00177       uint32_t g = g_colors_g[c.status] * 255.0;
00178       uint32_t b = g_colors_b[c.status] * 255.0;
00179       // uint32_t a = g_colors_a[c.status] * 255.0;
00180 
00181       uint32_t col = (r << 16) | (g << 8) | b;
00182       cval = *reinterpret_cast<float*>(&col);
00183     }
00184 
00185     pub_unknown.publish(cloud);
00186   }
00187 
00188   ros::WallTime end = ros::WallTime::now();
00189   ROS_DEBUG("Published %d points in %f seconds", num_marked + num_unknown, (end - start).toSec());
00190 }
00191 
00192 int main(int argc, char** argv)
00193 {
00194   ros::init(argc, argv, "costmap_2d_cloud");
00195   ros::NodeHandle n;
00196 
00197   ROS_DEBUG("Startup");
00198 
00199   ros::Publisher pub_marked = n.advertise < sensor_msgs::PointCloud > ("voxel_marked_cloud", 2);
00200   ros::Publisher pub_unknown = n.advertise < sensor_msgs::PointCloud > ("voxel_unknown_cloud", 2);
00201   ros::Subscriber sub = n.subscribe < costmap_2d::VoxelGrid
00202       > ("voxel_grid", 1, boost::bind(voxelCallback, pub_marked, pub_unknown, _1));
00203 
00204   ros::spin();
00205 }


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:15