Skip to content

Commit

Permalink
Switch to using resource_retriever
Browse files Browse the repository at this point in the history
  • Loading branch information
Martin-Idel-SI committed Mar 26, 2018
1 parent ea015cc commit 1a3b84f
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 28 deletions.
4 changes: 2 additions & 2 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@ set(CMAKE_AUTOMOC ON)

find_package(Qt5 REQUIRED COMPONENTS Widgets)

find_package(ament_index_cpp REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(resource_retriever REQUIRED)
find_package(rviz_assimp_vendor REQUIRED)
find_package(rviz_rendering REQUIRED)
find_package(rviz_yaml_cpp_vendor REQUIRED)
Expand Down Expand Up @@ -226,9 +226,9 @@ target_link_libraries(rviz_common
)

ament_target_dependencies(rviz_common
ament_index_cpp
geometry_msgs
rclcpp
resource_retriever
rviz_assimp_vendor
rviz_yaml_cpp_vendor
sensor_msgs
Expand Down
1 change: 0 additions & 1 deletion rviz_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
<exec_depend>libqt5-opengl</exec_depend>
<exec_depend>libqt5-widgets</exec_depend>

<depend>ament_index_cpp</depend>
<depend>geometry_msgs</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
Expand Down
41 changes: 16 additions & 25 deletions rviz_common/src/rviz_common/load_resource.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,31 +38,25 @@

#include "ament_index_cpp/get_package_share_directory.hpp"
#include "ament_index_cpp/get_package_prefix.hpp"
#include "resource_retriever/retriever.h"

#include "rviz_common/logging.hpp"

namespace rviz_common
{

QString getFilePath(const QString & url)
resource_retriever::MemoryResource getResource(const std::string & resource_path)
{
QString file_path = "";
if (url.indexOf("package://", 0, Qt::CaseInsensitive) == 0) {
QString package_name = url.section('/', 2, 2);
QString file_name = url.section('/', 3);
try {
std::string package_prefix =
ament_index_cpp::get_package_share_directory(package_name.toStdString());
file_path = QString::fromStdString(package_prefix) + "/" + file_name;
} catch (const ament_index_cpp::PackageNotFoundError & error) {
RVIZ_COMMON_LOG_ERROR_STREAM("Package not found: " << error.what());
}
} else if (url.indexOf("file://", 0, Qt::CaseInsensitive) == 0) {
file_path = url.section('/', 2);
} else {
RVIZ_COMMON_LOG_ERROR("Invalid or unsupported URL: " + url.toStdString());
resource_retriever::Retriever retriever;
resource_retriever::MemoryResource res;
try {
res = retriever.get(resource_path);
} catch (resource_retriever::Exception & e) {
RVIZ_COMMON_LOG_DEBUG(e.what());
return resource_retriever::MemoryResource();
}
return file_path;

return res;
}

QPixmap loadPixmap(QString url, bool fill_cache)
Expand All @@ -74,15 +68,12 @@ QPixmap loadPixmap(QString url, bool fill_cache)
return pixmap;
}

QString file_path = getFilePath(url);
RVIZ_COMMON_LOG_DEBUG("Load pixmap at " + file_path.toStdString());
QFile file(file_path);
RVIZ_COMMON_LOG_DEBUG("Load pixmap at " + url.toStdString());

// If something goes wrong here, we go on and store the empty pixmap,
// so the error won't appear again anytime soon.
if (file.exists()) {
if (!pixmap.load(file_path)) {
RVIZ_COMMON_LOG_ERROR("Could not load pixmap " + file_path.toStdString());
auto image = getResource(url.toStdString());
if (image.size != 0) {
if (!pixmap.loadFromData(image.data.get(), static_cast<uint32_t>(image.size))) {
RVIZ_COMMON_LOG_ERROR("Could not load pixmap " + url.toStdString());
}
}

Expand Down

0 comments on commit 1a3b84f

Please sign in to comment.