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 00037 #include <cv_bridge/cv_bridge.h> 00038 #include <opencv2/core/core.hpp> 00039 #include <tf/tf.h> 00040 00041 #include <nav_msgs/GetMap.h> 00042 #include <nav_msgs/MapMetaData.h> 00043 #include <ros/ros.h> 00044 #include <sensor_msgs/Image.h> 00045 #include <yaml-cpp/yaml.h> 00046 00047 // compute linear index for given map coords 00048 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) 00049 00057 class plannerMapServer 00058 { 00059 public: 00060 int negate; 00061 double freeThresh; 00062 double occThresh; 00063 double resolution; 00064 double origin[3]; 00065 bool deprecated; 00066 std::string frameID; 00067 std::string mapfname; 00068 ros::NodeHandle n; 00069 ros::Publisher mapPublisher; 00070 ros::Publisher metadataPublisher; 00071 ros::ServiceServer service; 00072 ros::Subscriber mapImageSubscriber; 00073 nav_msgs::GetMap::Response mapResponse; 00074 nav_msgs::MapMetaData metaDataMessage; 00075 00086 void loadMapFromMat(nav_msgs::GetMap::Response* resp, cv::Mat *opencvimg, double res, bool negate, double occThresh, 00087 double freeThresh, double* origin); 00088 00095 bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res); 00096 00101 void mapUpdateCallback(const sensor_msgs::Image& mapImg); 00102 00106 plannerMapServer(); 00107 };