4 #include "std_msgs/Int32.h" 5 #include "std_msgs/String.h" 10 #include "boost/foreach.hpp" 11 #include <gtest/gtest.h> 19 str.data = std::string(
"foo");
30 const char*
bag_filename =
"/tmp/rosbag_storage_create_and_iterate_bag.bag";
32 TEST(rosbag_storage, iterator_copy_constructor)
39 EXPECT_EQ(42, it0->instantiate<std_msgs::Int32>()->data);
42 EXPECT_EQ(42, it1->instantiate<std_msgs::Int32>()->data);
45 EXPECT_EQ(42, it0->instantiate<std_msgs::Int32>()->data);
48 TEST(rosbag_storage, iterator_copy_assignment)
55 EXPECT_EQ(42, it0->instantiate<std_msgs::Int32>()->data);
59 EXPECT_EQ(42, it1->instantiate<std_msgs::Int32>()->data);
62 EXPECT_EQ(42, it0->instantiate<std_msgs::Int32>()->data);
65 TEST(rosbag_storage, iterate_bag)
70 std::vector<std::string> topics;
71 topics.push_back(std::string(
"chatter"));
72 topics.push_back(std::string(
"numbers"));
78 std_msgs::String::ConstPtr s = m.
instantiate<std_msgs::String>();
81 if(s->data == std::string(
"foo")) {
82 printf(
"Successfully checked string foo\n");
86 printf(
"Failed checked string foo\n");
91 std_msgs::Int32::ConstPtr i = m.
instantiate<std_msgs::Int32>();
95 printf(
"Successfully checked value 42\n");
99 printf(
"Failed checked value 42.\n");
108 int main(
int argc,
char **argv) {
112 testing::InitGoogleTest(&argc, argv);
113 return RUN_ALL_TESTS();
void create_test_bag(const std::string &filename)
void open(std::string const &filename, uint32_t mode=bagmode::Read)
const char * bag_filename
int main(int argc, char **argv)
boost::shared_ptr< T > instantiate() const
TEST(rosbag_storage, iterator_copy_constructor)
void write(std::string const &topic, ros::MessageEvent< T > const &event)