Skip to content

Commit

Permalink
updated to new SerializedMessage
Browse files Browse the repository at this point in the history
Signed-off-by: Joshua Hampp <j.hampp@denso-adas.de>
  • Loading branch information
Joshua Hampp committed Apr 22, 2020
1 parent d676d12 commit aeb69bf
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,7 @@ class Publisher : public PublisherBase
do_inter_process_publish(const T & msg)
{
// for serialized messages the serialized method is needed
do_serialized_publish(&msg);
do_serialized_publish(&msg.get_rcl_serialized_message());
}

void
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/test_intra_process_communication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,8 +142,8 @@ std::array<uint32_t, 2> counts;

void OnMessageSerialized(const std::shared_ptr<const rclcpp::SerializedMessage> msg)
{
EXPECT_NE(msg->buffer, nullptr);
EXPECT_GT(msg->buffer_capacity, 0u);
EXPECT_NE(msg->get_rcl_serialized_message().buffer, nullptr);
EXPECT_GT(msg->get_rcl_serialized_message().buffer_capacity, 0u);

++counts[0];
}
Expand Down

0 comments on commit aeb69bf

Please sign in to comment.