diff --git a/rviz_default_plugins/test/rviz_default_plugins/publishers/map_publisher.hpp b/rviz_default_plugins/test/rviz_default_plugins/publishers/map_publisher.hpp index 63827e470..0f3b4834f 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/publishers/map_publisher.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/publishers/map_publisher.hpp @@ -84,10 +84,10 @@ class MapPublisher : public rclcpp::Node } } - auto occupancy_grid = std::make_shared(); - 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); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/publishers/point_cloud2_publisher.hpp b/rviz_default_plugins/test/rviz_default_plugins/publishers/point_cloud2_publisher.hpp index ffc81056b..503e86094 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/publishers/point_cloud2_publisher.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/publishers/point_cloud2_publisher.hpp @@ -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_;