42 #define USAGE "\nUSAGE: octomap_server <map.[bt|ot]>\n" \ 43 " map.bt: inital octomap 3D map file to read\n" 47 int main(
int argc,
char** argv){
51 std::string mapFilename(
""), mapFilenameParam(
"");
53 if (argc > 2 || (argc == 2 && std::string(argv[1]) ==
"-h")){
62 mapFilename = std::string(argv[1]);
65 if (private_nh.
getParam(
"map_file", mapFilenameParam)) {
66 if (mapFilename !=
"") {
67 ROS_WARN(
"map_file is specified by the argument '%s' and rosparam '%s'. now loads '%s'", mapFilename.c_str(), mapFilenameParam.c_str(), mapFilename.c_str());
69 mapFilename = mapFilenameParam;
73 if (mapFilename !=
"") {
75 ROS_ERROR(
"Could not open file %s", mapFilename.c_str());
82 }
catch(std::runtime_error& e){
83 ROS_ERROR(
"octomap_server exception: %s", e.what());
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, std::string &s) const
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
virtual bool openFile(const std::string &filename)