Skip to content

Commit

Permalink
fix build issues on rolling
Browse files Browse the repository at this point in the history
  • Loading branch information
berndpfrommer committed Apr 18, 2024
1 parent b427654 commit 2297cd9
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 1 deletion.
7 changes: 6 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,16 +27,21 @@ set(ament_dependencies
"ffmpeg_image_transport_msgs"
"rclcpp"
"rosbag2_cpp"
"rosbag2_storage"
"sensor_msgs")

foreach(pkg ${ament_dependencies})
find_package(${pkg} REQUIRED)
endforeach()

if(${cv_bridge_VERSION} GREATER "3.3.0")
if(${cv_bridge_VERSION} VERSION_GREATER "3.3.0")
add_definitions(-DUSE_CV_BRIDGE_HPP)
endif()

if(${rosbag2_storage_VERSION} VERSION_GREATER_EQUAL "0.26.1")
add_definitions(-DUSE_ROSBAG2_STORAGE_RECV_TIME)
endif()


#
# -------- bag_to_file
Expand Down
4 changes: 4 additions & 0 deletions include/ffmpeg_image_transport_tools/bag_processor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,11 @@ class BagProcessor
rclcpp::SerializedMessage serialized_msg(*msg->serialized_data);
typename T::SharedPtr m(new T());
serialization_.deserialize_message(&serialized_msg, m.get());
#ifdef USE_ROSBAG2_STORAGE_RECV_TIME
const auto t = Time(msg->recv_timestamp).nanoseconds();
#else
const auto t = Time(msg->time_stamp).nanoseconds();
#endif
if (t > end_time_) {
break;
}
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>ffmpeg_image_transport</depend>
<depend>ffmpeg_image_transport_msgs</depend>
<depend>rosbag2_cpp</depend>
<depend>rosbag2_storage</depend>
<depend>sensor_msgs</depend>


Expand Down

0 comments on commit 2297cd9

Please sign in to comment.