Skip to content

Commit

Permalink
add patch for grid map pcl
Browse files Browse the repository at this point in the history
Signed-off-by: wep21 <daisuke.nishimatsu1021@gmail.com>
  • Loading branch information
wep21 committed Feb 15, 2025
1 parent ab0aa98 commit b858f07
Showing 1 changed file with 16 additions and 0 deletions.
16 changes: 16 additions & 0 deletions patch/ros-jazzy-grid-map-pcl.osx.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
diff --git a/include/grid_map_pcl/helpers.hpp b/include/grid_map_pcl/helpers.hpp
index f3d9f38..fc94637 100644
--- a/include/grid_map_pcl/helpers.hpp
+++ b/include/grid_map_pcl/helpers.hpp
@@ -42,7 +42,11 @@ void saveGridMap(
const std::string & mapTopic);

inline void printTimeElapsedToRosInfoStream(
+#if defined(__APPLE__)
+ const std::chrono::steady_clock::time_point & start,
+#else
const std::chrono::system_clock::time_point & start,
+#endif
const std::string & prefix,
const rclcpp::Logger & node_logger)
{

0 comments on commit b858f07

Please sign in to comment.