39 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"test_perception");
 
   50     MoveItSetupTest::SetUp();
 
   51     config_data_->registerType(
"sensors", 
"moveit_setup::app::PerceptionConfig");
 
   65   EXPECT_EQ(sensors_config->getSensorPluginConfig().size(), 0u);
 
   68   auto configs = sensors_config->load3DSensorsYAML(default_yaml_path_);
 
   72   ASSERT_EQ(configs.size(), 2u);
 
   74   EXPECT_EQ(configs[0][
"sensor_plugin"], std::string(
"occupancy_map_monitor/PointCloudOctomapUpdater"));
 
   76   EXPECT_EQ(configs[1][
"sensor_plugin"], std::string(
"occupancy_map_monitor/DepthImageOctomapUpdater"));
 
   85   EXPECT_EQ(sensors_config->getSensorPluginConfig().size(), 0u);
 
   87   generateFiles<PerceptionConfig>(
"sensors");
 
   89   std::filesystem::path generated = output_dir_ / 
"config/sensors_3d.yaml";
 
   91   ASSERT_TRUE(std::filesystem::is_regular_file(generated));
 
   93   sensors_config->loadPrevious(std::filesystem::path(
"fake_path"), YAML::Node());
 
   96   EXPECT_EQ(sensors_config->getSensorPluginConfig().size(), 2u);
 
   98   generateFiles<PerceptionConfig>(
"sensors");
 
  103 int main(
int argc, 
char** argv)
 
  105   testing::InitGoogleTest(&argc, argv);
 
  106   rclcpp::init(argc, argv);
 
  107   return RUN_ALL_TESTS();
 
std::filesystem::path templates_path_
 
std::filesystem::path default_yaml_path_
 
Test environment with DataWarehouse setup and help for generating files in a temp dir.
 
moveit_setup::DataWarehousePtr config_data_
 
std::filesystem::path getSharePath(const std::string &package_name)
Return a path for the given package's share folder.
 
void expectYamlEquivalence(const YAML::Node &generated, const YAML::Node &reference, const std::filesystem::path &generated_path, const std::string &yaml_namespace="")
 
const rclcpp::Logger LOGGER
 
int main(int argc, char **argv)
 
TEST_F(PerceptionTest, ReadingSensorsConfig)