replay.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #include "slam_gmapping.h"
18 
19 #include <iostream>
20 #include <string>
21 
22 #include <boost/program_options.hpp>
23 #include <ros/ros.h>
24 
25 int
26 main(int argc, char** argv)
27 {
30  namespace po = boost::program_options;
31  po::options_description desc("Options");
32  desc.add_options()
33  ("help", "Print help messages")
34  ("scan_topic", po::value<std::string>()->default_value("/scan") ,"topic that contains the laserScan in the rosbag")
35  ("bag_filename", po::value<std::string>()->required(), "ros bag filename")
36  ("seed", po::value<unsigned long int>()->default_value(0), "seed")
37  ("max_duration_buffer", po::value<unsigned long int>()->default_value(99999), "max tf buffer duration")
38  ("on_done", po::value<std::string>(), "command to execute when done") ;
39 
40  po::variables_map vm;
41  try
42  {
43  po::store(po::parse_command_line(argc, argv, desc),
44  vm); // can throw
45 
48  if ( vm.count("help") )
49  {
50  std::cout << "Basic Command Line Parameter App" << std::endl
51  << desc << std::endl;
52  return 0;
53  }
54 
55  po::notify(vm); // throws on error, so do after help in case
56  // there are any problems
57  }
58  catch(po::error& e)
59  {
60  std::cerr << "ERROR: " << e.what() << std::endl << std::endl;
61  std::cerr << desc << std::endl;
62  return -1;
63  }
64 
65  std::string bag_fname = vm["bag_filename"].as<std::string>();
66  std::string scan_topic = vm["scan_topic"].as<std::string>();
67  unsigned long int seed = vm["seed"].as<unsigned long int>();
68  unsigned long int max_duration_buffer = vm["max_duration_buffer"].as<unsigned long int>();
69 
70  ros::init(argc, argv, "slam_gmapping");
71  SlamGMapping gn(seed, max_duration_buffer) ;
72  gn.startReplay(bag_fname, scan_topic);
73  ROS_INFO("replay stopped.");
74 
75  if ( vm.count("on_done") )
76  {
77  // Run the "on_done" command and then exit
78  system(vm["on_done"].as<std::string>().c_str());
79  }
80  else
81  {
82  ros::spin(); // wait so user can save the map
83  }
84  return(0);
85 
86 
87 }
88 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
void startReplay(const std::string &bag_fname, std::string scan_topic)
#define ROS_INFO(...)
int main(int argc, char **argv)
Definition: replay.cpp:26


gmapping
Author(s): Brian Gerkey
autogenerated on Wed Jun 5 2019 21:48:25