Skip to content

Commit 58e5a62

Browse files
emersonknappwjwwood
authored andcommitted
Fix call to create_publisher after API changed (#105)
* Fix call to create_publisher after API changed Signed-off-by: Emerson Knapp <[email protected]> * revert whitespace changes
1 parent 1073aca commit 58e5a62

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

tf2_ros/include/tf2_ros/static_transform_broadcaster.h

+2-1
Original file line numberDiff line numberDiff line change
@@ -64,9 +64,10 @@ class StaticTransformBroadcaster{
6464

6565
using MessageT = tf2_msgs::msg::TFMessage;
6666
using PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>;
67+
rclcpp::PublisherEventCallbacks callbacks;
6768
publisher_ = rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
6869
node_topics_interface.get(), "/tf_static",
69-
custom_qos_profile, false, std::make_shared<AllocatorT>());
70+
custom_qos_profile, callbacks, nullptr, false, std::make_shared<AllocatorT>());
7071
}
7172

7273
/** \brief Send a TransformStamped message

0 commit comments

Comments
 (0)