diff --git a/README.md b/README.md
index da162beda..def163a0e 100644
--- a/README.md
+++ b/README.md
@@ -10,55 +10,74 @@
| Buildfarm Build (kilted) | [](https://build.ros2.org/job/Kdev__ros2_canopen__ubuntu_noble_amd64/) |
| Buildfarm Build (jazzy) | [](https://build.ros2.org/job/Jdev__ros2_canopen__ubuntu_noble_amd64/) |
-The stack is currently under development and not yet ready for production use.
+The stack is currently under development and not yet ready for production use.
## Documentation
+
The documentation consists of two parts: a manual and an api reference.
The documentation is built for rolling (master), kilted, jazzy, iron and humble and hosted on github pages.
Older ROS 2 releases are EOL and are not supported anymore.
-***Note:** Master branch works with ROS2 **Jazzy**, **Kilted** and **Rolling** distributions. For **Humble** distribution use the `humble` branch.*
+***Note:** Master branch works with ROS2 **Jazzy**, **Kilted** and **Rolling** distributions.
+For **Humble** distribution use the `humble` branch.*
### Rolling
-* Manual: https://ros-industrial.github.io/ros2_canopen/manual/rolling/
-* API reference: https://ros-industrial.github.io/ros2_canopen/api/rolling/
+
+* Manual:
+* API reference:
### Humble
-* Manual: https://ros-industrial.github.io/ros2_canopen/manual/humble/
-* API reference: https://ros-industrial.github.io/ros2_canopen/api/humble/
+
+* Manual:
+* API reference:
## Features
-These are some of the features this stack implements. For further information please refer to the documentation.
+
+These are some of the features this stack implements.
+For further information please refer to the documentation.
* **YAML-Bus configuration**
- This canopen stack enables you to configure the bus using a YAML file. In this file you define the nodes that are connected to the bus by specifying their node id, the corresponding EDS file and the driver to run for the node. You can also specify further parameters that overwrite EDS parameters or are inputs to the driver.
+ This canopen stack enables you to configure the bus using a YAML file.
+In this file you define the nodes that are connected to the bus by specifying their node id, the corresponding EDS file and the driver to run for the node.
+You can also specify further parameters that overwrite EDS parameters or are inputs to the driver.
* **Service based operation**
- The stack can be operated using standard ROS2 nodes. In this case the device container will load the drivers for master and slave nodes. Each driver will be visible as a
- node and expose a ROS 2 interface. All drivers are brought up when the device manager is launched.
+ The stack can be operated using standard ROS2 nodes.
+In this case the device container will load the drivers for master and slave nodes.
+Each driver will be visible as a
+ node and expose a ROS 2 interface.
+All drivers are brought up when the device manager is launched.
* **Managed service based operation**
- The stack can be opeprated using managed ROS2 nodes. In
- this case the device container will load the drivers for master and slave nodes based on the bus configuration. Each driver will be a lifecycle node and expose a ROS 2 interface. The lifecycle manager can be used to bring all
+ The stack can be opeprated using managed ROS2 nodes.
+In
+ this case the device container will load the drivers for master and slave nodes based on the bus configuration.
+Each driver will be a lifecycle node and expose a ROS 2 interface.
+The lifecycle manager can be used to bring all
device up and down in the correct sequence.
* **ROS2 control based operation**
- Currently, multiple ros2_control interfaces are available. These can be used for controlling CANopen devices. The interfaces are:
+ Currently, multiple ros2_control interfaces are available.
+These can be used for controlling CANopen devices.
+The interfaces are:
* canopen_ros2_control/CANopenSystem
* canopen_ros2_control/CIA402System
* canopen_ros2_control/RobotSystem
* **CANopen drivers**
Currently, the following drivers are available:
- * ProxyDriver
- * Cia402Driver
-
+ * ProxyDriver
+ * Cia402Driver
## Post testing
+
To test stack after it was built from source you should first setup a virtual can network.
+
```bash
sudo modprobe vcan
sudo ip link add dev vcan0 type vcan
sudo ip link set vcan0 txqueuelen 1000
sudo ip link set up vcan0
```
+
Then you can launch a managed example
+
```bash
ros2 launch canopen_tests cia402_lifecycle_setup.launch.py
ros2 lifecycle set /lifecycle_manager configure
@@ -66,23 +85,28 @@ ros2 lifecycle set /lifecycle_manager activate
```
Or you can launch a standard example
+
```bash
ros2 launch canopen_tests cia402_setup.launch.py
```
Or you can launch a ros2_control example
+
```bash
ros2 launch canopen_tests robot_control_setup.launch.py
```
## Contributing
+
This repository uses `pre-commit` for code formatting.
This program has to be setup locally and installed inside the repository.
For this execute in the repository folder following commands:
-```
+
+```sh
sudo apt install -y pre-commit
pre-commit install
```
+
The checks are automatically executed before each commit.
This helps you to always commit well formatted code.
To run all the checks manually use `pre-commit run -a` command.
@@ -107,6 +131,7 @@ In a case of an "emergency" you can avoid execution of pre-commit hooks by addin
| canopen_utils | [](https://build.ros2.org/job/Rbin_uN64__canopen_utils__ubuntu_noble_amd64__binary/) | [](https://build.ros2.org/job/Rbin_rhel_el964__canopen_utils__rhel_9_x86_64__binary/) |
## Kilted Distribution (Noble & RHEL9)
+
| Package | Noble (Ubuntu) | RHEL9 |
|--------------------------|---------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------|
| canopen_interfaces | [](https://build.ros2.org/job/Kbin_uN64__canopen_interfaces__ubuntu_noble_amd64__binary/) | [](https://build.ros2.org/job/Kbin_rhel_el964__canopen_interfaces__rhel_9_x86_64__binary/) |
@@ -122,6 +147,7 @@ In a case of an "emergency" you can avoid execution of pre-commit hooks by addin
| canopen_utils | [](https://build.ros2.org/job/Kbin_uN64__canopen_utils__ubuntu_noble_amd64__binary/) | [](https://build.ros2.org/job/Kbin_rhel_el964__canopen_utils__rhel_9_x86_64__binary/) |
## Jazzy Distribution (Noble & RHEL9)
+
| Package | Noble (Ubuntu) | RHEL9 |
|--------------------------|---------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------|
| canopen_interfaces | [](https://build.ros2.org/job/Jbin_uN64__canopen_interfaces__ubuntu_noble_amd64__binary/) | [](https://build.ros2.org/job/Jbin_rhel_el964__canopen_interfaces__rhel_9_x86_64__binary/) |
diff --git a/canopen_core/include/canopen_core/detail/dcf_preprocessor.hpp b/canopen_core/include/canopen_core/detail/dcf_preprocessor.hpp
new file mode 100644
index 000000000..a4120555e
--- /dev/null
+++ b/canopen_core/include/canopen_core/detail/dcf_preprocessor.hpp
@@ -0,0 +1,170 @@
+// Copyright 2026 Tim Clephas, Nobleo Autonomous Solutions B.V.
+//
+// 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.
+
+#pragma once
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+namespace ros2_canopen::detail
+{
+
+/**
+ * @brief Expand environment variables in a string.
+ *
+ * Replaces ${VAR} or $VAR patterns with the corresponding environment variable value.
+ *
+ * @param input String potentially containing environment variable references
+ * @return String with environment variables expanded
+ */
+inline std::string expand_environment_variables(const std::string & input)
+{
+ std::string result = input;
+
+ // Match ${VAR} pattern
+ std::regex env_regex_braces(R"(\$\{([^}]+)\})");
+ std::smatch match;
+ while (std::regex_search(result, match, env_regex_braces))
+ {
+ const char * env_value = std::getenv(match[1].str().c_str());
+ std::string replacement = env_value ? env_value : "";
+ result = match.prefix().str() + replacement + match.suffix().str();
+ }
+
+ // Match $VAR pattern
+ std::regex env_regex_plain(R"(\$([A-Za-z_][A-Za-z0-9_]*))");
+ while (std::regex_search(result, match, env_regex_plain))
+ {
+ const char * env_value = std::getenv(match[1].str().c_str());
+ std::string replacement = env_value ? env_value : "";
+ result = match.prefix().str() + replacement + match.suffix().str();
+ }
+
+ return result;
+}
+
+/**
+ * @brief Resolve a potentially relative file path to an absolute path.
+ *
+ * If the path is relative, resolves it relative to base_dir.
+ * Also expands environment variables.
+ *
+ * @param path Path to resolve (may be relative or absolute)
+ * @param base_dir Base directory for resolving relative paths
+ * @return Absolute path string
+ */
+inline std::string resolve_file_path(
+ const std::string & path, const std::filesystem::path & base_dir)
+{
+ // First expand any environment variables
+ std::string expanded = expand_environment_variables(path);
+
+ std::filesystem::path fs_path(expanded);
+
+ // If relative, make it relative to base_dir
+ if (fs_path.is_relative())
+ {
+ fs_path = base_dir / fs_path;
+ }
+
+ // Normalize the path (resolve . and ..)
+ try
+ {
+ return std::filesystem::canonical(fs_path).string();
+ }
+ catch (const std::filesystem::filesystem_error &)
+ {
+ // If canonical fails (e.g., path doesn't exist), use weakly_canonical
+ return std::filesystem::weakly_canonical(fs_path).string();
+ }
+}
+
+/**
+ * @brief Preprocess DCF and write to a temporary file.
+ *
+ * Creates a temp file with preprocessed content (resolved UploadFile/DownloadFile paths).
+ * If no relative paths are found, returns the original path unchanged.
+ *
+ * @param dcf_path Path to the original DCF file
+ * @return Path to the preprocessed temporary file, or original path if no changes needed.
+ */
+inline std::string preprocess_dcf_to_temp(const std::string & dcf_path)
+{
+ std::filesystem::path dcf_file(dcf_path);
+ std::filesystem::path dcf_dir = dcf_file.parent_path();
+ if (dcf_dir.empty())
+ {
+ dcf_dir = std::filesystem::current_path();
+ }
+
+ std::ifstream infile(dcf_path);
+ if (!infile.is_open())
+ {
+ throw std::runtime_error("Failed to open DCF file: " + dcf_path);
+ }
+
+ std::stringstream result;
+ std::string line;
+ bool needs_preprocessing = false;
+
+ // Regex to match UploadFile= or DownloadFile= entries
+ std::regex file_entry_regex(R"(^(UploadFile|DownloadFile)=(.*)$)", std::regex::icase);
+
+ while (std::getline(infile, line))
+ {
+ std::smatch match;
+ if (std::regex_match(line, match, file_entry_regex))
+ {
+ std::string key = match[1].str();
+ std::string value = match[2].str();
+ std::string resolved = resolve_file_path(value, dcf_dir);
+
+ if (resolved != value)
+ {
+ needs_preprocessing = true;
+ }
+ result << key << "=" << resolved << "\n";
+ }
+ else
+ {
+ result << line << "\n";
+ }
+ }
+
+ if (!needs_preprocessing)
+ {
+ return dcf_path; // No changes needed
+ }
+
+ // Create temp file
+ std::filesystem::path temp_dir = std::filesystem::temp_directory_path();
+ std::filesystem::path temp_file =
+ temp_dir / ("canopen_" + std::to_string(std::hash{}(dcf_path)) + "_" +
+ dcf_file.filename().string());
+
+ std::ofstream outfile(temp_file);
+ if (!outfile.is_open())
+ {
+ throw std::runtime_error("Failed to create temp DCF file: " + temp_file.string());
+ }
+
+ outfile << result.str();
+ return temp_file.string();
+}
+
+} // namespace ros2_canopen::detail
diff --git a/canopen_core/include/canopen_core/node_interfaces/node_canopen_master.hpp b/canopen_core/include/canopen_core/node_interfaces/node_canopen_master.hpp
index 29ec2375e..89461c349 100644
--- a/canopen_core/include/canopen_core/node_interfaces/node_canopen_master.hpp
+++ b/canopen_core/include/canopen_core/node_interfaces/node_canopen_master.hpp
@@ -26,9 +26,11 @@
#include
#include
#include
+#include
#include
#include
#include
+#include "canopen_core/detail/dcf_preprocessor.hpp"
#include "canopen_core/master_error.hpp"
#include "canopen_core/node_interfaces/node_canopen_master_interface.hpp"
@@ -40,7 +42,7 @@ namespace node_interfaces
* @brief Node Canopen Master
*
* This class implements the NodeCanopenMasterInterface. It provides
- * core functionality and logic for CanopenMaster, indepentently of the
+ * core functionality and logic for CanopenMaster, independently of the
* ROS node type. Currently rclcpp::Node and rclcpp_lifecycle::LifecycleNode
* and derived classes are supported. Other node types will lead to compile
* time error.
@@ -163,6 +165,22 @@ class NodeCanopenMaster : public NodeCanopenMasterInterface
this->config_ = YAML::Load(config);
this->non_transmit_timeout_ = std::chrono::milliseconds(non_transmit_timeout);
+ // Preprocess DCF to resolve relative UploadFile/DownloadFile paths
+ // This enables portable install spaces by converting relative paths to absolute
+ try
+ {
+ std::string preprocessed = detail::preprocess_dcf_to_temp(master_dcf_);
+ RCLCPP_INFO_EXPRESSION(
+ node_->get_logger(), preprocessed != master_dcf_,
+ "Preprocessed DCF file for portable paths: %s -> %s", master_dcf_.c_str(),
+ preprocessed.c_str());
+ }
+ catch (const std::exception & e)
+ {
+ RCLCPP_WARN(
+ node_->get_logger(), "Failed to preprocess DCF file: %s. Using original.", e.what());
+ }
+
this->configure(true);
this->configured_.store(true);
}
diff --git a/canopen_core/src/configuration_manager.cpp b/canopen_core/src/configuration_manager.cpp
index 9b42802d8..5a8263112 100644
--- a/canopen_core/src/configuration_manager.cpp
+++ b/canopen_core/src/configuration_manager.cpp
@@ -13,14 +13,22 @@
// limitations under the License.
#include "canopen_core/configuration_manager.hpp"
-#include
+#include "canopen_core/detail/dcf_preprocessor.hpp"
namespace ros2_canopen
{
void ConfigurationManager::init_config()
{
- std::string dcf_path = "";
+ // Get the directory containing the bus config file
+ std::filesystem::path config_dir = std::filesystem::path(file_).parent_path();
+ if (config_dir.empty())
+ {
+ config_dir = std::filesystem::current_path();
+ }
+
+ // Default dcf_path to "." (same directory as bus.yml) for portable install spaces
+ std::string dcf_path = ".";
for (YAML::const_iterator it = root_.begin(); it != root_.end(); it++)
{
std::string driver_name = it->first.as();
@@ -29,9 +37,14 @@ void ConfigurationManager::init_config()
if (config_node["dcf_path"])
{
dcf_path = config_node["dcf_path"].as();
+ // Resolve the path (handles relative paths and environment variables)
+ dcf_path = detail::resolve_file_path(dcf_path, config_dir);
}
}
+ // Resolve the dcf_path (handles relative paths and environment variables)
+ dcf_path = detail::resolve_file_path(dcf_path, config_dir);
+
for (YAML::const_iterator it = root_.begin(); it != root_.end(); it++)
{
std::string driver_name = it->first.as();
@@ -41,6 +54,12 @@ void ConfigurationManager::init_config()
{
config_node["dcf_path"] = dcf_path;
}
+ else
+ {
+ // Also resolve per-device dcf_path if specified
+ std::string device_dcf_path = config_node["dcf_path"].as();
+ config_node["dcf_path"] = detail::resolve_file_path(device_dcf_path, config_dir);
+ }
devices_.insert({driver_name, config_node});
}
}
diff --git a/canopen_tests/config/simple/bus.yml b/canopen_tests/config/simple/bus.yml
index d590f0d80..2f05d6de5 100644
--- a/canopen_tests/config/simple/bus.yml
+++ b/canopen_tests/config/simple/bus.yml
@@ -1,6 +1,3 @@
-options:
- dcf_path: "@BUS_CONFIG_PATH@"
-
master:
node_id: 1
driver: "ros2_canopen::MasterDriver"
@@ -8,7 +5,7 @@ master:
proxy_device_1:
node_id: 2
- dcf: "simple.eds"
+ dcf: "simple.eds" # relative to bus.yml
driver: "ros2_canopen::ProxyDriver"
package: "canopen_proxy_driver"
polling: true
diff --git a/lely_core_libraries/cmake/lely_core_libraries-extras.cmake b/lely_core_libraries/cmake/lely_core_libraries-extras.cmake
index 0f095ef6c..4ebb2aace 100644
--- a/lely_core_libraries/cmake/lely_core_libraries-extras.cmake
+++ b/lely_core_libraries/cmake/lely_core_libraries-extras.cmake
@@ -16,6 +16,10 @@
macro(
generate_dcf
TARGET)
+ message(DEPRECATION
+ "@BUS_CONFIG_PATH@ in bus.yml is deprecated and might be removed in a future release. "
+ "Use relative paths (e.g., dcf_path: \".\") instead. "
+ "The runtime resolves relative paths to absolute paths automatically.")
add_custom_target(
${TARGET}_prepare ALL
COMMAND rm -rf ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}/*
@@ -29,9 +33,10 @@ macro(
DEPENDS ${TARGET}_prepare
)
+ # Use relative path "." for portable install spaces
add_custom_command(
TARGET ${TARGET} POST_BUILD
- COMMAND sed 's|@BUS_CONFIG_PATH@|${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}|g'
+ COMMAND sed 's|@BUS_CONFIG_PATH@|.|g'
${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/bus.yml > ${CMAKE_BINARY_DIR}/config/${TARGET}/bus.yml
COMMAND dcfgen -v -d ${CMAKE_BINARY_DIR}/config/${TARGET}/ -rS ${CMAKE_BINARY_DIR}/config/${TARGET}/bus.yml
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/
@@ -53,6 +58,10 @@ endmacro()
macro(
cogen_dcf
TARGET)
+ message(DEPRECATION
+ "@BUS_CONFIG_PATH@ in bus.yml is deprecated and might be removed in a future release. "
+ "Use relative paths (e.g., dcf_path: \".\") instead. "
+ "The runtime resolves relative paths to absolute paths automatically.")
add_custom_target(
${TARGET}_prepare ALL
COMMAND rm -rf ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}/*
@@ -66,10 +75,11 @@ macro(
DEPENDS ${TARGET}_prepare
)
+ # Use relative path "." for portable install spaces
add_custom_command(
TARGET ${TARGET} POST_BUILD
COMMAND cogen --input-file ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/bus.yml --output-file ${CMAKE_BINARY_DIR}/config/${TARGET}/preprocessed_bus.yml
- COMMAND sed 's|@BUS_CONFIG_PATH@|${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}|g'
+ COMMAND sed 's|@BUS_CONFIG_PATH@|.|g'
${CMAKE_BINARY_DIR}/config/${TARGET}/preprocessed_bus.yml > ${CMAKE_BINARY_DIR}/config/${TARGET}/bus.yml
COMMAND dcfgen -v -d ${CMAKE_BINARY_DIR}/config/${TARGET}/ -rS ${CMAKE_BINARY_DIR}/config/${TARGET}/bus.yml
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/