00001 00009 /* 00010 * Copyright (c) 2009-2012, A. Hornung, University of Freiburg 00011 * All rights reserved. 00012 * 00013 * Redistribution and use in source and binary forms, with or without 00014 * modification, are permitted provided that the following conditions are met: 00015 * 00016 * * Redistributions of source code must retain the above copyright 00017 * notice, this list of conditions and the following disclaimer. 00018 * * Redistributions in binary form must reproduce the above copyright 00019 * notice, this list of conditions and the following disclaimer in the 00020 * documentation and/or other materials provided with the distribution. 00021 * * Neither the name of the University of Freiburg nor the names of its 00022 * contributors may be used to endorse or promote products derived from 00023 * this software without specific prior written permission. 00024 * 00025 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00026 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00027 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00028 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00029 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00030 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00031 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00032 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00033 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00034 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00035 * POSSIBILITY OF SUCH DAMAGE. 00036 */ 00037 00038 00039 #include <ros/ros.h> 00040 #include <octomap_server/OctomapServerMultilayer.h> 00041 00042 #define USAGE "\nUSAGE: octomap_server_multilayer <map.bt>\n" \ 00043 " map.bt: inital octomap 3D map file to read\n" 00044 00045 using namespace octomap_server; 00046 00047 int main(int argc, char** argv){ 00048 ros::init(argc, argv, "octomap_server_multilayer"); 00049 std::string mapFilename(""); 00050 00051 if (argc > 2 || (argc == 2 && std::string(argv[1]) == "-h")){ 00052 ROS_ERROR("%s", USAGE); 00053 exit(-1); 00054 } 00055 00056 00057 OctomapServerMultilayer server; 00058 ros::spinOnce(); 00059 00060 if (argc == 2){ 00061 mapFilename = std::string(argv[1]); 00062 if (!server.openFile(mapFilename)){ 00063 ROS_ERROR("Could not open file %s", mapFilename.c_str()); 00064 exit(1); 00065 } 00066 } 00067 00068 00069 00070 00071 try{ 00072 ros::spin(); 00073 }catch(std::runtime_error& e){ 00074 ROS_ERROR("octomap_server_multilayer exception: %s", e.what()); 00075 return -1; 00076 } 00077 00078 return 0; 00079 }