Skip to content
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: 1 addition & 1 deletion canopen_core/include/canopen_core/device_container.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ class DeviceContainer : public rclcpp_components::ComponentManager
virtual bool load_component(
const std::string package_name, const std::string driver_name, const uint16_t node_id,
const std::string node_name, std::vector<rclcpp::Parameter> & params,
const std::string node_namespace = "");
std::map<std::string, std::string> remappings, const std::string node_namespace = "");

/**
* @brief Shutdown all devices.
Expand Down
18 changes: 15 additions & 3 deletions canopen_core/src/device_container.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ bool DeviceContainer::init_driver(uint16_t node_id)
bool DeviceContainer::load_component(
const std::string package_name, const std::string driver_name, const uint16_t node_id,
const std::string node_name, std::vector<rclcpp::Parameter> & params,
const std::string node_namespace)
std::map<std::string, std::string> remappings, const std::string node_namespace)
{
ComponentResource component;
std::string resource_index("rclcpp_components");
Expand Down Expand Up @@ -62,6 +62,13 @@ bool DeviceContainer::load_component(
remap_rules.push_back("-r");
remap_rules.push_back("__ns:=" + canopen_ns);

// Remappings
for (auto it = remappings.begin(); it != remappings.end(); it++)
{
remap_rules.push_back("-r");
remap_rules.push_back(it->first + ":=" + it->second);
}

if (node_namespace.empty())
{
RCLCPP_WARN(
Expand Down Expand Up @@ -230,6 +237,8 @@ bool DeviceContainer::load_master()
auto driver_name = config_->get_entry<std::string>(*it, "driver");
auto package_name = config_->get_entry<std::string>(*it, "package");
auto node_namespace = config_->get_entry<std::string>(*it, "namespace").value_or("");
auto remappings = config_->get_entry<std::map<std::string, std::string>>
(*it, "remappings").value_or(std::map<std::string, std::string>());
if (!node_id.has_value() || !driver_name.has_value() || !package_name.has_value())
{
RCLCPP_ERROR(
Expand All @@ -247,7 +256,7 @@ bool DeviceContainer::load_master()

if (!this->load_component(
package_name.value(), driver_name.value(), node_id.value(), *it, params,
node_namespace))
remappings, node_namespace))
{
RCLCPP_ERROR(this->get_logger(), "Error: Loading master failed.");
return false;
Expand Down Expand Up @@ -287,6 +296,9 @@ bool DeviceContainer::load_drivers()
auto driver_name = config_->get_entry<std::string>(*it, "driver");
auto package_name = config_->get_entry<std::string>(*it, "package");
auto node_namespace = config_->get_entry<std::string>(*it, "namespace").value_or("");
auto remappings = config_->get_entry<std::map<std::string, std::string>>
(*it, "remappings").value_or(std::map<std::string, std::string>());

if (!node_id.has_value() || !driver_name.has_value() || !package_name.has_value())
{
RCLCPP_ERROR(
Expand Down Expand Up @@ -323,7 +335,7 @@ bool DeviceContainer::load_drivers()

if (!this->load_component(
package_name.value(), driver_name.value(), node_id.value(), *it, params,
node_namespace))
remappings, node_namespace))
{
RCLCPP_ERROR(
this->get_logger(),
Expand Down
Loading