Skip to content

Conversation

christophfroehlich
Copy link
Contributor

This is useful to replay bags and inject state interfaces from a hardware component into the ros2_control stack.

I'm open for any name suggestions ;)

@codecov-commenter
Copy link

codecov-commenter commented Sep 24, 2025

Codecov Report

❌ Patch coverage is 41.66667% with 28 lines in your changes missing coverage. Please review.
✅ Project coverage is 39.37%. Comparing base (007cff1) to head (036b594).
⚠️ Report is 1 commits behind head on main.

Files with missing lines Patch % Lines
...ware_component/src/cm_topic_hardware_component.cpp 16.66% 24 Missing and 1 partial ⚠️
...omponent/test/cm_topic_hardware_component_test.cpp 83.33% 3 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main      #33      +/-   ##
==========================================
+ Coverage   38.62%   39.37%   +0.75%     
==========================================
  Files           2        4       +2     
  Lines         145      193      +48     
  Branches       34       40       +6     
==========================================
+ Hits           56       76      +20     
- Misses         80      107      +27     
- Partials        9       10       +1     
Flag Coverage Δ
unittests 39.37% <41.66%> (+0.75%) ⬆️

Flags with carried forward coverage won't be shown. Click here to find out more.

Files with missing lines Coverage Δ
...omponent/test/cm_topic_hardware_component_test.cpp 83.33% <83.33%> (ø)
...ware_component/src/cm_topic_hardware_component.cpp 16.66% <16.66%> (ø)
🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.
  • 📦 JS Bundle Analysis: Save yourself from yourself by tracking and limiting bundle sizes in JS merges.

Comment on lines +57 to +58
const size_t N = std::min(names.size(), latest_pal_values_.values.size());
for (size_t i = 0; i < N; i++)
Copy link
Member

Choose a reason for hiding this comment

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

I think it is better to check if both the data are of same size before continuing, because I'm not sure if the variables are appended or reordered for every instance

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I just copied this from plotjuggler
https://github.com/facontidavide/PlotJuggler/blob/75f9885826a7aca8c337057d368fe9e4ccfd89b2/plotjuggler_plugins/ParserROS/ros_parser.cpp#L585-L590

not sure why this std::min makes sense here? maybe for robustness for different data sources publishing the same names_version?

Comment on lines +35 to +38
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
Member

Choose a reason for hiding this comment

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

Do we need to worry about concurrent access?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

that's what my comment in L30 is about. But as there is no such thing in the other component here, I thought that it might not be worth it

topic_based_joint_states_subscriber_ = get_node()->create_subscription<sensor_msgs::msg::JointState>(
get_hardware_parameter("joint_states_topic", "/robot_joint_states"), rclcpp::SensorDataQoS(),
[this](const sensor_msgs::msg::JointState::SharedPtr joint_state) { latest_joint_state_ = *joint_state; });

"~/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

#include <rclcpp_lifecycle/state.hpp>
#include <ros2_control_test_assets/descriptions.hpp>

TEST(TestTopicBasedSystem, load_topic_based_system_2dof)
Copy link
Collaborator

Choose a reason for hiding this comment

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

What do you think about adding a test that publishes on the topics this system is listening to and verifying the state matches?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

would be great :D

Copy link
Collaborator

Choose a reason for hiding this comment

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

Awesome! Maybe have some data in there that is should nicely ignore 😄.

        if (joint_state_interfaces_.find(name) != joint_state_interfaces_.end() ||
            sensor_state_interfaces_.find(name) != sensor_state_interfaces_.end() ||
            gpio_state_interfaces_.find(name) != gpio_state_interfaces_.end() ||
            unlisted_state_interfaces_.find(name) != unlisted_state_interfaces_.end())

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants