image_cache.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #include <tile_map/image_cache.h>
00031 
00032 #include <boost/make_shared.hpp>
00033 
00034 #include <QtAlgorithms>
00035 #include <QByteArray>
00036 #include <QList>
00037 #include <QNetworkAccessManager>
00038 #include <QNetworkDiskCache>
00039 #include <QUrl>
00040 
00041 #include <ros/ros.h>
00042 
00043 namespace tile_map
00044 {
00045   bool ComparePriority(const ImagePtr left, const ImagePtr right)
00046   {
00047     return left->Priority() > right->Priority();
00048   }
00049 
00050   const int Image::MAXIMUM_FAILURES = 5;
00051 
00052   Image::Image(const QString& uri, size_t uri_hash, uint64_t priority) :
00053     uri_(uri),
00054     uri_hash_(uri_hash),
00055     loading_(false),
00056     failures_(0),
00057     failed_(false),
00058     priority_(priority)
00059   {
00060   }
00061 
00062   Image::~Image()
00063   {
00064   }
00065 
00066   void Image::InitializeImage()
00067   {
00068     image_ = boost::make_shared<QImage>();
00069   }
00070 
00071   void Image::ClearImage()
00072   {
00073     image_.reset();
00074   }
00075 
00076   void Image::AddFailure()
00077   {
00078     failures_++;
00079     failed_ = failures_ > MAXIMUM_FAILURES;
00080   }
00081 
00082   const int ImageCache::MAXIMUM_NETWORK_REQUESTS = 6;
00083 
00084   ImageCache::ImageCache(const QString& cache_dir, size_t size) :
00085     network_manager_(this),
00086     cache_dir_(cache_dir),
00087     cache_(size),
00088     exit_(false),
00089     tick_(0),
00090     cache_thread_(new CacheThread(this)),
00091     network_request_semaphore_(MAXIMUM_NETWORK_REQUESTS)
00092   {
00093     QNetworkDiskCache* disk_cache = new QNetworkDiskCache(this);
00094     disk_cache->setCacheDirectory(cache_dir_);
00095     network_manager_.setCache(disk_cache);
00096 
00097     connect(&network_manager_, SIGNAL(finished(QNetworkReply*)), this, SLOT(ProcessReply(QNetworkReply*)));
00098     connect(cache_thread_, SIGNAL(RequestImage(QString)), this, SLOT(ProcessRequest(QString)));
00099 
00100     cache_thread_->start();
00101     cache_thread_->setPriority(QThread::NormalPriority);
00102   }
00103 
00104   ImageCache::~ImageCache()
00105   {
00106     // After setting our exit flag to true, release any conditions the cache thread
00107     // might be waiting on so that it will exit.
00108     exit_ = true;
00109     cache_thread_->notify();
00110     network_request_semaphore_.release(MAXIMUM_NETWORK_REQUESTS);
00111     cache_thread_->wait();
00112     delete cache_thread_;
00113   }
00114 
00115   void ImageCache::Clear()
00116   {
00117     cache_.clear();
00118     network_manager_.cache()->clear();
00119   }
00120 
00121   ImagePtr ImageCache::GetImage(size_t uri_hash, const QString& uri, int32_t priority)
00122   {
00123     ImagePtr image;
00124 
00125     // Retrieve the image reference from the cache, updating the freshness.
00126     cache_mutex_.lock();
00127 
00128     if (failed_.contains(uri_hash))
00129     {
00130       cache_mutex_.unlock();
00131       return image;
00132     }
00133 
00134     ImagePtr* image_ptr = cache_.take(uri_hash);
00135     if (!image_ptr)
00136     {
00137       // If the image is not in the cache, create a new reference.
00138       image_ptr = new ImagePtr(boost::make_shared<Image>(uri, uri_hash));
00139       image = *image_ptr;
00140       if (!cache_.insert(uri_hash, image_ptr))
00141       {
00142         ROS_ERROR("FAILED TO CREATE HANDLE: %s", uri.toStdString().c_str());
00143         image_ptr = 0;
00144       }
00145     }
00146     else
00147     {
00148       image = *image_ptr;
00149 
00150       // Add raw pointer back to cache.
00151       cache_.insert(uri_hash, image_ptr);
00152     }
00153 
00154     cache_mutex_.unlock();
00155 
00156     unprocessed_mutex_.lock();
00157     if (image && !image->GetImage())
00158     {
00159       if (!image->Failed())
00160       {
00161         if (!unprocessed_.contains(uri_hash))
00162         {
00163           // Set an image's starting priority so that it's higher than the
00164           // starting priority of every other image we've requested so
00165           // far; that ensures that, all other things being equal, the
00166           // most recently requested images will be loaded first.
00167           image->SetPriority(priority + tick_++);
00168           unprocessed_[uri_hash] = image;
00169           uri_to_hash_map_[uri] = uri_hash;
00170           cache_thread_->notify();
00171         }
00172         else
00173         {
00174           // Every time an image is requested but hasn't been loaded yet,
00175           // increase its priority.  Tiles within the visible area will
00176           // be requested more frequently, so this will make them load faster
00177           // than tiles the user can't see.
00178           image->SetPriority(priority + tick_++);
00179         }
00180       }
00181       else
00182       {
00183         failed_.insert(uri_hash);
00184       }
00185     }
00186 
00187     unprocessed_mutex_.unlock();
00188 
00189     return image;
00190   }
00191 
00192   void ImageCache::ProcessRequest(QString uri)
00193   {
00194     QNetworkRequest request;
00195     request.setUrl(QUrl(uri));
00196     request.setRawHeader("User-Agent", "mapviz-1.0");
00197     request.setAttribute(
00198         QNetworkRequest::CacheLoadControlAttribute,
00199         QNetworkRequest::PreferCache);
00200     request.setAttribute(
00201         QNetworkRequest::HttpPipeliningAllowedAttribute,
00202         true);
00203 
00204     QNetworkReply *reply = network_manager_.get(request);
00205     connect(reply, SIGNAL(error(QNetworkReply::NetworkError)),
00206             this, SLOT(NetworkError(QNetworkReply::NetworkError)));
00207   }
00208 
00209   void ImageCache::ProcessReply(QNetworkReply* reply)
00210   {
00211     QString url = reply->url().toString();
00212 
00213     ImagePtr image;
00214     unprocessed_mutex_.lock();
00215 
00216     size_t hash = uri_to_hash_map_[url];
00217     image = unprocessed_[hash];
00218     if (image)
00219     {
00220       if (reply->error() == QNetworkReply::NoError)
00221       {
00222         QByteArray data = reply->readAll();
00223         image->InitializeImage();
00224         if (!image->GetImage()->loadFromData(data))
00225         {
00226           image->ClearImage();
00227           image->AddFailure();
00228         }
00229       }
00230       else
00231       {
00232         image->AddFailure();
00233       }
00234     }
00235 
00236     unprocessed_.remove(hash);
00237     uri_to_hash_map_.remove(url);
00238     if (image)
00239     {
00240       image->SetLoading(false);
00241     }
00242     network_request_semaphore_.release();
00243 
00244     unprocessed_mutex_.unlock();
00245 
00246     reply->deleteLater();
00247   }
00248 
00249   void ImageCache::NetworkError(QNetworkReply::NetworkError error)
00250   {
00251     ROS_ERROR("NETWORK ERROR");
00252     // TODO add failure
00253   }
00254 
00255   const int CacheThread::MAXIMUM_SEQUENTIAL_REQUESTS = 12;
00256 
00257   CacheThread::CacheThread(ImageCache* parent) :
00258     p(parent),
00259     waiting_mutex_()
00260   {
00261     waiting_mutex_.lock();
00262   }
00263 
00264   void CacheThread::notify()
00265   {
00266     waiting_mutex_.unlock();
00267   }
00268 
00269   void CacheThread::run()
00270   {
00271     while (!p->exit_)
00272     {
00273       // Wait until we're told there are images we need to request.
00274       waiting_mutex_.lock();
00275 
00276       // Next, get all of them and sort them by priority.
00277       p->unprocessed_mutex_.lock();
00278       QList<ImagePtr> images = p->unprocessed_.values();
00279       p->unprocessed_mutex_.unlock();
00280 
00281       qSort(images.begin(), images.end(), ComparePriority);
00282 
00283       // Go through all of them and request them.  Qt's network manager will
00284       // only handle six simultaneous requests at once, so we use a semaphore
00285       // to limit ourselves to that many.
00286       // Each individual image will release the semaphore when it is done loading.
00287       // Also, only load up to a certain number at a time in this loop.  If there
00288       // are more left afterward, we'll start over.  This ensures that we
00289       // concentrate on processing the highest-priority images.
00290       int count = 0;
00291       while (!p->exit_ && !images.empty() && count < MAXIMUM_SEQUENTIAL_REQUESTS)
00292       {
00293         p->network_request_semaphore_.acquire();
00294 
00295         ImagePtr image = images.front();
00296         p->unprocessed_mutex_.lock();
00297         if (!image->Loading() && !image->Failed())
00298         {
00299           count++;
00300           image->SetLoading(true);
00301           images.pop_front();
00302 
00303           QString uri = image->Uri();
00304           size_t hash = p->uri_to_hash_map_[uri];
00305           if (uri.startsWith(QString("file:///")))
00306           {
00307             image->InitializeImage();
00308             QString filepath = uri.replace(QString("file:///"), QString("/"));
00309             if (!image->GetImage()->load(filepath))
00310             {
00311               image->ClearImage();
00312               image->AddFailure();
00313             }
00314 
00315             p->unprocessed_.remove(hash);
00316             p->uri_to_hash_map_.remove(uri);
00317             image->SetLoading(false);
00318             p->network_request_semaphore_.release();
00319           }
00320           else
00321           {
00322             Q_EMIT RequestImage(image->Uri());
00323           }
00324         }
00325         else
00326         {
00327           images.pop_front();
00328         }
00329         p->unprocessed_mutex_.unlock();
00330 
00331       }
00332       if (!images.empty())
00333       {
00334         waiting_mutex_.unlock();
00335       }
00336     }
00337   }
00338 }


tile_map
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 18:51:19