00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "rosbag/bag.h"
00029 #include "rosbag/chunked_file.h"
00030 #include "rosbag/view.h"
00031
00032 #include <sys/stat.h>
00033 #include <sys/types.h>
00034
00035 #include <iostream>
00036 #include <set>
00037
00038 #include <boost/assign/list_of.hpp>
00039 #include <boost/foreach.hpp>
00040
00041 #include <gtest/gtest.h>
00042
00043 #include "std_msgs/String.h"
00044 #include "std_msgs/Int32.h"
00045
00046 #define foreach BOOST_FOREACH
00047
00048 class BagTest : public testing::Test
00049 {
00050 protected:
00051 std_msgs::String foo_, bar_;
00052 std_msgs::Int32 i_;
00053
00054 virtual void SetUp() {
00055 foo_.data = std::string("foo");
00056 bar_.data = std::string("bar");
00057 i_.data = 42;
00058 }
00059
00060 void dumpContents(std::string const& filename) {
00061 rosbag::Bag b;
00062 b.open(filename, rosbag::bagmode::Read);
00063 dumpContents(b);
00064 b.close();
00065 }
00066
00067 void dumpContents(rosbag::Bag& b) {
00068 rosbag::View view(b);
00069 foreach(rosbag::MessageInstance m, view)
00070 std::cout << m.getTime() << ": [" << m.getTopic() << "]" << std::endl;
00071 }
00072
00073 void checkContents(std::string const& filename) {
00074 rosbag::Bag b;
00075 b.open(filename, rosbag::bagmode::Read);
00076
00077 int message_count = 0;
00078
00079 rosbag::View view(b);
00080 foreach(rosbag::MessageInstance m, view) {
00081 std_msgs::String::ConstPtr s = m.instantiate<std_msgs::String>();
00082 if (s != NULL) {
00083 ASSERT_EQ(s->data, foo_.data);
00084 message_count++;
00085 }
00086 std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
00087 if (i != NULL) {
00088 ASSERT_EQ(i->data, i_.data);
00089 message_count++;
00090 }
00091 }
00092 ASSERT_EQ(message_count, 2);
00093
00094 b.close();
00095 }
00096 };
00097
00098 TEST_F(BagTest, write_then_read_works) {
00099 std::string filename("/tmp/write_then_read_works.bag");
00100
00101 rosbag::Bag b1;
00102 b1.open(filename, rosbag::bagmode::Write);
00103 b1.write("chatter", ros::Time::now(), foo_);
00104 b1.write("numbers", ros::Time::now(), i_);
00105 b1.close();
00106
00107 checkContents(filename);
00108 }
00109
00110 TEST_F(BagTest, append_works) {
00111 std::string filename("/tmp/append_works.bag");
00112
00113 rosbag::Bag b1;
00114 b1.open(filename, rosbag::bagmode::Write);
00115 b1.write("chatter", ros::Time::now(), foo_);
00116 b1.close();
00117
00118 rosbag::Bag b2;
00119 b2.open(filename, rosbag::bagmode::Append);
00120 b2.write("numbers", ros::Time::now(), i_);
00121 b2.close();
00122
00123 checkContents(filename);
00124 }
00125
00126 TEST_F(BagTest, different_writes) {
00127 std::string filename("/tmp/different_writes.bag");
00128
00129 rosbag::Bag b1;
00130 b1.open(filename, rosbag::bagmode::Write | rosbag::bagmode::Read);
00131
00132 std_msgs::String msg1;
00133 std_msgs::String::Ptr msg2 = boost::shared_ptr<std_msgs::String>(new std_msgs::String);
00134 std_msgs::String::ConstPtr msg3 = boost::shared_ptr<std_msgs::String const>(new std_msgs::String);
00135
00136 rosbag::View view;
00137 view.addQuery(b1);
00138
00139 b1.write("t1", ros::Time::now(), msg1);
00140 b1.write("t2", ros::Time::now(), msg2);
00141 b1.write("t3", ros::Time::now(), msg3);
00142 b1.write("t4", ros::Time::now(), *view.begin());
00143
00144 ASSERT_EQ(view.size(), (uint32_t)(4));
00145
00146 b1.close();
00147 }
00148
00149 TEST_F(BagTest, reopen_works) {
00150 rosbag::Bag b;
00151
00152 std::string filename1("/tmp/reopen_works1.bag");
00153 b.open(filename1, rosbag::bagmode::Write);
00154 b.write("chatter", ros::Time::now(), foo_);
00155 b.write("numbers", ros::Time::now(), i_);
00156 b.close();
00157
00158 std::string filename2("/tmp/reopen_works1.bag");
00159 b.open(filename2, rosbag::bagmode::Write);
00160 b.write("chatter", ros::Time::now(), foo_);
00161 b.write("numbers", ros::Time::now(), i_);
00162 b.close();
00163
00164 checkContents(filename1);
00165 checkContents(filename2);
00166 }
00167
00168 TEST_F(BagTest, bag_not_open_fails) {
00169 rosbag::Bag b;
00170 try
00171 {
00172 b.write("/test", ros::Time::now(), foo_);
00173 FAIL();
00174 }
00175 catch (rosbag::BagIOException ex) {
00176 SUCCEED();
00177 }
00178 }
00179
00180 TEST(rosbag, simple_write_and_read_works) {
00181 rosbag::Bag b1("/tmp/simple_write_and_read_works.bag", rosbag::bagmode::Write);
00182
00183 std_msgs::String str;
00184 str.data = std::string("foo");
00185
00186 std_msgs::Int32 i;
00187 i.data = 42;
00188
00189 b1.write("chatter", ros::Time::now(), str);
00190 b1.write("numbers", ros::Time::now(), i);
00191
00192 b1.close();
00193
00194 rosbag::Bag b2("/tmp/simple_write_and_read_works.bag", rosbag::bagmode::Read);
00195
00196 std::vector<std::string> topics;
00197 topics.push_back(std::string("chatter"));
00198 topics.push_back(std::string("numbers"));
00199
00200 int count = 0;
00201 rosbag::View view(b2, rosbag::TopicQuery(topics));
00202 foreach(rosbag::MessageInstance const m, view) {
00203 std_msgs::String::ConstPtr s = m.instantiate<std_msgs::String>();
00204 if (s != NULL)
00205 {
00206 count++;
00207 ASSERT_EQ(s->data, std::string("foo"));
00208 }
00209
00210 std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
00211 if (i != NULL)
00212 {
00213 count++;
00214 ASSERT_EQ(i->data, 42);
00215 }
00216 }
00217
00218 ASSERT_EQ(count,2);
00219
00220 b2.close();
00221 }
00222
00223 TEST(rosbag, append_indexed_1_2_fails) {
00224 try{
00225 rosbag::Bag b("test/test_indexed_1.2.bag", rosbag::bagmode::Append);
00226
00227 FAIL();
00228 }
00229 catch (rosbag::BagException ex) {
00230 SUCCEED();
00231 }
00232 }
00233
00234 TEST(rosbag, read_indexed_1_2_succeeds) {
00235 rosbag::Bag b("test/test_indexed_1.2.bag", rosbag::bagmode::Read);
00236 rosbag::View view(b);
00237
00238 int32_t i = 0;
00239
00240 foreach(rosbag::MessageInstance const m, view) {
00241 std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
00242 if (imsg != NULL)
00243 ASSERT_EQ(imsg->data, i++);
00244 }
00245
00246 b.close();
00247 }
00248
00249
00250 TEST(rosbag, write_then_read_without_read_mode_fails) {
00251 rosbag::Bag b("/tmp/write_then_read_without_read_mode_fails.bag", rosbag::bagmode::Write);
00252 std_msgs::String str;
00253 str.data = std::string("foo");
00254 b.write("chatter", ros::Time::now(), str);
00255
00256 try
00257 {
00258 rosbag::View view(b);
00259 foreach(rosbag::MessageInstance const m, view) {
00260 std_msgs::String::ConstPtr s = m.instantiate<std_msgs::String>();
00261 if (s != NULL)
00262 ASSERT_EQ(s->data, std::string("foo"));
00263 }
00264 FAIL();
00265 }
00266 catch (rosbag::BagException ex) {
00267 SUCCEED();
00268 }
00269 }
00270
00271 TEST_F(BagTest, read_then_write_without_write_mode_fails) {
00272 rosbag::Bag b1("/tmp/read_then_write_without_write_mode_fails.bag", rosbag::bagmode::Write);
00273 b1.write("chatter", ros::Time::now(), foo_);
00274 b1.close();
00275
00276 rosbag::Bag b2("/tmp/read_then_write_without_write_mode_fails.bag", rosbag::bagmode::Read);
00277 try
00278 {
00279 b2.write("chatter", ros::Time::now(), foo_);
00280 FAIL();
00281 }
00282 catch (rosbag::BagException ex) {
00283 SUCCEED();
00284 }
00285 }
00286
00287 TEST(rosbag, time_query_works) {
00288 rosbag::Bag outbag;
00289 outbag.open("/tmp/time_query_works.bag", rosbag::bagmode::Write);
00290
00291 std_msgs::Int32 imsg;
00292
00293 for (int i = 0; i < 1000; i++) {
00294 imsg.data = i;
00295 switch (rand() % 5) {
00296 case 0: outbag.write("t0", ros::Time(i, 1), imsg); break;
00297 case 1: outbag.write("t1", ros::Time(i, 1), imsg); break;
00298 case 2: outbag.write("t2", ros::Time(i, 1), imsg); break;
00299 case 3: outbag.write("t2", ros::Time(i, 1), imsg); break;
00300 case 4: outbag.write("t4", ros::Time(i, 1), imsg); break;
00301 }
00302 }
00303 outbag.close();
00304
00305 rosbag::Bag bag;
00306 bag.open("/tmp/time_query_works.bag", rosbag::bagmode::Read);
00307
00308 int i = 23;
00309
00310 rosbag::View view(bag, ros::Time(23, 1), ros::Time(782, 1));
00311 foreach(rosbag::MessageInstance const m, view) {
00312 std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
00313 if (imsg != NULL) {
00314 ASSERT_EQ(imsg->data, i++);
00315 ASSERT_TRUE(m.getTime() < ros::Time(783,0));
00316 }
00317 }
00318
00319 bag.close();
00320 }
00321
00322 TEST(rosbag, topic_query_works) {
00323 rosbag::Bag outbag;
00324 outbag.open("/tmp/topic_query_works.bag", rosbag::bagmode::Write);
00325
00326 std_msgs::Int32 imsg;
00327
00328 int j0 = 0;
00329 int j1 = 0;
00330
00331 for (int i = 0; i < 10; i++) {
00332 switch (rand() % 5) {
00333 case 0: imsg.data = j0++; outbag.write("t0", ros::Time(i, 1), imsg); break;
00334 case 1: imsg.data = j0++; outbag.write("t1", ros::Time(i, 1), imsg); break;
00335 case 2: imsg.data = j1++; outbag.write("t2", ros::Time(i, 1), imsg); break;
00336 case 3: imsg.data = j1++; outbag.write("t3", ros::Time(i, 1), imsg); break;
00337 case 4: imsg.data = j1++; outbag.write("t4", ros::Time(i, 1), imsg); break;
00338 }
00339 }
00340 outbag.close();
00341
00342 rosbag::Bag bag;
00343 bag.open("/tmp/topic_query_works.bag", rosbag::bagmode::Read);
00344
00345 std::vector<std::string> t = boost::assign::list_of("t0")("t1");
00346
00347 int i = 0;
00348
00349 rosbag::View view(bag, rosbag::TopicQuery(t));
00350 foreach(rosbag::MessageInstance const m, view) {
00351 std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
00352 if (imsg != NULL)
00353 ASSERT_EQ(imsg->data, i++);
00354 }
00355
00356 bag.close();
00357 }
00358
00359
00360 TEST(rosbag, bad_topic_query_works) {
00361 rosbag::Bag outbag;
00362 outbag.open("/tmp/bad_topic_query_works.bag", rosbag::bagmode::Write);
00363
00364 std_msgs::Int32 imsg;
00365
00366 for (int i = 0; i < 10; i++) {
00367 outbag.write("t0", ros::Time(i, 1), imsg);
00368 }
00369 outbag.close();
00370
00371 rosbag::Bag bag;
00372 bag.open("/tmp/bad_topic_query_works.bag", rosbag::bagmode::Read);
00373
00374 std::vector<std::string> t = boost::assign::list_of("t1");
00375
00376 rosbag::View view(bag, rosbag::TopicQuery(t));
00377 foreach(rosbag::MessageInstance const m, view) {
00378 FAIL();
00379 }
00380
00381 bag.close();
00382 }
00383
00384
00385
00386
00387
00388
00389
00390
00391
00392
00393
00394
00395
00396
00397 TEST(rosbag, multiple_bag_works) {
00398 rosbag::Bag outbag1("/tmp/multiple_bag_works1.bag", rosbag::bagmode::Write);
00399 rosbag::Bag outbag2("/tmp/multiple_bag_works2.bag", rosbag::bagmode::Write);
00400
00401 std_msgs::Int32 imsg;
00402 for (int i = 0; i < 1000; i++) {
00403 imsg.data = i;
00404 switch (rand() % 5) {
00405 case 0: outbag1.write("t0", ros::Time(0,i+1), imsg); break;
00406 case 1: outbag1.write("t1", ros::Time(0,i+1), imsg); break;
00407 case 2: outbag1.write("t2", ros::Time(0,i+1), imsg); break;
00408 case 3: outbag2.write("t0", ros::Time(0,i+1), imsg); break;
00409 case 4: outbag2.write("t1", ros::Time(0,i+1), imsg); break;
00410 }
00411 }
00412
00413 outbag1.close();
00414 outbag2.close();
00415
00416 rosbag::Bag bag1("/tmp/multiple_bag_works1.bag", rosbag::bagmode::Read);
00417 rosbag::Bag bag2("/tmp/multiple_bag_works2.bag", rosbag::bagmode::Read);
00418
00419 rosbag::View view;
00420 view.addQuery(bag1);
00421 view.addQuery(bag2);
00422
00423 int i = 0;
00424
00425 foreach(rosbag::MessageInstance const m, view) {
00426 std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
00427 if (imsg != NULL)
00428 ASSERT_EQ(imsg->data, i++);
00429 }
00430
00431 bag1.close();
00432 bag2.close();
00433 }
00434
00435
00436 TEST(rosbag, overlapping_query_works) {
00437 rosbag::Bag outbag1("/tmp/overlapping_query_1.bag", rosbag::bagmode::Write);
00438 rosbag::Bag outbag2("/tmp/overlapping_query_2.bag", rosbag::bagmode::Write);
00439
00440 std_msgs::Int32 imsg;
00441 for (int i = 0; i < 1000; i++) {
00442 imsg.data = i;
00443 switch (rand() % 5) {
00444 case 0: outbag1.write("t0", ros::Time(i+1), imsg); break;
00445 case 1: outbag1.write("t1", ros::Time(i+1), imsg); break;
00446 case 2: outbag1.write("t2", ros::Time(i+1), imsg); break;
00447 case 3: outbag2.write("t0", ros::Time(i+1), imsg); break;
00448 case 4: outbag2.write("t1", ros::Time(i+1), imsg); break;
00449 }
00450 }
00451
00452 outbag1.close();
00453 outbag2.close();
00454
00455 rosbag::Bag bag1("/tmp/overlapping_query_1.bag", rosbag::bagmode::Read);
00456 rosbag::Bag bag2("/tmp/overlapping_query_2.bag", rosbag::bagmode::Read);
00457
00458 rosbag::View view1(false);
00459 view1.addQuery(bag1, ros::Time(1), ros::Time(750));
00460 view1.addQuery(bag1, ros::Time(251), ros::Time(1002));
00461 view1.addQuery(bag2, ros::Time(1), ros::Time(750));
00462 view1.addQuery(bag2, ros::Time(251), ros::Time(1002));
00463
00464 rosbag::View view2(true);
00465 view2.addQuery(bag1, ros::Time(1), ros::Time(750));
00466 view2.addQuery(bag1, ros::Time(251), ros::Time(1002));
00467 view2.addQuery(bag2, ros::Time(1), ros::Time(750));
00468 view2.addQuery(bag2, ros::Time(251), ros::Time(1002));
00469
00470
00471 int i = 0;
00472 int j = 0;
00473
00474 foreach(rosbag::MessageInstance const m, view1) {
00475 std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
00476 if (imsg != NULL)
00477 ASSERT_EQ(imsg->data, i);
00478 if (i >= 250 && i < 750)
00479 {
00480 i += (j++ % 2);
00481 } else {
00482 i++;
00483 }
00484 }
00485
00486 i = 0;
00487
00488 foreach(rosbag::MessageInstance const m, view2) {
00489 std_msgs::Int32::ConstPtr imsg = m.instantiate<std_msgs::Int32>();
00490 if (imsg != NULL)
00491 ASSERT_EQ(imsg->data, i++);
00492 }
00493
00494 bag1.close();
00495 bag2.close();
00496 }
00497
00498
00499 TEST(rosbag, no_min_time) {
00500 rosbag::Bag outbag("/tmp/no_min_time.bag", rosbag::bagmode::Write);
00501
00502 std_msgs::Int32 imsg;
00503 try
00504 {
00505 outbag.write("t0", ros::Time(0,0), imsg);
00506 FAIL();
00507 } catch (rosbag::BagException& e)
00508 {
00509 SUCCEED();
00510 }
00511
00512 outbag.close();
00513 }
00514
00515 TEST(rosbag, modify_view_works) {
00516 rosbag::Bag outbag;
00517 outbag.open("/tmp/modify_view_works.bag", rosbag::bagmode::Write);
00518
00519 std_msgs::Int32 imsg;
00520
00521 int j0 = 0;
00522 int j1 = 1;
00523
00524
00525 for (int i = 0; i < 100; i++) {
00526 imsg.data = j0;
00527 j0 += 2;
00528 outbag.write("t0", ros::Time(2 * i + 1, 0), imsg);
00529
00530 imsg.data = j1;
00531 j1 += 2;
00532 outbag.write("t1", ros::Time(2 * i + 2, 0), imsg);
00533 }
00534 outbag.close();
00535
00536 rosbag::Bag bag;
00537 bag.open("/tmp/modify_view_works.bag", rosbag::bagmode::Read);
00538
00539 std::vector<std::string> t0 = boost::assign::list_of("t0");
00540 std::vector<std::string> t1 = boost::assign::list_of("t1");
00541
00542
00543 j0 = 0;
00544 j1 = 101;
00545
00546 rosbag::View view(bag, rosbag::TopicQuery(t0));
00547
00548 rosbag::View::iterator iter = view.begin();
00549
00550 for (int i = 0; i < 50; i++) {
00551 std_msgs::Int32::ConstPtr imsg = iter->instantiate<std_msgs::Int32>();
00552 if (imsg != NULL) {
00553 ASSERT_EQ(imsg->data, j0);
00554 j0 += 2;
00555 }
00556 iter++;
00557 }
00558
00559
00560 view.addQuery(bag, rosbag::TopicQuery(t1));
00561
00562 for (int i = 0; i < 50; i++) {
00563 std_msgs::Int32::ConstPtr imsg = iter->instantiate<std_msgs::Int32>();
00564 if (imsg != NULL) {
00565 ASSERT_EQ(imsg->data, j0);
00566 j0 += 2;
00567 }
00568 iter++;
00569
00570 imsg = iter->instantiate<std_msgs::Int32>();
00571 if (imsg != NULL) {
00572 ASSERT_EQ(imsg->data, j1);
00573 j1 += 2;
00574 }
00575 iter++;
00576 }
00577
00578 bag.close();
00579 }
00580
00581 TEST(rosbag, modify_bag_works) {
00582 rosbag::Bag rwbag("/tmp/modify_bag_works.bag", rosbag::bagmode::Write | rosbag::bagmode::Read);
00583 rwbag.setChunkThreshold(1);
00584
00585 std::vector<std::string> t0 = boost::assign::list_of("t0");
00586
00587 rosbag::View view(rwbag, rosbag::TopicQuery(t0));
00588
00589 std_msgs::Int32 omsg;
00590
00591
00592 omsg.data = 5;
00593 rwbag.write("t0", ros::Time(5 + 1, 0), omsg);
00594
00595
00596 rosbag::View::iterator iter1 = view.begin();
00597 std_msgs::Int32::ConstPtr imsg = iter1->instantiate<std_msgs::Int32>();
00598 ASSERT_EQ(imsg->data, 5);
00599
00600 for (int i = 0; i < 5; i++) {
00601 omsg.data = i;
00602 rwbag.write("t0", ros::Time(i + 1, 0), omsg);
00603 }
00604
00605
00606 rosbag::View::iterator iter2 = view.begin();
00607 imsg = iter2->instantiate<std_msgs::Int32>();
00608 ASSERT_EQ(imsg->data, 0);
00609
00610
00611 iter2++;
00612
00613
00614 for (int i = 6; i < 10; i++) {
00615 omsg.data = i;
00616 rwbag.write("t0", ros::Time(i + 1, 0), omsg);
00617 }
00618
00619
00620 for (int i = 1; i < 10; i++) {
00621 imsg = iter2->instantiate<std_msgs::Int32>();
00622 ASSERT_EQ(imsg->data, i);
00623 iter2++;
00624 }
00625
00626
00627 for (int i = 5; i < 10; i++) {
00628 imsg = iter1->instantiate<std_msgs::Int32>();
00629 ASSERT_EQ(imsg->data, i);
00630 iter1++;
00631 }
00632
00633 rwbag.close();
00634
00635 rosbag::Bag rwbag2("/tmp/modify_bag_works.bag", rosbag::bagmode::Read);
00636
00637 rosbag::View view2(rwbag2, rosbag::TopicQuery(t0));
00638
00639 rosbag::View::iterator iter3 = view2.begin();
00640 imsg = iter3->instantiate<std_msgs::Int32>();
00641
00642 for (int i = 0; i < 10; i++) {
00643 imsg = iter3->instantiate<std_msgs::Int32>();
00644 ASSERT_EQ(imsg->data, i);
00645 iter3++;
00646 }
00647 }
00648
00649 int main(int argc, char **argv) {
00650 ros::init(argc, argv, "test_bag");
00651 ros::Time::init();
00652
00653 testing::InitGoogleTest(&argc, argv);
00654 return RUN_ALL_TESTS();
00655 }