Skip to content

Commit

Permalink
Corrected publish calls with shared_ptr signature (#398)
Browse files Browse the repository at this point in the history
Signed-off-by: ivanpauno <ivanpauno@ekumenlabs.com>
  • Loading branch information
wjwwood authored May 6, 2019
1 parent b8be03d commit f99800c
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -84,10 +84,10 @@ class MapPublisher : public rclcpp::Node
}
}

auto occupancy_grid = std::make_shared<nav_msgs::msg::OccupancyGrid>();
occupancy_grid->header = header;
occupancy_grid->info = meta_data;
occupancy_grid->data = new_data;
nav_msgs::msg::OccupancyGrid occupancy_grid;
occupancy_grid.header = header;
occupancy_grid.info = meta_data;
occupancy_grid.data = new_data;

publisher->publish(occupancy_grid);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class PointCloud2Publisher : public rclcpp::Node
auto message = rviz_default_plugins::createPointCloud2WithPoints({{0, 0, 0}});
message->header.frame_id = "pointcloud2_frame";

publisher_->publish(message);
publisher_->publish(*message);
}

rclcpp::TimerBase::SharedPtr timer_;
Expand Down

0 comments on commit f99800c

Please sign in to comment.