Skip to content

Conversation

@christophfroehlich
Copy link
Member

@christophfroehlich christophfroehlich commented Nov 2, 2025

Fixes

2025-11-02T12:15:39.5228478Z --- stderr: admittance_controller
2025-11-02T12:15:39.5255761Z In file included from �[01m�[K/home/runner/work/ros2_controllers/ros2_controllers/.work/target_ws/src/ros2_controllers/admittance_controller/test/test_admittance_controller.cpp:17�[m�[K:
2025-11-02T12:15:39.5258958Z �[01m�[K/home/runner/work/ros2_controllers/ros2_controllers/.work/target_ws/src/ros2_controllers/admittance_controller/test/test_admittance_controller.hpp:�[m�[K In member function ‘�[01m�[Kvoid AdmittanceControllerTest::�[01;32m�[Kbroadcast_tfs�[m�[K()�[m�[K’:
2025-11-02T12:15:39.5265262Z �[01m�[K/home/runner/work/ros2_controllers/ros2_controllers/.work/target_ws/src/ros2_controllers/admittance_controller/test/test_admittance_controller.hpp:223:67:�[m�[K �[01;35m�[Kwarning: �[m�[K‘�[01m�[Ktf2_ros::TransformBroadcaster::�[01;32m�[KTransformBroadcaster�[m�[K(NodeT&&, const rclcpp::QoS&, const rclcpp::PublisherOptionsWithAllocator<AllocatorT>&) �[35m�[K[with NodeT = std::shared_ptr<rclcpp::Node>&; AllocatorT = std::allocator<void>; typename std::enable_if<rcpputils::is_pointer<T>::value, bool>::type <anonymous> = true]�[m�[K�[m�[K’ is deprecated: Use rclcpp::node_interfaces::NodeInterfaces instead of NodeT [�[01;35m�[K-Wdeprecated-declarations�[m�[K]
2025-11-02T12:15:39.5269779Z   223 |     static tf2_ros::TransformBroadcaster br(test_broadcaster_node_�[01;35m�[K)�[m�[K;
2025-11-02T12:20:19.3672881Z       |                                                                   �[01;35m�[K^�[m�[K
2025-11-02T12:20:19.3674513Z In file included from �[01m�[K/home/runner/work/ros2_controllers/ros2_controllers/.work/target_ws/src/ros2_controllers/admittance_controller/test/test_admittance_controller.hpp:41�[m�[K:
2025-11-02T12:20:19.3676446Z �[01m�[K/opt/ros/rolling/include/tf2_ros/tf2_ros/transform_broadcaster.hpp:92:3:�[m�[K �[01;36m�[Knote: �[m�[Kdeclared here
2025-11-02T12:20:19.3677495Z    92 |   �[01;36m�[KTransformBroadcaster�[m�[K(
2025-11-02T12:20:19.3678340Z       |   �[01;36m�[K^~~~~~~~~~~~~~~~~~~~�[m�[K
2025-11-02T12:20:19.3678735Z ---

from ros2/geometry2#714

@codecov
Copy link

codecov bot commented Nov 2, 2025

Codecov Report

✅ All modified and coverable lines are covered by tests.
✅ Project coverage is 85.32%. Comparing base (c38468c) to head (de523d2).
⚠️ Report is 3 commits behind head on master.

Additional details and impacted files
@@           Coverage Diff           @@
##           master    #1981   +/-   ##
=======================================
  Coverage   85.32%   85.32%           
=======================================
  Files         143      143           
  Lines       13934    13936    +2     
  Branches     1201     1201           
=======================================
+ Hits        11889    11891    +2     
  Misses       1638     1638           
  Partials      407      407           
Flag Coverage Δ
unittests 85.32% <100.00%> (+<0.01%) ⬆️

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

Files with missing lines Coverage Δ
...nce_controller/test/test_admittance_controller.hpp 95.10% <100.00%> (+0.05%) ⬆️
🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

Copy link
Member

@saikishor saikishor left a comment

Choose a reason for hiding this comment

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

Looks good to me, but is this only in the tests?

@christophfroehlich
Copy link
Member Author

Looks good to me, but is this only in the tests?

this is the only occurrence of tf2_ros::TransformBroadcaster

@christophfroehlich christophfroehlich merged commit 869c495 into master Nov 10, 2025
17 checks passed
@christophfroehlich christophfroehlich deleted the fix/tf-broadcaster branch November 10, 2025 17:19
@christophfroehlich christophfroehlich added the backport-kilted Triggers PR backport to ROS 2 kilted. label Nov 10, 2025
mergify bot pushed a commit that referenced this pull request Nov 10, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

backport-kilted Triggers PR backport to ROS 2 kilted.

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants