4 #include "std_msgs/Int32.h" 6 #include "boost/foreach.hpp" 7 #include <gtest/gtest.h> 21 std_msgs::Int32 a_msg, b_msg;
66 std::vector<std::string> topics;
67 topics.push_back(
"data");
74 std_msgs::Int32::ConstPtr i = m.
instantiate<std_msgs::Int32>();
76 EXPECT_EQ(i->data, a);
80 std_msgs::Int32::ConstPtr i = m.
instantiate<std_msgs::Int32>();
82 EXPECT_EQ(i->data, b);
86 TEST(rosbag_storage, swap_bags)
88 for (
int i = 0; i < 3; ++i) {
89 for (
int j = 0; j < 3; ++j) {
96 int main(
int argc,
char **argv) {
99 testing::InitGoogleTest(&argc, argv);
100 return RUN_ALL_TESTS();
void writeBags(rosbag::CompressionType a, rosbag::CompressionType b)
int main(int argc, char **argv)
void swap(Bag &a, Bag &b)
TEST(rosbag_storage, swap_bags)
void setCompression(CompressionType compression)
boost::shared_ptr< T > instantiate() const
void readBags(rosbag::CompressionType a, rosbag::CompressionType b)
void write(std::string const &topic, ros::MessageEvent< T > const &event)