41 #include <gtest/gtest.h> 
   60     node_ = rclcpp::Node::make_shared(
"test_node");
 
   62     output_dir_ = std::filesystem::temp_directory_path() / 
"moveit_setup_test";
 
   73     std::vector<moveit_setup::GeneratedFilePtr> files;
 
   75     for (moveit_setup::GeneratedFilePtr& file : files)
 
  104 std::set<std::string> 
getKeys(
const YAML::Node& node)
 
  106   std::set<std::string> keys;
 
  107   for (
const auto& kv : node)
 
  109     keys.insert(kv.first.as<std::string>());
 
  115                            const std::filesystem::path& generated_path, 
const std::string& yaml_namespace = 
"")
 
  117   std::string msg_prefix =
 
  118       std::string(
"In ") + generated_path.c_str() + 
", node with namespace '" + yaml_namespace + 
"' ";
 
  120   if (generated.Type() != reference.Type())
 
  122     ADD_FAILURE() << msg_prefix + 
"does not have matching types!";
 
  126   if (generated.IsSequence())
 
  128     if (generated.size() != reference.size())
 
  130       ADD_FAILURE() << msg_prefix + 
"does not have matching sizes!";
 
  133     for (std::size_t i = 0; i < generated.size(); ++i)
 
  135       std::string sub_namespace = yaml_namespace + 
"[" + std::to_string(i) + 
"]";
 
  139   else if (generated.IsMap())
 
  141     std::set<std::string> gkeys = 
getKeys(generated), rkeys = 
getKeys(reference), missing_keys, common_keys, extra_keys;
 
  143     std::set_difference(rkeys.begin(), rkeys.end(), gkeys.begin(), gkeys.end(),
 
  144                         std::inserter(missing_keys, missing_keys.end()));
 
  145     std::set_difference(gkeys.begin(), gkeys.end(), rkeys.begin(), rkeys.end(),
 
  146                         std::inserter(extra_keys, extra_keys.end()));
 
  147     std::set_intersection(gkeys.begin(), gkeys.end(), rkeys.begin(), rkeys.end(),
 
  148                           std::inserter(common_keys, common_keys.end()));
 
  150     for (
const std::string& key : missing_keys)
 
  152       ADD_FAILURE() << msg_prefix << 
"is missing the key '" << key << 
"'";
 
  154     for (
const std::string& key : extra_keys)
 
  156       ADD_FAILURE() << msg_prefix << 
"has an extra key '" << key << 
"'";
 
  158     for (
const std::string& key : common_keys)
 
  160       std::string sub_namespace = yaml_namespace + 
"/" + key;
 
  166     EXPECT_EQ(generated.as<std::string>(), reference.as<std::string>())
 
  167         << msg_prefix << 
"does not match scalar values!";
 
  171 void expectYamlEquivalence(
const std::filesystem::path& generated_path, 
const std::filesystem::path& reference_path)
 
  173   EXPECT_EQ(std::filesystem::is_regular_file(generated_path), std::filesystem::is_regular_file(reference_path));
 
  174   if (!std::filesystem::is_regular_file(reference_path))
 
  178   const YAML::Node& generated = YAML::LoadFile(generated_path);
 
  179   const YAML::Node& reference = YAML::LoadFile(reference_path);
 
Test environment with DataWarehouse setup and help for generating files in a temp dir.
 
moveit_setup::DataWarehousePtr config_data_
 
void SetUp() override
Initialize the node, DataWarehouse and output dir.
 
void generateFiles(const std::string &config_name)
Helper function for generating all the files for a particular config to a temporary directory.
 
void TearDown() override
Clean up by removing all files when complete.
 
std::filesystem::path output_dir_
 
bool delete_when_finished_
 
rclcpp::Node::SharedPtr node_
 
moveit_setup::GeneratedTime placeholder_timestamp_
 
void initializeStep(SetupStep &setup_step)
 
Contains all of the non-GUI code necessary for doing one "screen" worth of setup.
 
void initialize(const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data)
Called after construction to initialize the step.
 
std::set< std::string > getKeys(const YAML::Node &node)
 
void expectYamlEquivalence(const YAML::Node &generated, const YAML::Node &reference, const std::filesystem::path &generated_path, const std::string &yaml_namespace="")
 
std::filesystem::file_time_type GeneratedTime