file.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 
00039 #include <occupancy_grid_utils/file.h>
00040 #include <tf/transform_datatypes.h>
00041 #include <nav_msgs/GetMap.h>
00042 
00043 namespace occupancy_grid_utils
00044 {
00045 
00046 namespace nm=nav_msgs;
00047 namespace gm=geometry_msgs;
00048 
00049 /************************************************************
00050  * Implementation
00051  * This is lifted from map_server, which unfortunately
00052  * does not export the library in its manifest
00053  ***********************************************************/
00054 
00055 
00056 #include <cstring>
00057 #include <stdexcept>
00058 
00059 #include <stdlib.h>
00060 #include <stdio.h>
00061 
00062 // We use SDL_image to load the image from disk
00063 #include <SDL/SDL_image.h>
00064 
00065 #include "LinearMath/btMatrix3x3.h"
00066 
00067 // compute linear index for given map coords
00068 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
00069 
00070 void
00071 loadMapFromFile(nav_msgs::GetMap::Response* resp,
00072                 const char* fname, double res, bool negate,
00073                 double occ_th, double free_th, double* origin)
00074 {
00075   SDL_Surface* img;
00076 
00077   unsigned char* pixels;
00078   unsigned char* p;
00079   int rowstride, n_channels;
00080   unsigned int i,j;
00081   int k;
00082   double occ;
00083   int color_sum;
00084   double color_avg;
00085 
00086   // Load the image using SDL.  If we get NULL back, the image load failed.
00087   if(!(img = IMG_Load(fname)))
00088   {
00089     std::string errmsg = std::string("failed to open image file \"") + 
00090       std::string(fname) + std::string("\"");
00091     throw std::runtime_error(errmsg);
00092   }
00093 
00094   // Copy the image data into the map structure
00095   resp->map.info.width = img->w;
00096   resp->map.info.height = img->h;
00097   resp->map.info.resolution = res;
00098   resp->map.info.origin.position.x = *(origin);
00099   resp->map.info.origin.position.y = *(origin+1);
00100   resp->map.info.origin.position.z = 0.0;
00101   btQuaternion q;
00102   q.setEuler(*(origin + 2), 0, 0);
00103   resp->map.info.origin.orientation.x = q.x();
00104   resp->map.info.origin.orientation.y = q.y();
00105   resp->map.info.origin.orientation.z = q.z();
00106   resp->map.info.origin.orientation.w = q.w();
00107 
00108   // Allocate space to hold the data
00109   resp->map.data.resize(resp->map.info.width * resp->map.info.height);
00110 
00111   // Get values that we'll need to iterate through the pixels
00112   rowstride = img->pitch;
00113   n_channels = img->format->BytesPerPixel;
00114 
00115   // Copy pixel data into the map structure
00116   pixels = (unsigned char*)(img->pixels);
00117   for(j = 0; j < resp->map.info.height; j++)
00118   {
00119     for (i = 0; i < resp->map.info.width; i++)
00120     {
00121       // Compute mean of RGB for this pixel
00122       p = pixels + j*rowstride + i*n_channels;
00123       color_sum = 0;
00124       for(k=0;k<n_channels;k++)
00125         color_sum += *(p + (k));
00126       color_avg = color_sum / (double)n_channels;
00127 
00128       // If negate is true, we consider blacker pixels free, and whiter
00129       // pixels free.  Otherwise, it's vice versa.
00130       if(negate)
00131         occ = color_avg / 255.0;
00132       else
00133         occ = (255 - color_avg) / 255.0;
00134       
00135       // Apply thresholds to RGB means to determine occupancy values for
00136       // map.  Note that we invert the graphics-ordering of the pixels to
00137       // produce a map with cell (0,0) in the lower-left corner.
00138       if(occ > occ_th)
00139         resp->map.data[MAP_IDX(resp->map.info.width,i,resp->map.info.height - j - 1)] = +100;
00140       else if(occ < free_th)
00141         resp->map.data[MAP_IDX(resp->map.info.width,i,resp->map.info.height - j - 1)] = 0;
00142       else
00143         resp->map.data[MAP_IDX(resp->map.info.width,i,resp->map.info.height - j - 1)] = -1;
00144     }
00145   }
00146 
00147   SDL_FreeSurface(img);
00148 }
00149 
00150 
00151 /************************************************************
00152  * Interface
00153  ***********************************************************/
00154 
00155 nm::OccupancyGrid::Ptr loadGrid (const std::string& fname,
00156                                  const double resolution,
00157                                  const gm::Pose& origin_pose)
00158 {
00159   double origin[3];
00160   origin[0] = origin_pose.position.x;
00161   origin[1] = origin_pose.position.y;
00162   origin[2] = tf::getYaw(origin_pose.orientation);
00163 
00164   nm::GetMap::Response resp;
00165   loadMapFromFile(&resp, fname.c_str(), resolution, false,
00166                   DEFAULT_OCC_THRESHOLD, DEFAULT_FREE_THRESHOLD,
00167                   origin);
00168   nm::OccupancyGrid::Ptr grid(new nm::OccupancyGrid(resp.map));
00169   return grid;
00170 }
00171 
00172 
00173 
00174 } // namespace


occupancy_grid_utils
Author(s): Bhaskara Marthi
autogenerated on Thu Dec 12 2013 13:17:54