map_compressor.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2012, Robert Bosch LLC.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Robert Bosch nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036 
00037 #include "ros/ros.h"
00038 #include "std_msgs/String.h"
00039 #include "std_msgs/Int64MultiArray.h"
00040 #include "std_msgs/MultiArrayLayout.h"
00041 #include "std_msgs/MultiArrayDimension.h"
00042 #include "nav_msgs/OccupancyGrid.h"
00043 #include "map_compressor/CompressedOccupancyGrid.h"
00044 #include <vector>
00045 #include <sstream>
00046 
00047 ros::Publisher comp_map_pub;
00048 
00049 void compressCallback(const nav_msgs::OccupancyGrid::ConstPtr& msg)
00050 {
00051   ROS_INFO("Map width: [%d]\n Map height: [%d] ", msg->info.width, msg->info.height);
00052   uint32_t w = msg->info.width;
00053   uint32_t h = msg->info.height;
00054   uint32_t s_uncomp = w*h;
00055   uint32_t c0 = 0;
00056   uint32_t c1 = 0;
00057   uint32_t c2 = 0;
00058   int8_t current_val = msg->data[0];
00059   int8_t prev_val = msg->data[0];
00060   uint64_t count = 0;
00061   int num_switch = 0;
00062   std::vector<int64_t> compressed_data;
00063   map_compressor::CompressedOccupancyGrid compressed_map;
00064   
00065   for(uint32_t i=0; i<s_uncomp; i++){
00066     
00067     current_val = msg->data[i];
00068     
00069     if(current_val == -1)c0++;
00070     else if(current_val == 100)c1++;
00071     else if(current_val == 0)c2++;
00072 
00073     if(current_val != prev_val){
00074       num_switch++;
00075       //ROS_INFO("%d %ds;", count, prev_val);
00076 
00077       compressed_data.push_back(count);
00078       compressed_data.push_back((int64_t)prev_val);      
00079 
00080       count=0;
00081       prev_val = current_val;
00082     }
00083        
00084     count++;  
00085   }
00086 
00087   // Let's pack and publish our compressed map
00088   compressed_map.header = msg->header;
00089   compressed_map.info = msg->info;
00090   compressed_map.data = compressed_data;
00091   
00092   ROS_INFO("Map histogram:\n[%d] -1s,\n[%d] 100s,\n[%d] 0s ", c0, c1, c2);
00093 
00094   ROS_INFO("Map size before compression: %d\n", s_uncomp);
00095   
00096   ROS_INFO("Grid value changed %d times\n", (int)(compressed_data.size()/2));
00097 
00098   //for(uint32_t i=0; i<compressed_data.size()-1; i+=2){
00099   //  printf("[%d]: %d; ",compressed_data[i], compressed_data[i+1]);
00100   //}
00101 
00102   comp_map_pub.publish(compressed_map);
00103     
00104 }
00105 
00106 int main(int argc, char **argv)
00107 {
00108   ros::init(argc, argv, "map_compressor");
00109   ros::NodeHandle n;
00110   ros::Subscriber map_sub = n.subscribe("map",1,compressCallback);
00111   comp_map_pub = n.advertise<map_compressor::CompressedOccupancyGrid>("compressed_map",1);
00112   ros::spin();
00113   return 0;
00114 }


map_compressor
Author(s): Bener Suay
autogenerated on Fri Jan 3 2014 11:11:19