diff --git a/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_executor.h b/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_executor.h index 097847c13c..b3f81fd38b 100644 --- a/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_executor.h +++ b/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_executor.h @@ -69,9 +69,6 @@ class TaskComposerExecutor /** @brief Queries the number of running tasks at the time of this call */ virtual long getTaskCount() const = 0; - bool operator==(const TaskComposerExecutor& rhs) const; - bool operator!=(const TaskComposerExecutor& rhs) const; - protected: std::string name_; diff --git a/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_task.h b/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_task.h index f17335d698..7ba993bfe2 100644 --- a/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_task.h +++ b/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_task.h @@ -44,7 +44,6 @@ class TaskComposerTask : public TaskComposerNode using UPtr = std::unique_ptr; using ConstUPtr = std::unique_ptr; - TaskComposerTask(); explicit TaskComposerTask(std::string name, TaskComposerNodePorts ports, bool conditional); explicit TaskComposerTask(std::string name, TaskComposerNodePorts ports, const YAML::Node& config); ~TaskComposerTask() override = default; diff --git a/tesseract_task_composer/core/src/task_composer_executor.cpp b/tesseract_task_composer/core/src/task_composer_executor.cpp index 4c1d90fe4f..66b5a82eb1 100644 --- a/tesseract_task_composer/core/src/task_composer_executor.cpp +++ b/tesseract_task_composer/core/src/task_composer_executor.cpp @@ -44,10 +44,4 @@ std::unique_ptr TaskComposerExecutor::run(const TaskComposer return runImpl(node, std::move(context)); } -bool TaskComposerExecutor::operator==(const TaskComposerExecutor& rhs) const { return (name_ == rhs.name_); } - -// LCOV_EXCL_START -bool TaskComposerExecutor::operator!=(const TaskComposerExecutor& rhs) const { return !operator==(rhs); } -// LCOV_EXCL_STOP - } // namespace tesseract_planning diff --git a/tesseract_task_composer/core/src/task_composer_task.cpp b/tesseract_task_composer/core/src/task_composer_task.cpp index a9a7cd18c0..24954e4c82 100644 --- a/tesseract_task_composer/core/src/task_composer_task.cpp +++ b/tesseract_task_composer/core/src/task_composer_task.cpp @@ -33,7 +33,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP namespace tesseract_planning { -TaskComposerTask::TaskComposerTask() : TaskComposerTask("TaskComposerTask", TaskComposerNodePorts{}, true) {} TaskComposerTask::TaskComposerTask(std::string name, TaskComposerNodePorts ports, bool conditional) : TaskComposerNode(std::move(name), TaskComposerNodeType::TASK, std::move(ports), conditional) { diff --git a/tesseract_task_composer/taskflow/include/tesseract_task_composer/taskflow/taskflow_task_composer_executor.h b/tesseract_task_composer/taskflow/include/tesseract_task_composer/taskflow/taskflow_task_composer_executor.h index dcb2c7807f..c8d7babb28 100644 --- a/tesseract_task_composer/taskflow/include/tesseract_task_composer/taskflow/taskflow_task_composer_executor.h +++ b/tesseract_task_composer/taskflow/include/tesseract_task_composer/taskflow/taskflow_task_composer_executor.h @@ -80,9 +80,6 @@ class TaskflowTaskComposerExecutor : public TaskComposerExecutor long getTaskCount() const override final; - bool operator==(const TaskflowTaskComposerExecutor& rhs) const; - bool operator!=(const TaskflowTaskComposerExecutor& rhs) const; - private: std::size_t num_threads_; std::unique_ptr executor_; diff --git a/tesseract_task_composer/taskflow/src/taskflow_task_composer_executor.cpp b/tesseract_task_composer/taskflow/src/taskflow_task_composer_executor.cpp index fa6643cbf8..716a04725a 100644 --- a/tesseract_task_composer/taskflow/src/taskflow_task_composer_executor.cpp +++ b/tesseract_task_composer/taskflow/src/taskflow_task_composer_executor.cpp @@ -251,17 +251,4 @@ long TaskflowTaskComposerExecutor::getWorkerCount() const { return static_cast(executor_->num_topologies()); } -bool TaskflowTaskComposerExecutor::operator==(const TaskflowTaskComposerExecutor& rhs) const -{ - bool equal = true; - equal &= (num_threads_ == rhs.num_threads_); - equal &= TaskComposerExecutor::operator==(rhs); - return equal; -} - -bool TaskflowTaskComposerExecutor::operator!=(const TaskflowTaskComposerExecutor& rhs) const -{ - return !operator==(rhs); -} - } // namespace tesseract_planning diff --git a/tesseract_task_composer/test/tesseract_task_composer_core_unit.cpp b/tesseract_task_composer/test/tesseract_task_composer_core_unit.cpp index 4bdf7b23b8..6c626d92aa 100644 --- a/tesseract_task_composer/test/tesseract_task_composer_core_unit.cpp +++ b/tesseract_task_composer/test/tesseract_task_composer_core_unit.cpp @@ -35,13 +35,40 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP using namespace tesseract_planning; +TEST(TesseractTaskComposerCoreUnit, TaskComposerKeysTests) // NOLINT +{ + TaskComposerKeys keys; + EXPECT_TRUE(keys.empty()); + keys.add("first", "I1"); + keys.add("second", std::vector{ "I2" }); + EXPECT_TRUE(keys.size() == 2); + EXPECT_FALSE(keys.empty()); + EXPECT_EQ(keys.get("first"), "I1"); + EXPECT_EQ(keys.get>("second"), std::vector{ "I2" }); + EXPECT_TRUE(keys.has("first")); + EXPECT_TRUE(keys.has("second")); + std::map renaming; + renaming["I1"] = "I3"; + renaming["I2"] = "I4"; + keys.rename(renaming); + EXPECT_EQ(keys.get("first"), "I3"); + EXPECT_EQ(keys.get>("second"), std::vector{ "I4" }); + keys.remove("second"); + EXPECT_FALSE(keys.has("second")); + + TaskComposerKeys copy{ keys }; + EXPECT_TRUE(keys == copy); + EXPECT_FALSE(keys != copy); +} + TEST(TesseractTaskComposerCoreUnit, TaskComposerDataStorageTests) // NOLINT { std::string key{ "joint_state" }; std::vector joint_names{ "joint_1", "joint_2" }; Eigen::Vector2d joint_values(5, 10); tesseract_common::JointState js(joint_names, joint_values); - TaskComposerDataStorage data; + TaskComposerDataStorage data("test_name"); + EXPECT_EQ(data.getName(), "test_name"); EXPECT_FALSE(data.hasKey(key)); EXPECT_TRUE(data.getData(key).isNull()); @@ -2326,6 +2353,7 @@ TEST(TesseractTaskComposerCoreUnit, TaskComposerForEachTaskTests) // NOLINT // Solve auto executor = factory.createTaskComposerExecutor(factory.getDefaultTaskComposerExecutorPlugin()); auto context = std::make_shared("abc", std::move(data)); + context->dotgraph = true; EXPECT_EQ(task.run(*context, *executor), 1); auto node_info = context->task_infos->getInfo(task.getUUID()); if (!node_info.has_value())