Skip to content

Commit

Permalink
Added tests for Bag::swap
Browse files Browse the repository at this point in the history
  • Loading branch information
racko committed Mar 6, 2017
1 parent 761bfb7 commit 878187a
Show file tree
Hide file tree
Showing 2 changed files with 105 additions and 0 deletions.
4 changes: 4 additions & 0 deletions test/test_rosbag_storage/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,4 +15,8 @@ if(CATKIN_ENABLE_TESTING)
if(TARGET create_and_iterate_bag)
target_link_libraries(create_and_iterate_bag ${catkin_LIBRARIES})
endif()
catkin_add_gtest(swap_bags src/swap_bags.cpp)
if(TARGET swap_bags)
target_link_libraries(swap_bags ${catkin_LIBRARIES})
endif()
endif()
101 changes: 101 additions & 0 deletions test/test_rosbag_storage/src/swap_bags.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
#include "ros/time.h"
#include "rosbag/bag.h"
#include "rosbag/view.h"
#include "std_msgs/Int32.h"

#include "boost/foreach.hpp"
#include <gtest/gtest.h>

void writeBags(rosbag::CompressionType a, rosbag::CompressionType b) {
using std::swap;
rosbag::Bag bag1("/tmp/swap1.bag", rosbag::bagmode::Write);
rosbag::Bag bag2("/tmp/swap2.bag", rosbag::bagmode::Write);

// In the end "/tmp/swap1.bag" should have CompressionType a and contain two messages of value a.
// "/tmp/swap2.bag" should have CompressionType b and contain two messages of value b.
// We use these pointers to track the bags accordingly.

rosbag::Bag* a_bag = &bag1;
rosbag::Bag* b_bag = &bag2;

std_msgs::Int32 a_msg, b_msg;
a_msg.data = a;
b_msg.data = b;

swap(bag1, bag2);
swap(a_bag, b_bag);

a_bag->setCompression(a);
b_bag->setCompression(b);

swap(bag1, bag2);
swap(a_bag, b_bag);

a_bag->write("/data", ros::Time::now(), a_msg);
b_bag->write("/data", ros::Time::now(), b_msg);

swap(bag1, bag2);
swap(a_bag, b_bag);

a_bag->write("/data", ros::Time::now(), a_msg);
b_bag->write("/data", ros::Time::now(), b_msg);

swap(bag1, bag2);

bag1.close();
bag2.close();

swap(bag1, bag2);
}

void readBags(rosbag::CompressionType a, rosbag::CompressionType b) {
using std::swap;
rosbag::Bag bag1("/tmp/swap1.bag", rosbag::bagmode::Read);
rosbag::Bag bag2("/tmp/swap2.bag", rosbag::bagmode::Read);

rosbag::Bag* a_bag = &bag1;
rosbag::Bag* b_bag = &bag2;

swap(bag1, bag2);
swap(a_bag, b_bag);

// only valid when writing
//EXPECT_EQ(a_bag->getCompression(), a);
//EXPECT_EQ(b_bag->getCompression(), b);

std::vector<std::string> topics;
topics.push_back("data");

rosbag::View a_view(*a_bag, rosbag::TopicQuery(topics));
rosbag::View b_view(*b_bag, rosbag::TopicQuery(topics));

BOOST_FOREACH(rosbag::MessageInstance const m, a_view)
{
std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
ASSERT_TRUE(i);
EXPECT_EQ(i->data, a);
}
BOOST_FOREACH(rosbag::MessageInstance const m, b_view)
{
std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
ASSERT_TRUE(i);
EXPECT_EQ(i->data, b);
}
}

TEST(rosbag_storage, swap_bags)
{
for (int i = 0; i < 3; ++i) {
for (int j = 0; j < 3; ++j) {
writeBags(rosbag::CompressionType(i), rosbag::CompressionType(j));
readBags(rosbag::CompressionType(i), rosbag::CompressionType(j));
}
}
}

int main(int argc, char **argv) {
ros::Time::init();

testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

0 comments on commit 878187a

Please sign in to comment.