00001 /* 00002 * Copyright (c) 2009-2013, A. Hornung, University of Freiburg 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 University of Freiburg 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 #include <ros/ros.h> 00032 #include <octomap_server/OctomapServerMultilayer.h> 00033 00034 #define USAGE "\nUSAGE: octomap_server_multilayer <map.bt>\n" \ 00035 " map.bt: inital octomap 3D map file to read\n" 00036 00037 using namespace octomap_server; 00038 00039 int main(int argc, char** argv){ 00040 ros::init(argc, argv, "octomap_server_multilayer"); 00041 std::string mapFilename(""); 00042 00043 if (argc > 2 || (argc == 2 && std::string(argv[1]) == "-h")){ 00044 ROS_ERROR("%s", USAGE); 00045 exit(-1); 00046 } 00047 00048 00049 OctomapServerMultilayer server; 00050 ros::spinOnce(); 00051 00052 if (argc == 2){ 00053 mapFilename = std::string(argv[1]); 00054 if (!server.openFile(mapFilename)){ 00055 ROS_ERROR("Could not open file %s", mapFilename.c_str()); 00056 exit(1); 00057 } 00058 } 00059 00060 00061 00062 00063 try{ 00064 ros::spin(); 00065 }catch(std::runtime_error& e){ 00066 ROS_ERROR("octomap_server_multilayer exception: %s", e.what()); 00067 return -1; 00068 } 00069 00070 return 0; 00071 }