moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
testing_utils.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2022, Metro Robots
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 Metro Robots 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 OWNER 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 *********************************************************************/
34
35/* Author: David V. Lu!! */
36
37#pragma once
38
41#include <gtest/gtest.h>
42#include <algorithm>
43#include <filesystem>
44
45namespace moveit_setup
46{
50class MoveItSetupTest : public ::testing::Test
51{
52protected:
58 void SetUp() override
59 {
60 node_ = rclcpp::Node::make_shared("test_node");
61 config_data_ = std::make_shared<moveit_setup::DataWarehouse>(node_);
62 output_dir_ = std::filesystem::temp_directory_path() / "moveit_setup_test";
63 }
64
70 template <typename T>
71 void generateFiles(const std::string& config_name)
72 {
73 std::vector<moveit_setup::GeneratedFilePtr> files;
74 config_data_->get<T>(config_name)->collectFiles(output_dir_, placeholder_timestamp_, files);
75 for (moveit_setup::GeneratedFilePtr& file : files)
76 {
77 file->write();
78 }
79 }
80
81 void initializeStep(SetupStep& setup_step)
82 {
83 setup_step.initialize(node_, config_data_);
84 }
85
91 void TearDown() override
92 {
94 std::filesystem::remove_all(output_dir_);
95 }
96
97 rclcpp::Node::SharedPtr node_;
98 moveit_setup::DataWarehousePtr config_data_;
99 std::filesystem::path output_dir_;
101 bool delete_when_finished_{ true }; // Set to false to keep the files around
102};
103
104std::set<std::string> getKeys(const YAML::Node& node)
105{
106 std::set<std::string> keys;
107 for (const auto& kv : node)
108 {
109 keys.insert(kv.first.as<std::string>());
110 }
111 return keys;
112}
113
114void expectYamlEquivalence(const YAML::Node& generated, const YAML::Node& reference,
115 const std::filesystem::path& generated_path, const std::string& yaml_namespace = "")
116{
117 std::string msg_prefix =
118 std::string("In ") + generated_path.c_str() + ", node with namespace '" + yaml_namespace + "' ";
119
120 if (generated.Type() != reference.Type())
121 {
122 ADD_FAILURE() << msg_prefix + "does not have matching types!";
123 return;
124 }
125
126 if (generated.IsSequence())
127 {
128 if (generated.size() != reference.size())
129 {
130 ADD_FAILURE() << msg_prefix + "does not have matching sizes!";
131 return;
132 }
133 for (std::size_t i = 0; i < generated.size(); ++i)
134 {
135 std::string sub_namespace = yaml_namespace + "[" + std::to_string(i) + "]";
136 expectYamlEquivalence(generated[i], reference[i], generated_path, sub_namespace);
137 }
138 }
139 else if (generated.IsMap())
140 {
141 std::set<std::string> gkeys = getKeys(generated), rkeys = getKeys(reference), missing_keys, common_keys, extra_keys;
142
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()));
149
150 for (const std::string& key : missing_keys)
151 {
152 ADD_FAILURE() << msg_prefix << "is missing the key '" << key << "'";
153 }
154 for (const std::string& key : extra_keys)
155 {
156 ADD_FAILURE() << msg_prefix << "has an extra key '" << key << "'";
157 }
158 for (const std::string& key : common_keys)
159 {
160 std::string sub_namespace = yaml_namespace + "/" + key;
161 expectYamlEquivalence(generated[key], reference[key], generated_path, sub_namespace);
162 }
163 }
164 else
165 {
166 EXPECT_EQ(generated.as<std::string>(), reference.as<std::string>())
167 << msg_prefix << "does not match scalar values!";
168 }
169}
170
171void expectYamlEquivalence(const std::filesystem::path& generated_path, const std::filesystem::path& reference_path)
172{
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))
175 {
176 return;
177 }
178 const YAML::Node& generated = YAML::LoadFile(generated_path);
179 const YAML::Node& reference = YAML::LoadFile(reference_path);
180 expectYamlEquivalence(generated, reference, generated_path);
181}
182
183} // namespace moveit_setup
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_
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