Skip to content

Commit dbbc4b2

Browse files
committed
fix tests on humble
1 parent aef2e97 commit dbbc4b2

File tree

4 files changed

+10
-8
lines changed

4 files changed

+10
-8
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ find_package(rosbag2_storage REQUIRED)
3838
find_package(sensor_msgs REQUIRED)
3939
find_package(OpenCV REQUIRED core imgproc)
4040

41-
if(${rosbag2_cpp_VERSION_MAJOR} GREATER 0 OR ${rosbag2_cpp_VERSION_MINOR} GREATER 9)
41+
if(${rosbag2_cpp_VERSION} VERSION_GREATER_EQUAL "0.26.0")
4242
add_definitions(-DUSE_NEW_ROSBAG_WRITE_INTERFACE)
4343
endif()
4444

src/compress_bag.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -407,7 +407,8 @@ class Compressor : public ffmpeg_image_transport_tools::MessageProcessor<Image>
407407
#ifdef USE_NEW_ROSBAG_WRITE_INTERFACE
408408
writer_->write(smsg, topic, topicType, t_recv, t_send);
409409
#else
410-
writer_->write(*smsg, topic, topicType, t_recv);
410+
(void)t_send;
411+
writer_->write(smsg, topic, topicType, rclcpp::Time(t_recv));
411412
#endif
412413
num_msgs_written_++;
413414
}

src/uncompress_bag.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -251,7 +251,8 @@ class UnCompressor : public ffmpeg_image_transport_tools::MessageProcessor<FFMPE
251251
#ifdef USE_NEW_ROSBAG_WRITE_INTERFACE
252252
writer_->write(smsg, topic, topicType, t_recv, t_send);
253253
#else
254-
writer_->write(*smsg, topic, topicType, t_recv);
254+
(void)t_send;
255+
writer_->write(smsg, topic, topicType, rclcpp::Time(t_recv));
255256
#endif
256257
num_msgs_written_++;
257258
}

test/test_utils.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -73,17 +73,17 @@ void makeTestBag(
7373
writer->create_topic(meta);
7474
}
7575
for (const auto & topic : topics) {
76-
auto smsg = std::make_shared<rclcpp::SerializedMessage>();
77-
rclcpp::Serialization<Image> serialization;
7876
for (size_t i = 0; i < num_images; i++) {
77+
auto smsg = std::make_shared<rclcpp::SerializedMessage>();
78+
rclcpp::Serialization<Image> serialization;
7979
auto m = makeImageMessage(static_cast<uint8_t>(i), width, height, encoding);
80-
const rcutils_time_point_value_t t_recv = rclcpp::Time(m->header.stamp).nanoseconds() + 1;
81-
const rcutils_time_point_value_t t_send = rclcpp::Time(m->header.stamp).nanoseconds() + 2;
8280
serialization.serialize_message(m.get(), smsg.get());
81+
const rcutils_time_point_value_t t_recv = rclcpp::Time(m->header.stamp).nanoseconds() + 1;
8382
#ifdef USE_NEW_ROSBAG_WRITE_INTERFACE
83+
const rcutils_time_point_value_t t_send = rclcpp::Time(m->header.stamp).nanoseconds() + 2;
8484
writer->write(smsg, topic, topic_type, t_recv, t_send);
8585
#else
86-
writer->write(*smsg, topic, topic_type, t_recv);
86+
writer->write(smsg, topic, topic_type, rclcpp::Time(t_recv));
8787
#endif
8888
}
8989
}

0 commit comments

Comments
 (0)