image_to_map_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, CoroWare
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, Stanford U. 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 #include "ros/ros.h"
00031 
00032 #include <nav_msgs/GetMap.h>
00033 #include <geometry_msgs/Quaternion.h>
00034 #include <geometry_msgs/PoseStamped.h>
00035 #include <sensor_msgs/image_encodings.h>
00036 #include <image_transport/image_transport.h>
00037 #include <Eigen/Geometry>
00038 #include <HectorMapTools.h>
00039 #include <math.h>
00040 #include <tf/transform_datatypes.h>
00041 
00042 using namespace std;
00043 
00044 //resolution of the map
00045 double resolution = 0.05; 
00046 
00050 class MapAsImageProvider
00051 {
00052 
00053 public:
00054 
00055   // Publisher for the map
00056   ros::Publisher map_publisher;
00057 
00058   //Subscriber to the image topic
00059   image_transport::Subscriber image_transport_subscriber_map;
00060 
00061   image_transport::ImageTransport* image_transport_;
00062 
00063   ros::NodeHandle n_;
00064   ros::NodeHandle pn_;
00065 
00066 
00067   MapAsImageProvider()
00068     : pn_("~")
00069   {
00070 
00071     image_transport_ = new image_transport::ImageTransport(n_);
00072     //subscribe to the image topic representing the map
00073     image_transport_subscriber_map = image_transport_->subscribe("map_image_raw", 1, &MapAsImageProvider::mapCallback,this); 
00074     // publish the map as an occupancy grid
00075     map_publisher = n_.advertise<nav_msgs::OccupancyGrid>("/map_from_jpeg", 50); 
00076 
00077 
00078     ROS_INFO("Image to Map node started.");
00079   }
00080 
00081   ~MapAsImageProvider()
00082   {
00083     delete image_transport_;
00084   }
00085 
00086 
00087   //The map->image conversion runs every time a new map is received
00088   void mapCallback(const sensor_msgs::ImageConstPtr& image)
00089   {
00090 
00091     nav_msgs::OccupancyGrid map;
00092     //fill in some map parameters
00093     map.header.stamp = image->header.stamp;
00094     map.header.frame_id = "map";
00095     map.info.width = image->width;
00096     map.info.height = image->height;
00097     map.info.origin.orientation.w = 1;
00098     map.info.resolution = resolution;
00099     map.info.origin.position.x = -((image->width + 1) * map.info.resolution * 0.5f);
00100     map.info.origin.position.y = -((image->height + 1) * map.info.resolution * 0.5f);
00101 
00102     //read the pixels of the image and fill the map table
00103     int data;
00104     for(int i=image->height -1; i>=0; i--)
00105     {
00106         for (unsigned int j=0; j<image->width;j++)
00107         {
00108             data = image->data[i*image->width + j];
00109             if(data >=123 && data <= 131){
00110                 map.data.push_back(-1);
00111             }
00112             else if (data >=251 && data <= 259){
00113                 map.data.push_back(0);
00114             }
00115             else
00116                 map.data.push_back(100);
00117         }
00118     }
00119     //publish the map
00120     map_publisher.publish(map); 
00121   }
00122 
00123 };
00124 
00125 int main(int argc, char** argv)
00126 {
00127   ros::init(argc, argv, "image_to_map_node");
00128 
00129   ros::NodeHandle nh("~");
00130   nh.param("resolution", resolution, 0.05); 
00131 
00132   // The 
00133   MapAsImageProvider map_image_provider;
00134 
00135   ros::spin();
00136 
00137   return 0;
00138 }


map_to_jpeg
Author(s):
autogenerated on Sun Oct 5 2014 23:18:27