replay.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Aldebaran
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 #include "slam_gmapping.h"
00018 
00019 #include <iostream>
00020 #include <string>
00021 
00022 #include <boost/program_options.hpp>
00023 #include <ros/ros.h>
00024 
00025 int
00026 main(int argc, char** argv)
00027 {
00030     namespace po = boost::program_options; 
00031     po::options_description desc("Options"); 
00032     desc.add_options() 
00033     ("help", "Print help messages") 
00034     ("scan_topic",  po::value<std::string>()->default_value("/scan") ,"topic that contains the laserScan in the rosbag")
00035     ("bag_filename", po::value<std::string>()->required(), "ros bag filename") 
00036     ("seed", po::value<unsigned long int>()->default_value(0), "seed")
00037     ("max_duration_buffer", po::value<unsigned long int>()->default_value(99999), "max tf buffer duration")
00038     ("on_done", po::value<std::string>(), "command to execute when done") ;
00039     
00040     po::variables_map vm; 
00041     try 
00042     { 
00043         po::store(po::parse_command_line(argc, argv, desc),  
00044                   vm); // can throw 
00045         
00048         if ( vm.count("help")  ) 
00049         { 
00050             std::cout << "Basic Command Line Parameter App" << std::endl 
00051             << desc << std::endl; 
00052             return 0; 
00053         } 
00054         
00055         po::notify(vm); // throws on error, so do after help in case 
00056         // there are any problems 
00057     } 
00058     catch(po::error& e) 
00059     { 
00060         std::cerr << "ERROR: " << e.what() << std::endl << std::endl; 
00061         std::cerr << desc << std::endl; 
00062         return -1; 
00063     } 
00064     
00065     std::string bag_fname = vm["bag_filename"].as<std::string>();
00066     std::string scan_topic = vm["scan_topic"].as<std::string>();
00067     unsigned long int seed = vm["seed"].as<unsigned long int>();
00068     unsigned long int max_duration_buffer = vm["max_duration_buffer"].as<unsigned long int>();
00069     
00070     ros::init(argc, argv, "slam_gmapping");
00071     SlamGMapping gn(seed, max_duration_buffer) ;
00072     gn.startReplay(bag_fname, scan_topic);
00073     ROS_INFO("replay stopped.");
00074 
00075     if ( vm.count("on_done") )
00076     {
00077         // Run the "on_done" command and then exit
00078         system(vm["on_done"].as<std::string>().c_str());
00079     }
00080     else
00081     {
00082         ros::spin(); // wait so user can save the map
00083     }
00084     return(0);
00085     
00086     
00087 }
00088 


gmapping
Author(s): Brian Gerkey
autogenerated on Sat Jun 8 2019 19:40:33