Skip to content

Commit

Permalink
fix rosbag::View::iterator copy assignment operator
Browse files Browse the repository at this point in the history
the compiler-generated copy assignment operator did lead to segfault and
memory leaks.
  • Loading branch information
Sébastien Barthélémy authored and sbarthelemy committed Mar 17, 2017
1 parent 2b16d6c commit f8676e2
Show file tree
Hide file tree
Showing 3 changed files with 47 additions and 0 deletions.
33 changes: 33 additions & 0 deletions test/test_rosbag_storage/src/create_and_iterate_bag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,39 @@ void create_test_bag(const std::string &filename)

const char* bag_filename = "/tmp/rosbag_storage_create_and_iterate_bag.bag";

TEST(rosbag_storage, iterator_copy_constructor)
{
// 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);
}

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;
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 f8676e2

Please sign in to comment.