Skip to content

Commit 3df3700

Browse files
authored
Update subscription callback signatures (#2225)
Signed-off-by: mini-1235 <[email protected]>
1 parent d20f755 commit 3df3700

File tree

3 files changed

+4
-4
lines changed

3 files changed

+4
-4
lines changed

rosbag2_examples/rosbag2_examples_cpp/src/compressed_bag_recorder.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ class CompressedBagRecorder : public rclcpp::Node {
4545
}
4646

4747
private:
48-
void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
48+
void topic_callback(std::shared_ptr<const rclcpp::SerializedMessage> msg) const
4949
{
5050
rclcpp::Time time_stamp = this->now();
5151

rosbag2_examples/rosbag2_examples_cpp/src/simple_bag_recorder.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ class SimpleBagRecorder : public rclcpp::Node
3636
}
3737

3838
private:
39-
void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
39+
void topic_callback(std::shared_ptr<const rclcpp::SerializedMessage> msg) const
4040
{
4141
rclcpp::Time time_stamp = this->now();
4242
writer_->write(msg, "chatter", "example_interfaces/msg/String", time_stamp);

rosbag2_test_common/include/rosbag2_test_common/subscription_manager.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class SubscriptionManager
6363
subscriber_node_->create_subscription<MessageT>(
6464
topic_name,
6565
qos,
66-
[this, topic_name](std::shared_ptr<rclcpp::SerializedMessage> msg) {
66+
[this, topic_name](std::shared_ptr<const rclcpp::SerializedMessage> msg) {
6767
subscribed_messages_[topic_name].push_back(msg);
6868
},
6969
options);
@@ -219,7 +219,7 @@ class SubscriptionManager
219219

220220
std::unordered_map<std::string, rclcpp::SubscriptionBase::SharedPtr> subscriptions_;
221221
std::unordered_map<std::string,
222-
std::vector<std::shared_ptr<rclcpp::SerializedMessage>>> subscribed_messages_;
222+
std::vector<std::shared_ptr<const rclcpp::SerializedMessage>>> subscribed_messages_;
223223
std::unordered_map<std::string, size_t> expected_topics_with_size_;
224224
rclcpp::Node::SharedPtr subscriber_node_;
225225
const std::chrono::milliseconds sleep_per_loop_ = std::chrono::milliseconds(2);

0 commit comments

Comments
 (0)