cost_interpretation_tables.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include <nav_grid_pub_sub/cost_interpretation_tables.h>
00036 #include <vector>
00037 
00038 namespace nav_grid_pub_sub
00039 {
00040 
00041 std::vector<unsigned char> pixelColoringInterpretation(const double free_threshold, const double occupied_threshold)
00042 {
00043   std::vector<unsigned char> cost_interpretation_table(256);
00044   for (unsigned int i = 0; i < cost_interpretation_table.size(); i++)
00045   {
00046     double intensity = static_cast<double>(i) / 255.0;
00047     if (intensity > occupied_threshold)
00048     {
00049       cost_interpretation_table[i] = +100;
00050     }
00051     else if (intensity < free_threshold)
00052     {
00053       cost_interpretation_table[i] = 0;
00054     }
00055     else
00056     {
00057       cost_interpretation_table[i] = -1;
00058     }
00059   }
00060   return cost_interpretation_table;
00061 }
00062 
00063 std::vector<unsigned char> grayScaleInterpretation(const double free_threshold, const double occupied_threshold)
00064 {
00065   std::vector<unsigned char> cost_interpretation_table(256);
00066   for (unsigned int i = 0; i < cost_interpretation_table.size(); i++)
00067   {
00068     double intensity = static_cast<double>(i) / 255.0;
00069     if (intensity > occupied_threshold)
00070     {
00071       cost_interpretation_table[i] = +100;
00072     }
00073     else if (intensity < free_threshold)
00074     {
00075       cost_interpretation_table[i] = 0;
00076     }
00077     else
00078     {
00079       // scale from [free_threshold, occupied_threshold] to [1, 99]
00080       cost_interpretation_table[i] = 99 * (intensity - free_threshold) / (occupied_threshold - free_threshold);
00081     }
00082   }
00083   return cost_interpretation_table;
00084 }
00085 
00086 std::vector<unsigned char> getOccupancyInput(bool trinary, bool use_unknown_value)
00087 {
00088   std::vector<unsigned char> cost_interpretation_table(256);
00089   for (unsigned int i = 0; i < cost_interpretation_table.size(); i++)
00090   {
00091     unsigned char value;
00092     if (use_unknown_value && i == 255)
00093       value = 255;
00094     else if (!use_unknown_value && i == 255)
00095       value = 0;
00096     else if (i >= 100)
00097       value = 254;
00098     else if (trinary)
00099       value = 0;
00100     else
00101     {
00102       double scale = static_cast<double>(i) / 100.0;
00103       value = static_cast<unsigned char>(scale * 254);
00104     }
00105     cost_interpretation_table[i] = value;
00106   }
00107   return cost_interpretation_table;
00108 }
00109 
00110 }  // namespace nav_grid_pub_sub


nav_grid_pub_sub
Author(s):
autogenerated on Wed Jun 26 2019 20:09:52