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 85.47009% with 17 lines in your changes missing coverage. Please review.
✅ Project coverage is 68.85%. Comparing base (cd86811) to head (286b51f).

Files with missing lines Patch % Lines
...omponent/test/cm_topic_hardware_component_test.cpp 87.35% 9 Missing and 2 partials ⚠️
...ware_component/src/cm_topic_hardware_component.cpp 80.00% 2 Missing and 4 partials ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main      #33      +/-   ##
==========================================
+ Coverage   61.44%   68.85%   +7.40%     
==========================================
  Files           3        5       +2     
  Lines         249      366     +117     
  Branches       42       52      +10     
==========================================
+ Hits          153      252      +99     
- Misses         75       86      +11     
- Partials       21       28       +7     
Flag Coverage Δ
unittests 68.85% <85.47%> (+7.40%) ⬆️

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

Files with missing lines Coverage Δ
...ware_component/src/cm_topic_hardware_component.cpp 80.00% <80.00%> (ø)
...omponent/test/cm_topic_hardware_component_test.cpp 87.35% <87.35%> (ø)

... and 1 file with indirect coverage changes

🚀 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.

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

#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())

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Added some tests with 002ec8a

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