create_and_iterate_bag.cpp
Go to the documentation of this file.
00001 #include "ros/time.h"
00002 #include "rosbag/bag.h"
00003 #include "rosbag/view.h"
00004 #include "std_msgs/Int32.h"
00005 #include "std_msgs/String.h"
00006 
00007 #include <string>
00008 #include <vector>
00009 
00010 #include "boost/foreach.hpp"
00011 #include <gtest/gtest.h>
00012 
00013 
00014 TEST(rosbag_storage, create_and_iterate_bag)
00015 {
00016   const char* bag_filename = "/tmp/rosbag_storage_create_and_iterate_bag.bag";
00017   {
00018     rosbag::Bag bag;
00019     bag.open(bag_filename, rosbag::bagmode::Write);
00020 
00021     std_msgs::String str;
00022     str.data = std::string("foo");
00023   
00024     std_msgs::Int32 i;
00025     i.data = 42;
00026   
00027     bag.write("chatter", ros::Time::now(), str);
00028     bag.write("numbers", ros::Time::now(), i);
00029 
00030     bag.close();
00031   }
00032 
00033   {
00034     rosbag::Bag bag;
00035     bag.open(bag_filename, rosbag::bagmode::Read);
00036 
00037     std::vector<std::string> topics;
00038     topics.push_back(std::string("chatter"));
00039     topics.push_back(std::string("numbers"));
00040 
00041     rosbag::View view(bag, rosbag::TopicQuery(topics));
00042 
00043     BOOST_FOREACH(rosbag::MessageInstance const m, view)
00044     {
00045       std_msgs::String::ConstPtr s = m.instantiate<std_msgs::String>();
00046       if (s != NULL)
00047       {
00048         if(s->data == std::string("foo")) { 
00049           printf("Successfully checked string foo\n");
00050         }
00051         else
00052         {
00053           printf("Failed checked string foo\n");
00054           FAIL();
00055         }
00056       }
00057 
00058       std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
00059       if (i != NULL)
00060       {
00061         if (i->data == 42) { 
00062           printf("Successfully checked value 42\n");
00063         }
00064         else
00065         {
00066           printf("Failed checked value 42.\n"); 
00067           FAIL();
00068         }
00069       }
00070     }
00071 
00072     bag.close();
00073   }
00074 }
00075 
00076 int main(int argc, char **argv) {
00077     ros::Time::init();
00078 
00079     testing::InitGoogleTest(&argc, argv);
00080     return RUN_ALL_TESTS();
00081 }


test_rosbag_storage
Author(s):
autogenerated on Fri Aug 28 2015 12:33:44