Skip to content

Commit db2f917

Browse files
authored
windows build fix. (#1959)
1 parent 671dde6 commit db2f917

File tree

4 files changed

+7
-2
lines changed

4 files changed

+7
-2
lines changed

nav2_bt_navigator/src/ros_topic_logger.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ void RosTopicLogger::callback(
4343
event.timestamp =
4444
tf2_ros::toMsg(std::chrono::time_point<std::chrono::high_resolution_clock>(timestamp));
4545
#else
46-
event.timestamp = tf2_ros::toMsg(timestamp);
46+
event.timestamp = tf2_ros::toMsg(tf2::TimePoint(timestamp));
4747
#endif
4848
event.node_name = node.name();
4949
event.previous_status = toStr(prev_status, false);

nav2_costmap_2d/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
<buildtool_depend>ament_cmake</buildtool_depend>
2020
<build_depend>nav2_common</build_depend>
2121

22+
<depend>angles</depend>
2223
<depend>geometry_msgs</depend>
2324
<depend>laser_geometry</depend>
2425
<depend>map_msgs</depend>

nav2_dwb_controller/nav_2d_utils/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,10 @@ add_library(tf_help SHARED
4747
src/tf_help.cpp
4848
)
4949

50+
target_link_libraries(tf_help
51+
conversions
52+
)
53+
5054
ament_target_dependencies(tf_help
5155
${dependencies}
5256
)

nav2_map_server/src/map_io.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ char * dirname(char * path)
7878
/* This assignment is ill-designed but the XPG specs require to
7979
return a string containing "." in any case no directory part is
8080
found and so a static and constant string is required. */
81-
path = reinterpret_cast<char *>(dot);
81+
path = const_cast<char *>(&dot[0]);
8282
}
8383

8484
return path;

0 commit comments

Comments
 (0)