many_map_node.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
35 #include <pluginlib/class_loader.h>
36 #include <string>
37 
38 int main(int argc, char** argv)
39 {
40  ros::init(argc, argv, "plan");
41  ros::NodeHandle private_nh("~");
42  TFListenerPtr tf = std::make_shared<tf::TransformListener>(ros::Duration(10));
43 
44  pluginlib::ClassLoader<nav_core2::GlobalPlanner> global_planner_loader("nav_core2", "nav_core2::GlobalPlanner");
45 
46  std::string planner_name;
47  private_nh.param("global_planner", planner_name, std::string("dlux_global_planner::DluxGlobalPlanner"));
48  boost::shared_ptr<nav_core2::GlobalPlanner> global_planner = global_planner_loader.createInstance(planner_name);
49 
50  global_planner_tests::many_map_test_suite(*global_planner, tf, global_planner_loader.getName(planner_name),
51  "package://global_planner_tests/config/standard_tests.yaml",
52  true, true, false);
53 
54  return (0);
55 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool many_map_test_suite(nav_core2::GlobalPlanner &planner, TFListenerPtr tf, const std::string &planner_name, const std::string &maps_list_filename="package://global_planner_tests/config/standard_tests.yaml", bool check_exception_type=true, bool verbose=false, bool quit_early=true)
Run a collection of global_planner_tests on the provided maps.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
int main(int argc, char **argv)
std::shared_ptr< tf::TransformListener > TFListenerPtr


global_planner_tests
Author(s):
autogenerated on Wed Jun 26 2019 20:06:09