Skip to content

Commit

Permalink
Fix segfault when camera dispay closed. Closes #1372.
Browse files Browse the repository at this point in the history
  • Loading branch information
hexonxons committed Jul 31, 2019
1 parent f9b357f commit e691a37
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 2 deletions.
9 changes: 7 additions & 2 deletions src/rviz/image/image_display_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ ImageDisplayBase::ImageDisplayBase() :
Display()
, sub_()
, tf_filter_()
, tf_filter_callback_id_(std::numeric_limits<uint64_t>::max())
, messages_received_(0)
{
topic_property_ = new RosTopicProperty("Image Topic", "",
Expand Down Expand Up @@ -176,14 +177,17 @@ void ImageDisplayBase::subscribe()
}
else
{
tf_filter_.reset(new tf2_ros::MessageFilter<sensor_msgs::Image>(
auto filter = new tf2_ros::MessageFilter<sensor_msgs::Image>(
*sub_,
*context_->getTF2BufferPtr(),
targetFrame_,
queue_size_property_->getInt(),
update_nh_
));
);
tf_filter_.reset(filter);
tf_filter_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
// See https://github.com/ros-visualization/rviz/issues/1372 PR.
tf_filter_callback_id_ = (uint64_t) filter;
}
}
setStatus(StatusProperty::Ok, "Topic", "OK");
Expand All @@ -203,6 +207,7 @@ void ImageDisplayBase::subscribe()

void ImageDisplayBase::unsubscribe()
{
update_nh_.getCallbackQueue()->removeByID(tf_filter_callback_id_);
tf_filter_.reset();
sub_.reset(new image_transport::SubscriberFilter());
}
Expand Down
1 change: 1 addition & 0 deletions src/rviz/image/image_display_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,7 @@ protected Q_SLOTS:
boost::scoped_ptr<image_transport::ImageTransport> it_;
boost::shared_ptr<image_transport::SubscriberFilter> sub_;
boost::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::Image> > tf_filter_;
uint64_t tf_filter_callback_id_;

std::string targetFrame_;

Expand Down

0 comments on commit e691a37

Please sign in to comment.