36 #include <gtest/gtest.h>
40 #include <urdf_parser/urdf_parser.h>
43 #include <boost/filesystem/path.hpp>
44 #include <boost/filesystem/operations.hpp>
55 std::string robot_name =
"panda";
70 moveit_setup_assistant::MoveItConfigDataPtr config_data;
72 config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
73 config_data->srdf_->srdf_model_ = srdf_model_;
74 config_data->setRobotModel(robot_model_);
77 EXPECT_EQ(config_data->getControllers().size(), 0u);
80 config_data->addDefaultControllers();
83 size_t group_count = config_data->srdf_->srdf_model_->getGroups().size();
86 EXPECT_EQ(config_data->getControllers().size(), group_count);
89 char test_file[] =
"/tmp/msa_unittest_ros_controller.yaml";
92 EXPECT_EQ(config_data->outputROSControllersYAML(test_file),
true);
95 config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
98 EXPECT_EQ(config_data->getControllers().size(), 0u);
101 EXPECT_EQ(config_data->inputROSControllersYAML(test_file),
true);
104 EXPECT_EQ(config_data->getControllers().size(), group_count);
107 boost::filesystem::remove(test_file);
114 moveit_setup_assistant::MoveItConfigDataPtr config_data;
115 config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
117 boost::filesystem::path setup_assistant_path(config_data->setup_assistant_path_);
120 EXPECT_EQ(config_data->getSensorPluginConfig().size(), 0u);
123 config_data->input3DSensorsYAML(
124 (setup_assistant_path /
"templates/moveit_config_pkg_template/config/sensors_3d.yaml").
string());
125 auto configs = config_data->getSensorPluginConfig();
129 ASSERT_EQ(configs.size(), 2u);
131 EXPECT_EQ(configs[0][
"sensor_plugin"].getValue(), std::string(
"occupancy_map_monitor/PointCloudOctomapUpdater"));
133 EXPECT_EQ(configs[1][
"sensor_plugin"].getValue(), std::string(
"occupancy_map_monitor/DepthImageOctomapUpdater"));
140 moveit_setup_assistant::MoveItConfigDataPtr config_data;
141 config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
144 EXPECT_EQ(config_data->getSensorPluginConfig().size(), 0u);
147 char test_file[] =
"/tmp/msa_unittest_sensors.yaml";
150 EXPECT_EQ(config_data->output3DSensorPluginYAML(test_file),
true);
153 std::string default_file_path =
154 config_data->setup_assistant_path_ +
"/templates/moveit_config_pkg_template/config/sensors_3d.yaml";
162 config_data = std::make_shared<moveit_setup_assistant::MoveItConfigData>();
163 config_data->input3DSensorsYAML(default_file_path);
164 EXPECT_EQ(config_data->getSensorPluginConfig().size(), 2u);
165 EXPECT_EQ(config_data->output3DSensorPluginYAML(test_file),
true);
172 int main(
int argc,
char** argv)
174 testing::InitGoogleTest(&argc, argv);
175 return RUN_ALL_TESTS();