Skip to content

Commit

Permalink
add test_rosbag_storage package which simple unit test for storage API (
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas committed Oct 12, 2013
1 parent e73774f commit d6b62d3
Show file tree
Hide file tree
Showing 3 changed files with 116 additions and 0 deletions.
18 changes: 18 additions & 0 deletions test/test_rosbag_storage/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
cmake_minimum_required(VERSION 2.8.3)

project(test_rosbag_storage)

find_package(catkin REQUIRED COMPONENTS rosbag_storage std_msgs)

find_package(Boost REQUIRED)

catkin_package()

if(CATKIN_ENABLE_TESTING)
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})

catkin_add_gtest(create_and_iterate_bag src/create_and_iterate_bag.cpp)
if(TARGET create_and_iterate_bag)
target_link_libraries(create_and_iterate_bag ${catkin_LIBRARIES})
endif()
endif()
17 changes: 17 additions & 0 deletions test/test_rosbag_storage/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<package>
<name>test_rosbag_storage</name>
<version>1.9.50</version>
<description>
A package containing the unit tests for rosbag_storage.
</description>
<maintainer email="dthomas@osrfoundation.org">Dirk Thomas</maintainer>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>

<build_depend>rosbag_storage</build_depend>
<build_depend>std_msgs</build_depend>

<run_depend>rosbag_storage</run_depend>
<run_depend>std_msgs</run_depend>
</package>
81 changes: 81 additions & 0 deletions test/test_rosbag_storage/src/create_and_iterate_bag.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
#include "ros/time.h"
#include "rosbag/bag.h"
#include "rosbag/view.h"
#include "std_msgs/Int32.h"
#include "std_msgs/String.h"

#include <string>
#include <vector>

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


TEST(rosbag_storage, create_and_iterate_bag)
{
const char* bag_filename = "/tmp/rosbag_storage_create_and_iterate_bag.bag";
{
rosbag::Bag bag;
bag.open(bag_filename, rosbag::bagmode::Write);

std_msgs::String str;
str.data = std::string("foo");

std_msgs::Int32 i;
i.data = 42;

bag.write("chatter", ros::Time::now(), str);
bag.write("numbers", ros::Time::now(), i);

bag.close();
}

{
rosbag::Bag bag;
bag.open(bag_filename, rosbag::bagmode::Read);

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

rosbag::View view(bag, rosbag::TopicQuery(topics));

BOOST_FOREACH(rosbag::MessageInstance const m, view)
{
std_msgs::String::ConstPtr s = m.instantiate<std_msgs::String>();
if (s != NULL)
{
if(s->data == std::string("foo")) {
printf("Successfully checked string foo\n");
}
else
{
printf("Failed checked string foo\n");
FAIL();
}
}

std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
if (i != NULL)
{
if (i->data == 42) {
printf("Successfully checked value 42\n");
}
else
{
printf("Failed checked value 42.\n");
FAIL();
}
}
}

bag.close();
}
}

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

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

0 comments on commit d6b62d3

Please sign in to comment.