image_loader.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 /*
00031  * This file contains helper functions for loading images as maps.
00032  * 
00033  * Author: Brian Gerkey
00034  */
00035 
00036 #include <cstring>
00037 #include <stdexcept>
00038 
00039 #include <stdlib.h>
00040 #include <stdio.h>
00041 
00042 // We use SDL_image to load the image from disk
00043 #include <SDL/SDL_image.h>
00044 
00045 #include "map_server/image_loader.h"
00046 #include <tf/tf.h>
00047 
00048 // compute linear index for given map coords
00049 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
00050 
00051 namespace map_server
00052 {
00053 
00054 void
00055 loadMapFromFile(nav_msgs::GetMap::Response* resp,
00056                 const char* fname, double res, bool negate,
00057                 double occ_th, double free_th, double* origin,
00058                 MapMode mode)
00059 {
00060   SDL_Surface* img;
00061 
00062   unsigned char* pixels;
00063   unsigned char* p;
00064   unsigned char value;
00065   int rowstride, n_channels, avg_channels;
00066   unsigned int i,j;
00067   int k;
00068   double occ;
00069   int alpha;
00070   int color_sum;
00071   double color_avg;
00072 
00073   // Load the image using SDL.  If we get NULL back, the image load failed.
00074   if(!(img = IMG_Load(fname)))
00075   {
00076     std::string errmsg = std::string("failed to open image file \"") + 
00077             std::string(fname) + std::string("\"");
00078     throw std::runtime_error(errmsg);
00079   }
00080 
00081   // Copy the image data into the map structure
00082   resp->map.info.width = img->w;
00083   resp->map.info.height = img->h;
00084   resp->map.info.resolution = res;
00085   resp->map.info.origin.position.x = *(origin);
00086   resp->map.info.origin.position.y = *(origin+1);
00087   resp->map.info.origin.position.z = 0.0;
00088   tf::Quaternion q;
00089   q.setRPY(0,0, *(origin+2));
00090   resp->map.info.origin.orientation.x = q.x();
00091   resp->map.info.origin.orientation.y = q.y();
00092   resp->map.info.origin.orientation.z = q.z();
00093   resp->map.info.origin.orientation.w = q.w();
00094 
00095   // Allocate space to hold the data
00096   resp->map.data.resize(resp->map.info.width * resp->map.info.height);
00097 
00098   // Get values that we'll need to iterate through the pixels
00099   rowstride = img->pitch;
00100   n_channels = img->format->BytesPerPixel;
00101 
00102   // NOTE: Trinary mode still overrides here to preserve existing behavior.
00103   // Alpha will be averaged in with color channels when using trinary mode.
00104   if (mode==TRINARY || !img->format->Amask)
00105     avg_channels = n_channels;
00106   else
00107     avg_channels = n_channels - 1;
00108 
00109   // Copy pixel data into the map structure
00110   pixels = (unsigned char*)(img->pixels);
00111   for(j = 0; j < resp->map.info.height; j++)
00112   {
00113     for (i = 0; i < resp->map.info.width; i++)
00114     {
00115       // Compute mean of RGB for this pixel
00116       p = pixels + j*rowstride + i*n_channels;
00117       color_sum = 0;
00118       for(k=0;k<avg_channels;k++)
00119         color_sum += *(p + (k));
00120       color_avg = color_sum / (double)avg_channels;
00121 
00122       if (n_channels == 1)
00123           alpha = 1;
00124       else
00125           alpha = *(p+n_channels-1);
00126 
00127       if(negate)
00128         color_avg = 255 - color_avg;
00129 
00130       if(mode==RAW){
00131           value = color_avg;
00132           resp->map.data[MAP_IDX(resp->map.info.width,i,resp->map.info.height - j - 1)] = value;
00133           continue;
00134       }
00135 
00136 
00137       // If negate is true, we consider blacker pixels free, and whiter
00138       // pixels free.  Otherwise, it's vice versa.
00139       occ = (255 - color_avg) / 255.0;
00140       
00141       // Apply thresholds to RGB means to determine occupancy values for
00142       // map.  Note that we invert the graphics-ordering of the pixels to
00143       // produce a map with cell (0,0) in the lower-left corner.
00144       if(occ > occ_th)
00145         value = +100;
00146       else if(occ < free_th)
00147         value = 0;
00148       else if(mode==TRINARY || alpha < 1.0)
00149         value = -1;
00150       else {
00151         double ratio = (occ - free_th) / (occ_th - free_th);
00152         value = 99 * ratio;
00153       }
00154            
00155       resp->map.data[MAP_IDX(resp->map.info.width,i,resp->map.info.height - j - 1)] = value;
00156     }
00157   }
00158 
00159   SDL_FreeSurface(img);
00160 }
00161 
00162 }


map_server
Author(s): Brian Gerkey, Tony Pratkanis, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:05