Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Introduce a common TaskRemapper with wildcard support #55

Open
wants to merge 6 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions nexus_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ add_library(${PROJECT_NAME} SHARED
src/node_thread.cpp
src/node_utils.cpp
src/pausable_sequence.cpp
src/task_remapper.cpp
)
GENERATE_EXPORT_HEADER(${PROJECT_NAME}
EXPORT_FILE_NAME "include/nexus_common_export.hpp"
Expand Down Expand Up @@ -130,6 +131,7 @@ if(BUILD_TESTING)
)
nexus_add_test(logging_test src/logging_test.cpp)
nexus_add_test(sync_ros_client_test src/sync_ros_client_test.cpp)
nexus_add_test(task_remapper_test src/task_remapper_test.cpp)
endif()

ament_export_targets(${PROJECT_NAME})
Expand Down
55 changes: 55 additions & 0 deletions nexus_common/include/nexus_common/task_remapper.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
/*
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#ifndef NEXUS_COMMON__TASK_REMAPPER_HPP
#define NEXUS_COMMON__TASK_REMAPPER_HPP

#include "nexus_common_export.hpp"

#include <rclcpp/rclcpp.hpp>

#include <optional>
#include <string>

namespace nexus::common {

/**
* Provides task remapping capability
*/
class NEXUS_COMMON_EXPORT TaskRemapper
{
public:
/*
* Initialize the remapper with the value of a ROS parameter containing a YAML
*/
TaskRemapper(const std::string& param);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This API is error prone especially if users do not pass a string that can be deserialized into a YAML. ie YAML::Load() can throw an exception in the implementation.
I suggest we accept a concrete type here instead like an std::multimap where the key is the remapped process and the values for each key are the process steps in the work order.

This way if the param definition changes in the orchestrators, this API would not have to change.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This PR doesn't introduce any new exception since all uses of this class were doing YAML::Load anyway, so they would have thrown on an invalid YAML.
The "proper" way I considered going for was either passing a YAML node as an input (so we won't throw) or keep the string and make the constructor fallible (i.e. a make function, return nullptr if the YAML failed deserializing). I didn't do it only because I saw that the codebase doesn't seem to use this paradigm but I'm happy to do it.

I feel that if we add a multimap and users of the API need to manually parse the YAML, handle exceptions, add its content to a multimap, then we read the multimap, iterate over it, check for wildcards, populate internal data structures accordingly, it becomes much more complex and clunky. Instead of being a refactor to reduce duplicated code we actually end up with a fair bit more code and complexity.


/*
* Remaps, if necessary, the input task
* Returns a value if the task was remapped, std::nullopt otherwise
*/
std::optional<std::string> remap(const std::string& task) const;

private:
// If present, match every incoming task to the target task
std::optional<std::string> _wildcard_match;
std::unordered_map<std::string, std::string> _task_remaps;
};

}

#endif
61 changes: 61 additions & 0 deletions nexus_common/src/task_remapper.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
/*
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include "task_remapper.hpp"

#include <yaml-cpp/yaml.h>

namespace nexus::common {

TaskRemapper::TaskRemapper(const std::string& param)
{
const auto remaps = YAML::Load(param);
for (const auto& n : remaps)
{
const auto task_type = n.first.as<std::string>();
const auto& mappings = n.second;
for (const auto& m : mappings)
{
auto mapping = m.as<std::string>();
if (mapping == "*")
{
this->_wildcard_match = task_type;
this->_task_remaps.clear();
return;
}
// TODO(luca) check for duplicates, logging if found
this->_task_remaps.emplace(mapping, task_type);
}
}
}

std::optional<std::string> TaskRemapper::remap(const std::string& task) const
{
if (this->_wildcard_match.has_value())
{
return this->_wildcard_match.value();
}
const auto it = this->_task_remaps.find(task);
if (it != this->_task_remaps.end())
{
return it->second;
}
return std::nullopt;
}


}
58 changes: 58 additions & 0 deletions nexus_common/src/task_remapper_test.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
/*
* Copyright (C) 2025 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#define CATCH_CONFIG_MAIN
#include <rmf_utils/catch.hpp>

#include "task_remapper.hpp"

namespace nexus::common::test {

TEST_CASE("task_remapping") {
std::string param =
R"(
pick_and_place: [pick, place]
)";
auto remapper = TaskRemapper(param);
CHECK(remapper.remap("pick") == "pick_and_place");
CHECK(remapper.remap("place") == "pick_and_place");
CHECK(remapper.remap("other") == std::nullopt);
}

TEST_CASE("task_remapping_with_wildcard") {
std::string param =
R"(
pick_and_place: [pick, place]
main : ["*"]
)";
auto remapper = TaskRemapper(param);
CHECK(remapper.remap("pick") == "main");
CHECK(remapper.remap("place") == "main");
CHECK(remapper.remap("other") == "main");
}

luca-della-vedova marked this conversation as resolved.
Show resolved Hide resolved
TEST_CASE("task_remapping_with_normal_and_wildcard") {
std::string param =
R"(
pick_and_place: [pick, "*"]
)";
auto remapper = TaskRemapper(param);
CHECK(remapper.remap("pick") == "pick_and_place");
CHECK(remapper.remap("place") == "pick_and_place");
}

}
4 changes: 2 additions & 2 deletions nexus_system_orchestrator/src/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

#include "session.hpp"

#include <nexus_common/task_remapper.hpp>
#include <nexus_common/models/work_order.hpp>
#include <nexus_endpoints.hpp>
#include <nexus_orchestrator_msgs/msg/task_state.hpp>
Expand All @@ -43,8 +44,7 @@ public: rclcpp_lifecycle::LifecycleNode& node;
public: std::string job_id;
public: WorkOrder wo;
public: std::vector<WorkcellTask> tasks;
public: std::shared_ptr<const std::unordered_map<std::string,
std::string>> task_remaps;
public: std::shared_ptr<const common::TaskRemapper> task_remapper;
/**
* Map of task ids and their assigned workcell ids.
*/
Expand Down
8 changes: 4 additions & 4 deletions nexus_system_orchestrator/src/execute_task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,16 +41,16 @@ BT::NodeStatus ExecuteTask::onStart()

// Remap the BT filename to load if one is provided.
std::string bt_name = task->type;
auto it = _ctx->task_remaps->find(task->type);
if (it != _ctx->task_remaps->end())
const auto new_task = _ctx->task_remapper->remap(task->type);
if (new_task.has_value())
{
RCLCPP_DEBUG(
_ctx->node.get_logger(),
"[ExecuteTask] Loading remapped BT [%s] for original task type [%s]",
it->second.c_str(),
new_task.value().c_str(),
task->type.c_str()
);
bt_name = it->second;
bt_name = new_task.value();
}
std::filesystem::path task_bt_path(this->_bt_path / (bt_name + ".xml"));
if (!std::filesystem::is_regular_file(task_bt_path))
Expand Down
17 changes: 3 additions & 14 deletions nexus_system_orchestrator/src/system_orchestrator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,23 +100,12 @@ SystemOrchestrator::SystemOrchestrator(const rclcpp::NodeOptions& options)
}

{
_task_remaps =
std::make_shared<std::unordered_map<std::string, std::string>>();
ParameterDescriptor desc;
desc.read_only = true;
desc.description =
"A yaml containing a dictionary of task types and an array of remaps.";
const auto yaml = this->declare_parameter("remap_task_types", "", desc);
const auto remaps = YAML::Load(yaml);
for (const auto& n : remaps)
{
const auto task_type = n.first.as<std::string>();
const auto& mappings = n.second;
for (const auto& m : mappings)
{
this->_task_remaps->emplace(m.as<std::string>(), task_type);
}
}
const auto param = this->declare_parameter("remap_task_types", "", desc);
this->_task_remapper = std::make_shared<common::TaskRemapper>(param);
}

{
Expand Down Expand Up @@ -545,7 +534,7 @@ void SystemOrchestrator::_create_job(const WorkOrderActionType::Goal& goal)

// using `new` because make_shared does not work with aggregate initializer
std::shared_ptr<Context> ctx{new Context{*this,
goal.order.id, wo, tasks, this->_task_remaps,
goal.order.id, wo, tasks, this->_task_remapper,
std::unordered_map<std::string, std::string>{},
this->_workcell_sessions,
this->_transporter_sessions, {}, nullptr,
Expand Down
5 changes: 3 additions & 2 deletions nexus_system_orchestrator/src/system_orchestrator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <nexus_common/action_client_bt_node.hpp>
#include <nexus_common/models/work_order.hpp>
#include <nexus_common/sync_service_client.hpp>
#include <nexus_common/task_remapper.hpp>
#include <nexus_endpoints.hpp>
#include <nexus_lifecycle_manager/lifecycle_manager.hpp>
#include <nexus_orchestrator_msgs/msg/workcell_task.hpp>
Expand Down Expand Up @@ -96,8 +97,8 @@ class SystemOrchestrator : public
std::unique_ptr<lifecycle_manager::LifecycleManager<>> _lifecycle_mgr{nullptr};
rclcpp::TimerBase::SharedPtr _pre_configure_timer;
rclcpp::SubscriptionBase::SharedPtr _estop_sub;
// mapping of mapped task type and the original
std::shared_ptr<std::unordered_map<std::string, std::string>> _task_remaps;
// Manages task remapping
std::shared_ptr<common::TaskRemapper> _task_remapper;
std::shared_ptr<OnSetParametersCallbackHandle> _param_cb_handle;

/**
Expand Down
28 changes: 15 additions & 13 deletions nexus_workcell_orchestrator/src/workcell_orchestrator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,18 +92,8 @@ WorkcellOrchestrator::WorkcellOrchestrator(const rclcpp::NodeOptions& options)
desc.read_only = true;
desc.description =
"A yaml containing a dictionary of task types and an array of remaps.";
const auto yaml = this->declare_parameter("remap_task_types", std::string{},
desc);
const auto remaps = YAML::Load(yaml);
for (const auto& n : remaps)
{
const auto task_type = n.first.as<std::string>();
const auto& mappings = n.second;
for (const auto& m : mappings)
{
this->_task_remaps.emplace(m.as<std::string>(), task_type);
}
}
const auto param = this->declare_parameter("remap_task_types", "", desc);
this->_task_remapper = std::make_shared<common::TaskRemapper>(param);
}
{
ParameterDescriptor desc;
Expand Down Expand Up @@ -988,8 +978,20 @@ BT::Tree WorkcellOrchestrator::_create_bt(const std::shared_ptr<Context>& ctx)
{
// To keep things simple, the task type is used as the key for the behavior tree to use.
this->_ctx_mgr->set_active_context(ctx);
const auto new_task = this->_task_remapper->remap(ctx->task.type);
auto bt_name = ctx->task.type;
if (new_task.has_value())
{
RCLCPP_DEBUG(
this->get_logger(),
"Loading remapped BT [%s] for original task type [%s]",
new_task.value().c_str(),
ctx->task.type.c_str()
);
bt_name = new_task.value();
}
return this->_bt_factory->createTreeFromFile(this->_bt_store.get_bt(
ctx->task.type));
bt_name));
}

void WorkcellOrchestrator::_handle_command_success(
Expand Down
5 changes: 3 additions & 2 deletions nexus_workcell_orchestrator/src/workcell_orchestrator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@

#include <nexus_common/action_client_bt_node.hpp>
#include <nexus_common/bt_store.hpp>
#include <nexus_common/task_remapper.hpp>

#include <behaviortree_cpp_v3/action_node.h>
#include <behaviortree_cpp_v3/bt_factory.h>
Expand Down Expand Up @@ -124,8 +125,8 @@ private: std::list<std::shared_ptr<Context>> _ctxs;
private: std::shared_ptr<ContextManager> _ctx_mgr;
private: std::unique_ptr<lifecycle_manager::LifecycleManager<>> _lifecycle_mgr{
nullptr};
// mapping of mapped task type and the original
private: std::unordered_map<std::string, std::string> _task_remaps;
// Takes care of remapping tasks
private: std::shared_ptr<common::TaskRemapper> _task_remapper;
private: TaskParser _task_parser;
private: pluginlib::ClassLoader<TaskChecker> _task_checker_loader;
private: std::shared_ptr<TaskChecker> _task_checker;
Expand Down
Loading