array_plugin_manager.cpp
Go to the documentation of this file.
2 #include <gtest/gtest.h>
3 #include <ros/ros.h>
4 
5 using namespace gpp_plugin;
6 
7 // currently disabled, since global-planner will segfault without calling init
8 // see https://github.com/ros-planning/navigation/issues/1026
9 TEST(ArrayPluginManagerTest, DISABLED_Loading) {
10  // here we check that we can properly load plugins, even if some are invalid
11  GlobalPlannerManager manager;
12  ros::NodeHandle nh("~");
13  manager.load("plugins", nh);
14 
15  // check the size of the array
16  ASSERT_EQ(manager.getPlugins().size(), 3);
17 
18  // now check the flags
19  const auto& plugins = manager.getPlugins();
20  std::array<bool, 3> on_success_break = {false, true, false};
21  std::array<bool, 3> on_failure_break = {true, false, true};
22 
23  // check the loaded flags
24  for (size_t ii = 0; ii != plugins.size(); ++ii) {
25  EXPECT_EQ(plugins.at(ii).first.on_success_break, on_success_break.at(ii));
26  EXPECT_EQ(plugins.at(ii).first.on_failure_break, on_failure_break.at(ii));
27  }
28 }
29 
30 TEST(CostmapPlannerManagerTest, DISABLED_Loading) {
31  // same as above, but with the CostmapPluginManager
32  CostmapPlannerManager manager;
33  ros::NodeHandle nh("~");
34  manager.load("plugins", nh);
35 
36  // check the size of the array
37  ASSERT_EQ(manager.getPlugins().size(), 3);
38 
39  // now check the flags
40  const auto& plugins = manager.getPlugins();
41  std::array<bool, 3> on_success_break = {false, true, false};
42  std::array<bool, 3> on_failure_break = {true, false, true};
43 
44  // check the loaded flags
45  for (size_t ii = 0; ii != plugins.size(); ++ii) {
46  EXPECT_EQ(plugins.at(ii).first.on_success_break, on_success_break.at(ii));
47  EXPECT_EQ(plugins.at(ii).first.on_failure_break, on_failure_break.at(ii));
48  }
49 }
50 
51 TEST(ArrayPluginManagerTest, NotAnArray) {
52  // here we check that we survive really bad user configs
53  GlobalPlannerManager manager;
54  ros::NodeHandle nh("~");
55  manager.load("not_an_array", nh);
56 
57  // nothing to load here
58  EXPECT_TRUE(manager.getPlugins().empty());
59 }
60 
61 TEST(ArrayPluginManagerTest, Missing) {
62  // here we check that we survive if the user forgets to define the parameter
63  GlobalPlannerManager manager;
64  ros::NodeHandle nh("~");
65  manager.load("missing", nh);
66 
67  // nothing to load here
68  EXPECT_TRUE(manager.getPlugins().empty());
69 }
70 
71 int
72 main(int argc, char** argv) {
73  ros::init(argc, argv, "array_plugin_manager");
74  ros::NodeHandle nh;
75  testing::InitGoogleTest(&argc, argv);
76  return RUN_ALL_TESTS();
77 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
gpp_plugin.hpp
gpp_plugin::PluginGroup::getPlugins
const PluginMap & getPlugins() const noexcept
Definition: gpp_plugin.hpp:156
main
int main(int argc, char **argv)
Definition: array_plugin_manager.cpp:72
TEST
TEST(ArrayPluginManagerTest, DISABLED_Loading)
Definition: array_plugin_manager.cpp:9
gpp_plugin::CostmapPlannerManager
Loads either CostmapPlanner or BaseGlobalPlanner plugins under a uniform interface.
Definition: gpp_plugin.hpp:349
gpp_plugin::ArrayPluginManager
Loads an array of plugins.
Definition: gpp_plugin.hpp:297
gpp_plugin
Definition: gpp_plugin.hpp:41
gpp_plugin::ArrayPluginManager::load
void load(const std::string &_resource, ros::NodeHandle &_nh)
Definition: gpp_plugin.cpp:84
ros::NodeHandle


gpp_plugin
Author(s):
autogenerated on Wed Mar 2 2022 00:21:23