diff --git a/cartographer_ros/cartographer_ros/msg_conversion.cc b/cartographer_ros/cartographer_ros/msg_conversion.cc index bc73b58..3b3afe5 100644 --- a/cartographer_ros/cartographer_ros/msg_conversion.cc +++ b/cartographer_ros/cartographer_ros/msg_conversion.cc @@ -375,7 +375,6 @@ std::unique_ptr CreateOccupancyGridMsg( const int width = cairo_image_surface_get_width(painted_slices.surface.get()); const int height = cairo_image_surface_get_height(painted_slices.surface.get()); - const ros::Time now = ros::Time::now(); occupancy_grid->header.stamp = time; occupancy_grid->header.frame_id = frame_id;