Skip to content

Commit

Permalink
publisher handle returns shared pointer (#31)
Browse files Browse the repository at this point in the history
Signed-off-by: Knese Karsten <karsten.knese@us.bosch.com>
  • Loading branch information
Karsten1987 authored Jun 1, 2020
1 parent a0b7646 commit 26a82d8
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion iceoryx_ros2_bridge/src/generic_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ void GenericPublisher::publish(std::shared_ptr<rmw_serialized_message_t> message
void GenericPublisher::publish(const rmw_serialized_message_t * message)
{
auto return_code = rcl_publish_serialized_message(
get_publisher_handle(), message, NULL);
get_publisher_handle().get(), message, NULL);

if (return_code != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(return_code, "failed to publish serialized message");
Expand Down

0 comments on commit 26a82d8

Please sign in to comment.