swap_bags.cpp
Go to the documentation of this file.
1 #include "ros/time.h"
2 #include "rosbag/bag.h"
3 #include "rosbag/view.h"
4 #include "std_msgs/Int32.h"
5 
6 #include "boost/foreach.hpp"
7 #include <gtest/gtest.h>
8 
10  using std::swap;
11  rosbag::Bag bag1("/tmp/swap1.bag", rosbag::bagmode::Write);
12  rosbag::Bag bag2("/tmp/swap2.bag", rosbag::bagmode::Write);
13 
14  // In the end "/tmp/swap1.bag" should have CompressionType a and contain two messages of value a.
15  // "/tmp/swap2.bag" should have CompressionType b and contain two messages of value b.
16  // We use these pointers to track the bags accordingly.
17 
18  rosbag::Bag* a_bag = &bag1;
19  rosbag::Bag* b_bag = &bag2;
20 
21  std_msgs::Int32 a_msg, b_msg;
22  a_msg.data = a;
23  b_msg.data = b;
24 
25  swap(bag1, bag2);
26  swap(a_bag, b_bag);
27 
28  a_bag->setCompression(a);
29  b_bag->setCompression(b);
30 
31  swap(bag1, bag2);
32  swap(a_bag, b_bag);
33 
34  a_bag->write("/data", ros::Time::now(), a_msg);
35  b_bag->write("/data", ros::Time::now(), b_msg);
36 
37  swap(bag1, bag2);
38  swap(a_bag, b_bag);
39 
40  a_bag->write("/data", ros::Time::now(), a_msg);
41  b_bag->write("/data", ros::Time::now(), b_msg);
42 
43  swap(bag1, bag2);
44 
45  bag1.close();
46  bag2.close();
47 
48  swap(bag1, bag2);
49 }
50 
52  using std::swap;
53  rosbag::Bag bag1("/tmp/swap1.bag", rosbag::bagmode::Read);
54  rosbag::Bag bag2("/tmp/swap2.bag", rosbag::bagmode::Read);
55 
56  rosbag::Bag* a_bag = &bag1;
57  rosbag::Bag* b_bag = &bag2;
58 
59  swap(bag1, bag2);
60  swap(a_bag, b_bag);
61 
62  // only valid when writing
63  //EXPECT_EQ(a_bag->getCompression(), a);
64  //EXPECT_EQ(b_bag->getCompression(), b);
65 
66  std::vector<std::string> topics;
67  topics.push_back("data");
68 
69  rosbag::View a_view(*a_bag, rosbag::TopicQuery(topics));
70  rosbag::View b_view(*b_bag, rosbag::TopicQuery(topics));
71 
72  BOOST_FOREACH(rosbag::MessageInstance const m, a_view)
73  {
74  std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
75  ASSERT_TRUE(i);
76  EXPECT_EQ(i->data, a);
77  }
78  BOOST_FOREACH(rosbag::MessageInstance const m, b_view)
79  {
80  std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
81  ASSERT_TRUE(i);
82  EXPECT_EQ(i->data, b);
83  }
84 }
85 
86 TEST(rosbag_storage, swap_bags)
87 {
88  for (int i = 0; i < 3; ++i) {
89  for (int j = 0; j < 3; ++j) {
92  }
93  }
94 }
95 
96 int main(int argc, char **argv) {
98 
99  testing::InitGoogleTest(&argc, argv);
100  return RUN_ALL_TESTS();
101 }
void writeBags(rosbag::CompressionType a, rosbag::CompressionType b)
Definition: swap_bags.cpp:9
int main(int argc, char **argv)
Definition: swap_bags.cpp:96
void swap(Bag &a, Bag &b)
TEST(rosbag_storage, swap_bags)
Definition: swap_bags.cpp:86
void close()
static void init()
void setCompression(CompressionType compression)
boost::shared_ptr< T > instantiate() const
void readBags(rosbag::CompressionType a, rosbag::CompressionType b)
Definition: swap_bags.cpp:51
static Time now()
void write(std::string const &topic, ros::MessageEvent< T > const &event)


test_rosbag_storage
Author(s): Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:23