Skip to content

Commit 2297cd9

Browse files
committed
fix build issues on rolling
1 parent b427654 commit 2297cd9

File tree

3 files changed

+11
-1
lines changed

3 files changed

+11
-1
lines changed

CMakeLists.txt

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,16 +27,21 @@ set(ament_dependencies
2727
"ffmpeg_image_transport_msgs"
2828
"rclcpp"
2929
"rosbag2_cpp"
30+
"rosbag2_storage"
3031
"sensor_msgs")
3132

3233
foreach(pkg ${ament_dependencies})
3334
find_package(${pkg} REQUIRED)
3435
endforeach()
3536

36-
if(${cv_bridge_VERSION} GREATER "3.3.0")
37+
if(${cv_bridge_VERSION} VERSION_GREATER "3.3.0")
3738
add_definitions(-DUSE_CV_BRIDGE_HPP)
3839
endif()
3940

41+
if(${rosbag2_storage_VERSION} VERSION_GREATER_EQUAL "0.26.1")
42+
add_definitions(-DUSE_ROSBAG2_STORAGE_RECV_TIME)
43+
endif()
44+
4045

4146
#
4247
# -------- bag_to_file

include/ffmpeg_image_transport_tools/bag_processor.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,11 @@ class BagProcessor
7474
rclcpp::SerializedMessage serialized_msg(*msg->serialized_data);
7575
typename T::SharedPtr m(new T());
7676
serialization_.deserialize_message(&serialized_msg, m.get());
77+
#ifdef USE_ROSBAG2_STORAGE_RECV_TIME
78+
const auto t = Time(msg->recv_timestamp).nanoseconds();
79+
#else
7780
const auto t = Time(msg->time_stamp).nanoseconds();
81+
#endif
7882
if (t > end_time_) {
7983
break;
8084
}

package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
<depend>ffmpeg_image_transport</depend>
2121
<depend>ffmpeg_image_transport_msgs</depend>
2222
<depend>rosbag2_cpp</depend>
23+
<depend>rosbag2_storage</depend>
2324
<depend>sensor_msgs</depend>
2425

2526

0 commit comments

Comments
 (0)