From ddfa9304b761d034f32fe333a55901e68bd51c96 Mon Sep 17 00:00:00 2001 From: Levi Armstrong Date: Sat, 13 Jul 2024 16:40:32 -0500 Subject: [PATCH] fixup --- .../core/task_composer_node_ports.h | 14 +++++-- .../src/nodes/has_data_storage_entry_task.cpp | 2 +- .../core/src/task_composer_node.cpp | 42 +++++++++---------- .../core/src/task_composer_node_ports.cpp | 16 +++---- .../core/src/test_suite/test_task.cpp | 8 ++-- .../examples/task_composer_example.cpp | 12 +++--- .../planning/nodes/motion_planner_task.hpp | 14 +++---- .../nodes/continuous_contact_check_task.cpp | 10 ++--- .../src/nodes/discrete_contact_check_task.cpp | 10 ++--- .../src/nodes/fix_state_bounds_task.cpp | 12 +++--- .../src/nodes/fix_state_collision_task.cpp | 12 +++--- .../src/nodes/format_as_input_task.cpp | 6 +-- .../src/nodes/format_as_result_task.cpp | 4 +- ...iterative_spline_parameterization_task.cpp | 14 +++---- .../planning/src/nodes/min_length_task.cpp | 10 ++--- .../src/nodes/process_planning_input_task.cpp | 4 +- .../src/nodes/profile_switch_task.cpp | 6 +-- .../planning/src/nodes/raster_motion_task.cpp | 8 ++-- .../src/nodes/raster_only_motion_task.cpp | 8 ++-- .../ruckig_trajectory_smoothing_task.cpp | 14 +++---- .../time_optimal_parameterization_task.cpp | 14 +++---- .../src/nodes/update_end_state_task.cpp | 6 +-- .../nodes/update_start_and_end_state_task.cpp | 8 ++-- .../src/nodes/update_start_state_task.cpp | 6 +-- .../src/nodes/upsample_trajectory_task.cpp | 8 ++-- 25 files changed, 136 insertions(+), 132 deletions(-) diff --git a/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_node_ports.h b/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_node_ports.h index 054eed9be6..4890a4eb01 100644 --- a/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_node_ports.h +++ b/tesseract_task_composer/core/include/tesseract_task_composer/core/task_composer_node_ports.h @@ -40,11 +40,17 @@ namespace tesseract_planning */ struct TaskComposerNodePorts { - std::unordered_map input_required; - std::unordered_map input_optional; + enum Type + { + SINGLE = 0, + MULTIPLE = 1 + }; - std::unordered_map output_required; - std::unordered_map output_optional; + std::unordered_map input_required; + std::unordered_map input_optional; + + std::unordered_map output_required; + std::unordered_map output_optional; std::string toString() const; diff --git a/tesseract_task_composer/core/src/nodes/has_data_storage_entry_task.cpp b/tesseract_task_composer/core/src/nodes/has_data_storage_entry_task.cpp index 12f81e1d87..0ea3490f90 100644 --- a/tesseract_task_composer/core/src/nodes/has_data_storage_entry_task.cpp +++ b/tesseract_task_composer/core/src/nodes/has_data_storage_entry_task.cpp @@ -37,7 +37,7 @@ HasDataStorageEntryTask::HasDataStorageEntryTask(std::string name, TaskComposerNodePorts HasDataStorageEntryTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_KEYS_PORT] = true; + ports.input_required[INPUT_KEYS_PORT] = TaskComposerNodePorts::MULTIPLE; return ports; } diff --git a/tesseract_task_composer/core/src/task_composer_node.cpp b/tesseract_task_composer/core/src/task_composer_node.cpp index 37d40ba73c..fec3e0bb13 100644 --- a/tesseract_task_composer/core/src/task_composer_node.cpp +++ b/tesseract_task_composer/core/src/task_composer_node.cpp @@ -154,7 +154,7 @@ void TaskComposerNode::validatePorts() const const auto& output_keys = output_keys_.data(); // Check for required ports - for (const auto& [port, container] : ports_.input_required) + for (const auto& [port, type] : ports_.input_required) { auto it = input_keys.find(port); if (it == input_keys.end()) @@ -164,38 +164,38 @@ void TaskComposerNode::validatePorts() const msg.append(", missing required input port '"); msg.append(port); msg.append(":"); - msg.append((container) ? "Multiple" : "Single"); + msg.append((static_cast(type)) ? "Multiple" : "Single"); msg.append("'. Supported Ports:\n"); msg.append(ports_.toString()); throw std::runtime_error(msg); } - if (static_cast(it->second.index()) != container) + if (it->second.index() != type) { std::string msg; msg.append(name_); msg.append(", required input port is wrong type'"); msg.append(port); msg.append(":"); - msg.append((container) ? "Multiple" : "Single"); + msg.append((static_cast(type)) ? "Multiple" : "Single"); msg.append("'. Supported Ports:\n"); msg.append(ports_.toString()); throw std::runtime_error(msg); } - if (container && std::get>(it->second).empty()) + if (static_cast(type) && std::get>(it->second).empty()) { std::string msg; msg.append(name_); msg.append(", required input port container is empty'"); msg.append(port); - msg.append(":Container'. Supported Ports:\n"); + msg.append(":Multiple'. Supported Ports:\n"); msg.append(ports_.toString()); throw std::runtime_error(msg); } } - for (const auto& [port, container] : ports_.output_required) + for (const auto& [port, type] : ports_.output_required) { auto it = output_keys.find(port); if (it == output_keys.end()) @@ -205,32 +205,32 @@ void TaskComposerNode::validatePorts() const msg.append(", missing required output port '"); msg.append(port); msg.append(":"); - msg.append((container) ? "Multiple" : "Single"); + msg.append((static_cast(type)) ? "Multiple" : "Single"); msg.append("'. Supported Ports:\n"); msg.append(ports_.toString()); throw std::runtime_error(msg); } - if (static_cast(it->second.index()) != container) + if (it->second.index() != type) { std::string msg; msg.append(name_); msg.append(", required output port is wrong type'"); msg.append(port); msg.append(":"); - msg.append((container) ? "Multiple" : "Single"); + msg.append((static_cast(type)) ? "Multiple" : "Single"); msg.append("'. Supported Ports:\n"); msg.append(ports_.toString()); throw std::runtime_error(msg); } - if (container && std::get>(it->second).empty()) + if (static_cast(type) && std::get>(it->second).empty()) { std::string msg; msg.append(name_); msg.append(", required output port container is empty'"); msg.append(port); - msg.append(":Container'. Supported Ports:\n"); + msg.append(":Multiple'. Supported Ports:\n"); msg.append(ports_.toString()); throw std::runtime_error(msg); } @@ -241,17 +241,16 @@ void TaskComposerNode::validatePorts() const { { auto it = ports_.input_required.find(port); - if ((it != ports_.input_required.end()) && - ((key.index() == 0 && !it->second) || (key.index() == 1 && it->second))) + if ((it != ports_.input_required.end()) && (key.index() == it->second)) continue; } { auto it = ports_.input_optional.find(port); - if ((it != ports_.input_optional.end()) && - ((key.index() == 0 && !it->second) || (key.index() == 1 && it->second))) + if ((it != ports_.input_optional.end()) && (key.index() == it->second)) { - if ((it != ports_.input_optional.end()) && it->second && std::get>(key).empty()) + if ((it != ports_.input_optional.end()) && static_cast(it->second) && + std::get>(key).empty()) { std::string msg; msg.append(name_); @@ -281,17 +280,16 @@ void TaskComposerNode::validatePorts() const { { auto it = ports_.output_required.find(port); - if ((it != ports_.output_required.end()) && - ((key.index() == 0 && !it->second) || (key.index() == 1 && it->second))) + if ((it != ports_.output_required.end()) && (key.index() == it->second)) continue; } { auto it = ports_.output_optional.find(port); - if ((it != ports_.output_optional.end()) && - ((key.index() == 0 && !it->second) || (key.index() == 1 && it->second))) + if ((it != ports_.output_optional.end()) && (key.index() == it->second)) { - if ((it != ports_.output_optional.end()) && it->second && std::get>(key).empty()) + if ((it != ports_.output_optional.end()) && static_cast(it->second) && + std::get>(key).empty()) { std::string msg; msg.append(name_); diff --git a/tesseract_task_composer/core/src/task_composer_node_ports.cpp b/tesseract_task_composer/core/src/task_composer_node_ports.cpp index 9c08ef34d9..7dfb72fc9a 100644 --- a/tesseract_task_composer/core/src/task_composer_node_ports.cpp +++ b/tesseract_task_composer/core/src/task_composer_node_ports.cpp @@ -40,9 +40,9 @@ std::string TaskComposerNodePorts::toString() const { std::string temp = " required: ["; std::size_t cnt{ 0 }; - for (const auto& [port, container] : input_required) + for (const auto& [port, type] : input_required) { - std::string bool_str = (container) ? "Multiple" : "Single"; + std::string bool_str = (static_cast(type)) ? "Multiple" : "Single"; temp.append(port); temp.append(":"); temp.append(bool_str); @@ -64,9 +64,9 @@ std::string TaskComposerNodePorts::toString() const { std::string temp = " optional: ["; std::size_t cnt{ 0 }; - for (const auto& [port, container] : input_optional) + for (const auto& [port, type] : input_optional) { - std::string bool_str = (container) ? "Multiple" : "Single"; + std::string bool_str = (static_cast(type)) ? "Multiple" : "Single"; temp.append(port); temp.append(":"); temp.append(bool_str); @@ -89,9 +89,9 @@ std::string TaskComposerNodePorts::toString() const { std::string temp = " required: ["; std::size_t cnt{ 0 }; - for (const auto& [port, container] : output_required) + for (const auto& [port, type] : output_required) { - std::string bool_str = (container) ? "Multiple" : "Single"; + std::string bool_str = (static_cast(type)) ? "Multiple" : "Single"; temp.append(port); temp.append(":"); temp.append(bool_str); @@ -113,9 +113,9 @@ std::string TaskComposerNodePorts::toString() const { std::string temp = " optional: ["; std::size_t cnt{ 0 }; - for (const auto& [port, container] : output_optional) + for (const auto& [port, type] : output_optional) { - std::string bool_str = (container) ? "Multiple" : "Single"; + std::string bool_str = (static_cast(type)) ? "Multiple" : "Single"; temp.append(port); temp.append(":"); temp.append(bool_str); diff --git a/tesseract_task_composer/core/src/test_suite/test_task.cpp b/tesseract_task_composer/core/src/test_suite/test_task.cpp index b6f96787cb..2548ed12b6 100644 --- a/tesseract_task_composer/core/src/test_suite/test_task.cpp +++ b/tesseract_task_composer/core/src/test_suite/test_task.cpp @@ -70,10 +70,10 @@ TestTask::TestTask(std::string name, const YAML::Node& config, const TaskCompose TaskComposerNodePorts TestTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PORT1_PORT] = false; - ports.input_required[INOUT_PORT2_PORT] = true; - ports.output_required[INOUT_PORT1_PORT] = false; - ports.output_required[INOUT_PORT2_PORT] = true; + ports.input_required[INOUT_PORT1_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INOUT_PORT2_PORT] = TaskComposerNodePorts::MULTIPLE; + ports.output_required[INOUT_PORT1_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[INOUT_PORT2_PORT] = TaskComposerNodePorts::MULTIPLE; return ports; } diff --git a/tesseract_task_composer/examples/task_composer_example.cpp b/tesseract_task_composer/examples/task_composer_example.cpp index 22465fea0e..454cb593d4 100644 --- a/tesseract_task_composer/examples/task_composer_example.cpp +++ b/tesseract_task_composer/examples/task_composer_example.cpp @@ -33,9 +33,9 @@ class AddTaskComposerNode : public TaskComposerTask static TaskComposerNodePorts ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_LEFT_PORT] = false; - ports.input_required[INPUT_RIGHT_PORT] = false; - ports.output_required[OUTPUT_RESULT_PORT] = false; + ports.input_required[INPUT_LEFT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_RIGHT_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[OUTPUT_RESULT_PORT] = TaskComposerNodePorts::SINGLE; return ports; } @@ -76,9 +76,9 @@ class MultiplyTaskComposerNode : public TaskComposerTask static TaskComposerNodePorts ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_LEFT_PORT] = false; - ports.input_required[INPUT_RIGHT_PORT] = false; - ports.output_required[OUTPUT_RESULT_PORT] = false; + ports.input_required[INPUT_LEFT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_RIGHT_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[OUTPUT_RESULT_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/include/tesseract_task_composer/planning/nodes/motion_planner_task.hpp b/tesseract_task_composer/planning/include/tesseract_task_composer/planning/nodes/motion_planner_task.hpp index 3edde1edbd..1825b12896 100644 --- a/tesseract_task_composer/planning/include/tesseract_task_composer/planning/nodes/motion_planner_task.hpp +++ b/tesseract_task_composer/planning/include/tesseract_task_composer/planning/nodes/motion_planner_task.hpp @@ -126,15 +126,15 @@ class MotionPlannerTask : public TaskComposerTask static TaskComposerNodePorts ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; - ports.input_optional[INPUT_MOVE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_MOVE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/continuous_contact_check_task.cpp b/tesseract_task_composer/planning/src/nodes/continuous_contact_check_task.cpp index 9ab781639b..461afe8322 100644 --- a/tesseract_task_composer/planning/src/nodes/continuous_contact_check_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/continuous_contact_check_task.cpp @@ -93,12 +93,12 @@ ContinuousContactCheckTask::ContinuousContactCheckTask(std::string name, TaskComposerNodePorts ContinuousContactCheckTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INPUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/discrete_contact_check_task.cpp b/tesseract_task_composer/planning/src/nodes/discrete_contact_check_task.cpp index a1fb03d883..a2ffe545d2 100644 --- a/tesseract_task_composer/planning/src/nodes/discrete_contact_check_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/discrete_contact_check_task.cpp @@ -93,12 +93,12 @@ DiscreteContactCheckTask::DiscreteContactCheckTask(std::string name, TaskComposerNodePorts DiscreteContactCheckTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INPUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/fix_state_bounds_task.cpp b/tesseract_task_composer/planning/src/nodes/fix_state_bounds_task.cpp index b65f9edce5..5363f4adb7 100644 --- a/tesseract_task_composer/planning/src/nodes/fix_state_bounds_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/fix_state_bounds_task.cpp @@ -83,14 +83,14 @@ FixStateBoundsTask::FixStateBoundsTask(std::string name, TaskComposerNodePorts FixStateBoundsTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/fix_state_collision_task.cpp b/tesseract_task_composer/planning/src/nodes/fix_state_collision_task.cpp index d2828a4de5..becdc36503 100644 --- a/tesseract_task_composer/planning/src/nodes/fix_state_collision_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/fix_state_collision_task.cpp @@ -376,14 +376,14 @@ FixStateCollisionTask::FixStateCollisionTask(std::string name, TaskComposerNodePorts FixStateCollisionTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/format_as_input_task.cpp b/tesseract_task_composer/planning/src/nodes/format_as_input_task.cpp index c8f62b0ce5..97fb51e608 100644 --- a/tesseract_task_composer/planning/src/nodes/format_as_input_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/format_as_input_task.cpp @@ -79,10 +79,10 @@ FormatAsInputTask::FormatAsInputTask(std::string name, TaskComposerNodePorts FormatAsInputTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_PRE_PLANNING_PROGRAM_PORT] = false; - ports.input_required[INPUT_POST_PLANNING_PROGRAM_PORT] = false; + ports.input_required[INPUT_PRE_PLANNING_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_POST_PLANNING_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; - ports.output_required[OUTPUT_PROGRAM_PORT] = false; + ports.output_required[OUTPUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/format_as_result_task.cpp b/tesseract_task_composer/planning/src/nodes/format_as_result_task.cpp index bf31ac2dd7..bf263966b2 100644 --- a/tesseract_task_composer/planning/src/nodes/format_as_result_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/format_as_result_task.cpp @@ -47,8 +47,8 @@ FormatAsResultTask::FormatAsResultTask(std::string name, TaskComposerNodePorts FormatAsResultTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAMS_PORT] = true; - ports.output_required[INOUT_PROGRAMS_PORT] = true; + ports.input_required[INOUT_PROGRAMS_PORT] = TaskComposerNodePorts::MULTIPLE; + ports.output_required[INOUT_PROGRAMS_PORT] = TaskComposerNodePorts::MULTIPLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/iterative_spline_parameterization_task.cpp b/tesseract_task_composer/planning/src/nodes/iterative_spline_parameterization_task.cpp index ec9b4cf187..5e5d2baf5b 100644 --- a/tesseract_task_composer/planning/src/nodes/iterative_spline_parameterization_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/iterative_spline_parameterization_task.cpp @@ -103,15 +103,15 @@ IterativeSplineParameterizationTask::IterativeSplineParameterizationTask( TaskComposerNodePorts IterativeSplineParameterizationTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; - ports.input_optional[INPUT_MOVE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_MOVE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/min_length_task.cpp b/tesseract_task_composer/planning/src/nodes/min_length_task.cpp index edfa72bfcf..ee973865ed 100644 --- a/tesseract_task_composer/planning/src/nodes/min_length_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/min_length_task.cpp @@ -86,13 +86,13 @@ MinLengthTask::MinLengthTask(std::string name, TaskComposerNodePorts MinLengthTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/process_planning_input_task.cpp b/tesseract_task_composer/planning/src/nodes/process_planning_input_task.cpp index 89ab53b750..746d6f68b0 100644 --- a/tesseract_task_composer/planning/src/nodes/process_planning_input_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/process_planning_input_task.cpp @@ -71,8 +71,8 @@ ProcessPlanningInputTask::ProcessPlanningInputTask(std::string name, TaskComposerNodePorts ProcessPlanningInputTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_PLANNING_INPUT_PORT] = false; - ports.output_required[OUTPUT_PROGRAM_PORT] = false; + ports.input_required[INPUT_PLANNING_INPUT_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[OUTPUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/profile_switch_task.cpp b/tesseract_task_composer/planning/src/nodes/profile_switch_task.cpp index 1a3cc8e9cd..a74dac807d 100644 --- a/tesseract_task_composer/planning/src/nodes/profile_switch_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/profile_switch_task.cpp @@ -73,9 +73,9 @@ ProfileSwitchTask::ProfileSwitchTask(std::string name, TaskComposerNodePorts ProfileSwitchTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; + ports.input_required[INPUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/raster_motion_task.cpp b/tesseract_task_composer/planning/src/nodes/raster_motion_task.cpp index 4ca3c8816a..ad581a8509 100644 --- a/tesseract_task_composer/planning/src/nodes/raster_motion_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/raster_motion_task.cpp @@ -332,11 +332,11 @@ RasterMotionTask::RasterMotionTask(std::string name, TaskComposerNodePorts RasterMotionTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/raster_only_motion_task.cpp b/tesseract_task_composer/planning/src/nodes/raster_only_motion_task.cpp index 6720570a70..498cd69b48 100644 --- a/tesseract_task_composer/planning/src/nodes/raster_only_motion_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/raster_only_motion_task.cpp @@ -270,11 +270,11 @@ RasterOnlyMotionTask::RasterOnlyMotionTask(std::string name, TaskComposerNodePorts RasterOnlyMotionTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/ruckig_trajectory_smoothing_task.cpp b/tesseract_task_composer/planning/src/nodes/ruckig_trajectory_smoothing_task.cpp index 0c02aaba55..add4fae28e 100644 --- a/tesseract_task_composer/planning/src/nodes/ruckig_trajectory_smoothing_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/ruckig_trajectory_smoothing_task.cpp @@ -88,15 +88,15 @@ RuckigTrajectorySmoothingTask::RuckigTrajectorySmoothingTask(std::string name, TaskComposerNodePorts RuckigTrajectorySmoothingTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; - ports.input_optional[INPUT_MOVE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_MOVE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/time_optimal_parameterization_task.cpp b/tesseract_task_composer/planning/src/nodes/time_optimal_parameterization_task.cpp index 2f608892d2..47516d614b 100644 --- a/tesseract_task_composer/planning/src/nodes/time_optimal_parameterization_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/time_optimal_parameterization_task.cpp @@ -95,15 +95,15 @@ TimeOptimalParameterizationTask::TimeOptimalParameterizationTask(std::string nam TaskComposerNodePorts TimeOptimalParameterizationTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_ENVIRONMENT_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_ENVIRONMENT_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; - ports.input_optional[INPUT_MANIP_INFO_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; - ports.input_optional[INPUT_MOVE_PROFILE_REMAPPING_PORT] = false; + ports.input_optional[INPUT_MANIP_INFO_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_MOVE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/update_end_state_task.cpp b/tesseract_task_composer/planning/src/nodes/update_end_state_task.cpp index fe97c4e29e..a1608c5dff 100644 --- a/tesseract_task_composer/planning/src/nodes/update_end_state_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/update_end_state_task.cpp @@ -78,9 +78,9 @@ UpdateEndStateTask::UpdateEndStateTask(std::string name, TaskComposerNodePorts UpdateEndStateTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_CURRENT_PROGRAM_PORT] = false; - ports.input_required[INPUT_NEXT_PROGRAM_PORT] = false; - ports.output_required[OUTPUT_PROGRAM_PORT] = false; + ports.input_required[INPUT_CURRENT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_NEXT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[OUTPUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/update_start_and_end_state_task.cpp b/tesseract_task_composer/planning/src/nodes/update_start_and_end_state_task.cpp index f4ac7027c7..f34a613cd2 100644 --- a/tesseract_task_composer/planning/src/nodes/update_start_and_end_state_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/update_start_and_end_state_task.cpp @@ -83,10 +83,10 @@ UpdateStartAndEndStateTask::UpdateStartAndEndStateTask(std::string name, TaskComposerNodePorts UpdateStartAndEndStateTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_CURRENT_PROGRAM_PORT] = false; - ports.input_required[INPUT_PREVIOUS_PROGRAM_PORT] = false; - ports.input_required[INPUT_NEXT_PROGRAM_PORT] = false; - ports.output_required[OUTPUT_PROGRAM_PORT] = false; + ports.input_required[INPUT_CURRENT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PREVIOUS_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_NEXT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[OUTPUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/update_start_state_task.cpp b/tesseract_task_composer/planning/src/nodes/update_start_state_task.cpp index 1e4f4d7fc0..0c40487c00 100644 --- a/tesseract_task_composer/planning/src/nodes/update_start_state_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/update_start_state_task.cpp @@ -78,9 +78,9 @@ UpdateStartStateTask::UpdateStartStateTask(std::string name, TaskComposerNodePorts UpdateStartStateTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INPUT_CURRENT_PROGRAM_PORT] = false; - ports.input_required[INPUT_PREVIOUS_PROGRAM_PORT] = false; - ports.output_required[OUTPUT_PROGRAM_PORT] = false; + ports.input_required[INPUT_CURRENT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PREVIOUS_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[OUTPUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; } diff --git a/tesseract_task_composer/planning/src/nodes/upsample_trajectory_task.cpp b/tesseract_task_composer/planning/src/nodes/upsample_trajectory_task.cpp index 6adefad970..927cfd6abc 100644 --- a/tesseract_task_composer/planning/src/nodes/upsample_trajectory_task.cpp +++ b/tesseract_task_composer/planning/src/nodes/upsample_trajectory_task.cpp @@ -82,10 +82,10 @@ UpsampleTrajectoryTask::UpsampleTrajectoryTask(std::string name, TaskComposerNodePorts UpsampleTrajectoryTask::ports() { TaskComposerNodePorts ports; - ports.input_required[INOUT_PROGRAM_PORT] = false; - ports.input_required[INPUT_PROFILES_PORT] = false; - ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = false; - ports.output_required[INOUT_PROGRAM_PORT] = false; + ports.input_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_required[INPUT_PROFILES_PORT] = TaskComposerNodePorts::SINGLE; + ports.input_optional[INPUT_COMPOSITE_PROFILE_REMAPPING_PORT] = TaskComposerNodePorts::SINGLE; + ports.output_required[INOUT_PROGRAM_PORT] = TaskComposerNodePorts::SINGLE; return ports; }