File tree Expand file tree Collapse file tree 4 files changed +7
-2
lines changed
nav2_dwb_controller/nav_2d_utils Expand file tree Collapse file tree 4 files changed +7
-2
lines changed Original file line number Diff line number Diff line change @@ -43,7 +43,7 @@ void RosTopicLogger::callback(
43
43
event.timestamp =
44
44
tf2_ros::toMsg (std::chrono::time_point<std::chrono::high_resolution_clock>(timestamp));
45
45
#else
46
- event.timestamp = tf2_ros::toMsg (timestamp);
46
+ event.timestamp = tf2_ros::toMsg (tf2::TimePoint ( timestamp) );
47
47
#endif
48
48
event.node_name = node.name ();
49
49
event.previous_status = toStr (prev_status, false );
Original file line number Diff line number Diff line change 19
19
<buildtool_depend >ament_cmake</buildtool_depend >
20
20
<build_depend >nav2_common</build_depend >
21
21
22
+ <depend >angles</depend >
22
23
<depend >geometry_msgs</depend >
23
24
<depend >laser_geometry</depend >
24
25
<depend >map_msgs</depend >
Original file line number Diff line number Diff line change @@ -47,6 +47,10 @@ add_library(tf_help SHARED
47
47
src/tf_help.cpp
48
48
)
49
49
50
+ target_link_libraries (tf_help
51
+ conversions
52
+ )
53
+
50
54
ament_target_dependencies(tf_help
51
55
${dependencies}
52
56
)
Original file line number Diff line number Diff line change @@ -78,7 +78,7 @@ char * dirname(char * path)
78
78
/* This assignment is ill-designed but the XPG specs require to
79
79
return a string containing "." in any case no directory part is
80
80
found and so a static and constant string is required. */
81
- path = reinterpret_cast <char *>(dot);
81
+ path = const_cast <char *>(& dot[ 0 ] );
82
82
}
83
83
84
84
return path;
You can’t perform that action at this time.
0 commit comments