Fix race condition (#293)

* Change mutex locker scope in SubmapsDisplay::update()

This avoids the potential unsafe situation where someone (for example,
SubmapsDisplay::Reset()) clears the trajectories vector, but update()
uses it after the mutex has been released, since the scope of the lock
was only in the try block.

Also resolve a miscellaneous signed-unsigned warning.

* Make DrawableSubmap destructor safer

Make the DrawableSubmap destructor wait for the asynchronous fetch
thread to finish - otherwise, it's possible to crash rviz by rapidly
pressing the enable checkbox of the submaps plugin. Eventually the race
condition will be triggered, and the fetch thread will write into a
deleted DrawableSubmap object, which causes a crash.
master
Juraj Oršulić 2017-03-31 16:36:47 +02:00 committed by Wolfgang Hess
parent 27db0e9566
commit 319be1ad8c
2 changed files with 5 additions and 2 deletions

View File

@ -78,6 +78,9 @@ DrawableSubmap::DrawableSubmap(const int trajectory_id, const int submap_index,
} }
DrawableSubmap::~DrawableSubmap() { DrawableSubmap::~DrawableSubmap() {
if (QueryInProgress()) {
rpc_request_future_.wait();
}
Ogre::MaterialManager::getSingleton().remove(material_->getHandle()); Ogre::MaterialManager::getSingleton().remove(material_->getHandle());
if (!texture_.isNull()) { if (!texture_.isNull()) {
Ogre::TextureManager::getSingleton().remove(texture_->getHandle()); Ogre::TextureManager::getSingleton().remove(texture_->getHandle());

View File

@ -114,13 +114,13 @@ void SubmapsDisplay::processMessage(
} }
void SubmapsDisplay::update(const float wall_dt, const float ros_dt) { void SubmapsDisplay::update(const float wall_dt, const float ros_dt) {
::cartographer::common::MutexLocker locker(&mutex_);
// Update the fading by z distance. // Update the fading by z distance.
try { try {
const ::geometry_msgs::TransformStamped transform_stamped = const ::geometry_msgs::TransformStamped transform_stamped =
tf_buffer_.lookupTransform(map_frame_property_->getStdString(), tf_buffer_.lookupTransform(map_frame_property_->getStdString(),
tracking_frame_property_->getStdString(), tracking_frame_property_->getStdString(),
ros::Time(0) /* latest */); ros::Time(0) /* latest */);
::cartographer::common::MutexLocker locker(&mutex_);
for (auto& trajectory : trajectories_) { for (auto& trajectory : trajectories_) {
for (auto& submap : trajectory) { for (auto& submap : trajectory) {
submap->SetAlpha(transform_stamped.transform.translation.z); submap->SetAlpha(transform_stamped.transform.translation.z);
@ -138,7 +138,7 @@ void SubmapsDisplay::update(const float wall_dt, const float ros_dt) {
++num_ongoing_requests; ++num_ongoing_requests;
} }
} }
for (int submap_index = trajectory.size() - 1; for (int submap_index = static_cast<int>(trajectory.size()) - 1;
submap_index >= 0 && submap_index >= 0 &&
num_ongoing_requests < kMaxOnGoingRequestsPerTrajectory; num_ongoing_requests < kMaxOnGoingRequestsPerTrajectory;
--submap_index) { --submap_index) {