Skip to content

Commit

Permalink
fix rosbag::View::iterator copy assignment operator (#1017)
Browse files Browse the repository at this point in the history
* refactor test_rosbag_storage

* fix rosbag::View::iterator copy assignment operator

the compiler-generated copy assignment operator did lead to segfault and
memory leaks.
  • Loading branch information
sbarthelemy authored and dirk-thomas committed Oct 25, 2017
1 parent ac213f9 commit a95d25e
Show file tree
Hide file tree
Showing 3 changed files with 94 additions and 47 deletions.
127 changes: 80 additions & 47 deletions test/test_rosbag_storage/src/create_and_iterate_bag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,71 +10,104 @@
#include "boost/foreach.hpp"
#include <gtest/gtest.h>

void create_test_bag(const std::string &filename)
{
rosbag::Bag bag;
bag.open(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();
}

TEST(rosbag_storage, create_and_iterate_bag)
const char* bag_filename = "/tmp/rosbag_storage_create_and_iterate_bag.bag";

TEST(rosbag_storage, iterator_copy_constructor)
{
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();
}
// copy ctor
rosbag::Bag bag;
bag.open(bag_filename, rosbag::bagmode::Read);
rosbag::View view(bag, rosbag::TopicQuery("numbers"));
rosbag::View::const_iterator it0 = view.begin();
EXPECT_EQ(42, it0->instantiate<std_msgs::Int32>()->data);
rosbag::View::const_iterator it1(it0);
EXPECT_EQ(it0, it1);
EXPECT_EQ(42, it1->instantiate<std_msgs::Int32>()->data);
++it1;
EXPECT_NE(it0, it1);
EXPECT_EQ(42, it0->instantiate<std_msgs::Int32>()->data);
}

{
rosbag::Bag bag;
bag.open(bag_filename, rosbag::bagmode::Read);
TEST(rosbag_storage, iterator_copy_assignment)
{
// copy assignment
rosbag::Bag bag;
bag.open(bag_filename, rosbag::bagmode::Read);
rosbag::View view(bag, rosbag::TopicQuery("numbers"));
rosbag::View::const_iterator it0 = view.begin();
EXPECT_EQ(42, it0->instantiate<std_msgs::Int32>()->data);
rosbag::View::const_iterator it1;
it1 = it0;
EXPECT_EQ(it0, it1);
EXPECT_EQ(42, it1->instantiate<std_msgs::Int32>()->data);
++it1;
EXPECT_NE(it0, it1);
EXPECT_EQ(42, it0->instantiate<std_msgs::Int32>()->data);
}

TEST(rosbag_storage, iterate_bag)
{
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"));
std::vector<std::string> topics;
topics.push_back(std::string("chatter"));
topics.push_back(std::string("numbers"));

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

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

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

bag.close();
}

bag.close();
}

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

testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
Expand Down
1 change: 1 addition & 0 deletions tools/rosbag_storage/include/rosbag/view.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ class ROSBAG_DECL View
{
public:
iterator(iterator const& i);
iterator &operator=(iterator const& i);
iterator();
~iterator();

Expand Down
13 changes: 13 additions & 0 deletions tools/rosbag_storage/src/view.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,19 @@ View::iterator::iterator(View* view, bool end) : view_(view), view_revision_(0),

View::iterator::iterator(const iterator& i) : view_(i.view_), iters_(i.iters_), view_revision_(i.view_revision_), message_instance_(NULL) { }

View::iterator &View::iterator::operator=(iterator const& i) {
if (this != &i) {
view_ = i.view_;
iters_ = i.iters_;
view_revision_ = i.view_revision_;
if (message_instance_ != NULL) {
delete message_instance_;
message_instance_ = NULL;
}
}
return *this;
}

void View::iterator::populate() {
assert(view_ != NULL);

Expand Down

0 comments on commit a95d25e

Please sign in to comment.