Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
0de1722
Initial version for rosbag replay component
christophfroehlich Sep 23, 2025
18d39e0
Cleanup
christophfroehlich Sep 23, 2025
eccba8a
Pre-commit
christophfroehlich Sep 23, 2025
2cf0578
Add some documentation
christophfroehlich Sep 24, 2025
6098d91
Activate gmock test
christophfroehlich Sep 24, 2025
7807816
Cleanup
christophfroehlich Sep 24, 2025
81eeb5f
Early abort if no message is received yet
christophfroehlich Sep 24, 2025
b96d057
Format code
christophfroehlich Sep 24, 2025
9c5acb5
Update clock topic in docs
christophfroehlich Sep 24, 2025
d80c16a
Update package description
christophfroehlich Sep 24, 2025
324639b
Fix test for jazzy
christophfroehlich Sep 24, 2025
ab30d66
Fix comment
christophfroehlich Sep 24, 2025
aedcd9c
Rename package
christophfroehlich Sep 24, 2025
ba67168
Update copyright claim
christophfroehlich Sep 24, 2025
bd9f7ca
Merge branch 'main' into add/CMTopicSystem
saikishor Sep 24, 2025
32a8351
Remove old comment
christophfroehlich Oct 3, 2025
036b594
Merge branch 'main' into add/CMTopicSystem
christophfroehlich Oct 3, 2025
002ec8a
Add test with received messages
christophfroehlich Oct 17, 2025
b2ff118
Add throttled warning
christophfroehlich Oct 17, 2025
96365e3
Merge branch 'main' into add/CMTopicSystem
christophfroehlich Oct 17, 2025
93f280d
Fix -Wsign-conversion
christophfroehlich Oct 17, 2025
09887bc
Use has_state instead
christophfroehlich Oct 19, 2025
286b51f
Simplify code
christophfroehlich Oct 19, 2025
e204d49
Merge branch 'main' into add/CMTopicSystem
christophfroehlich Oct 22, 2025
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
77 changes: 77 additions & 0 deletions cm_topic_hardware_component/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
cmake_minimum_required(VERSION 3.16)
project(cm_topic_hardware_component CXX)

find_package(ros2_control_cmake REQUIRED)
set_compiler_options()
if(WIN32)
# set the same behavior for windows as it is on linux
export_windows_symbols()
endif()

option(BUILD_SHARED_LIBS "Build shared libraries" ON)

set(THIS_PACKAGE_INCLUDE_DEPENDS
angles
rclcpp
hardware_interface
pal_statistics_msgs
)

find_package(ament_cmake REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

###########
## Build ##
###########

# Declare a C++ library
add_library(
${PROJECT_NAME}
src/cm_topic_hardware_component.cpp
)
target_link_libraries(${PROJECT_NAME} PUBLIC
angles::angles
rclcpp::rclcpp
hardware_interface::hardware_interface
${pal_statistics_msgs_TARGETS})
target_include_directories(${PROJECT_NAME}
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_17)

#############
## Install ##
#############

install(
TARGETS ${PROJECT_NAME}
EXPORT ${PROJECT_NAME}Targets
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION lib/${PROJECT_NAME}
)

#############
## Testing ##
#############

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ros2_control_test_assets REQUIRED)

# GTests
ament_add_gmock(cm_topic_hardware_component_test test/cm_topic_hardware_component_test.cpp)
target_link_libraries(cm_topic_hardware_component_test
${PROJECT_NAME}
rclcpp::rclcpp
hardware_interface::hardware_interface
${pal_statistics_msgs_TARGETS}
ros2_control_test_assets::ros2_control_test_assets)
endif()

pluginlib_export_plugin_description_file(hardware_interface cm_topic_hardware_component_plugin_description.xml)
ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
3 changes: 3 additions & 0 deletions cm_topic_hardware_component/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# cm_topic_hardware_component

See doc/index.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<library path="cm_topic_hardware_component">
<class
name="cm_topic_hardware_component/CMTopicSystem"
type="cm_topic_hardware_component::CMTopicSystem"
base_class_type="hardware_interface::SystemInterface"
>
<description>
ros2_control hardware interface for CM topic based control.
</description>
</class>
</library>
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
// Copyright 2025 AIT Austrian Institute of Technology GmbH
//
// 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.

/* Author: Christoph Froehlich */

#pragma once

// C++
#include <memory>
#include <string>

// ROS
#include <hardware_interface/system_interface.hpp>
#include <hardware_interface/types/hardware_component_interface_params.hpp>
#include <rclcpp/subscription.hpp>

#include <pal_statistics_msgs/msg/statistics_names.hpp>
#include <pal_statistics_msgs/msg/statistics_values.hpp>

namespace cm_topic_hardware_component
{
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class CMTopicSystem : public hardware_interface::SystemInterface
{
public:
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams& params) override;

hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;

hardware_interface::return_type write(const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) override;

private:
rclcpp::Subscription<pal_statistics_msgs::msg::StatisticsNames>::SharedPtr pal_names_subscriber_;
rclcpp::Subscription<pal_statistics_msgs::msg::StatisticsValues>::SharedPtr pal_values_subscriber_;
pal_statistics_msgs::msg::StatisticsValues latest_pal_values_;
std::unordered_map<uint32_t, std::vector<std::string>> pal_statistics_names_per_topic_;
};

} // namespace cm_topic_hardware_component
34 changes: 34 additions & 0 deletions cm_topic_hardware_component/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<?xml version="1.0"?>
<package format="3">
<name>cm_topic_hardware_component</name>
<version>0.2.0</version>
<description>ros2_control hardware interface using pal_statistics messages</description>

<maintainer email="marq.razz@gmail.com">Marq Rasmussen</maintainer>
<maintainer email="jafar.uruc@gmail.com">Jafar Uruc</maintainer>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>

<author email="christoph.froehlich@ait.ac.at">Christoph Froehlich</author>

<license>Apache License 2.0</license>

<url type="website">https://github.com/ros-controls/topic_based_hardware_interfaces</url>
<url type="bugtracker">
https://github.com/ros-controlsros-controls/topic_based_hardware_interfaces/issues</url>
<url type="repository">https://github.com/ros-controlsros-controls/topic_based_hardware_interfaces</url>

<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>ros2_control_cmake</build_depend>

<depend>rclcpp</depend>
<depend>hardware_interface</depend>
<depend>pal_statistics_msgs</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>hardware_interface</test_depend>
<test_depend>ros2_control_test_assets</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
87 changes: 87 additions & 0 deletions cm_topic_hardware_component/src/cm_topic_hardware_component.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
// Copyright 2025 AIT Austrian Institute of Technology GmbH
//
// 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.

/* Author: Christoph Froehlich */

#include <string>

#include <cm_topic_hardware_component/cm_topic_hardware_component.hpp>

namespace cm_topic_hardware_component
{

CallbackReturn CMTopicSystem::on_init(const hardware_interface::HardwareComponentInterfaceParams& params)
{
if (hardware_interface::SystemInterface::on_init(params) != CallbackReturn::SUCCESS)
{
return CallbackReturn::ERROR;
}
// TODO(christophfroehlich): should we use RT box here?
pal_names_subscriber_ = get_node()->create_subscription<pal_statistics_msgs::msg::StatisticsNames>(
"~/names", rclcpp::SensorDataQoS(), [this](const pal_statistics_msgs::msg::StatisticsNames::SharedPtr pal_names) {
pal_statistics_names_per_topic_[pal_names->names_version] = std::move(pal_names->names);
});
pal_values_subscriber_ = get_node()->create_subscription<pal_statistics_msgs::msg::StatisticsValues>(
"~/values", rclcpp::SensorDataQoS(),
[this](const pal_statistics_msgs::msg::StatisticsValues::SharedPtr pal_values) {
latest_pal_values_ = *pal_values;
});
Copy link
Collaborator

Choose a reason for hiding this comment

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

Should we add a warning if nothing is publishing on the configured topics? That or add a throttled print when // no data received yet in read().

Copy link
Contributor Author

Choose a reason for hiding this comment

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

in my case it was obvious because no joint_states/tf was published then. But sure, a throttled warning does not hurt

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed with b2ff118


return CallbackReturn::SUCCESS;
}

hardware_interface::return_type CMTopicSystem::read(const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/)
{
if (latest_pal_values_.names_version == 0 || pal_statistics_names_per_topic_.empty())
{
RCLCPP_WARN_THROTTLE(get_node()->get_logger(), *get_node()->get_clock(), 1000, "No data received yet");
return hardware_interface::return_type::OK;
}

auto it = pal_statistics_names_per_topic_.find(latest_pal_values_.names_version);
if (it != pal_statistics_names_per_topic_.end())
{
const auto& names = it->second;
const size_t N = std::min(names.size(), latest_pal_values_.values.size());
for (size_t i = 0; i < N; i++)
{
// If name begins with "state_interface.", extract the remainder
const std::string prefix = "state_interface.";
if (names[i].rfind(prefix, 0) == 0)
{ // starts with prefix
const auto& name = names[i].substr(prefix.length());
if (has_state(name))
{
// TODO(christophfroehlich): does not support other values than double now
set_state(name, latest_pal_values_.values.at(i));
}
}
}
}
else
{
RCLCPP_WARN(get_node()->get_logger(), "No matching statistics names found");
}
return hardware_interface::return_type::OK;
}

hardware_interface::return_type CMTopicSystem::write(const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/)
{
// nothing to do here
return hardware_interface::return_type::OK;
}
} // end namespace cm_topic_hardware_component

#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(cm_topic_hardware_component::CMTopicSystem, hardware_interface::SystemInterface)
Loading
Loading