Skip to content

Commit

Permalink
Restore icons throughout RViz2 (#235)
Browse files Browse the repository at this point in the history
* Move icons to rviz_common or rviz_default_plugins

* Unify installs in CMakeLists

* Install icons

* Reenable loading of PixMaps using ament_index_cpp

* Rename plugins in plugin_description and classes

- This is necessary to be able to find icons (name=path)

* Adapt names so that all icons are found

* Change names in default config

- Otherwise using the default config can't load classes anymore

* Reenable image loading for cursor icons

- this does not functionally reenable different cursors

* Improve error message in loading from ament_index_cpp

* Set cursor for RenderWindow

* Fix rviz crash for invalid config file

By catching the exception rviz will start with a visibly broken config
so that the user can fix the config manually.

* Switch to using resource_retriever

* Add simple mechanism to automatically convert old configs
  • Loading branch information
anhosi authored and wjwwood committed Mar 31, 2018
1 parent f2aaabd commit 4aaa893
Show file tree
Hide file tree
Showing 107 changed files with 141 additions and 127 deletions.
7 changes: 7 additions & 0 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ find_package(Qt5 REQUIRED COMPONENTS Widgets)
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 @@ -227,6 +228,7 @@ target_link_libraries(rviz_common
ament_target_dependencies(rviz_common
geometry_msgs
rclcpp
resource_retriever
rviz_assimp_vendor
rviz_yaml_cpp_vendor
sensor_msgs
Expand Down Expand Up @@ -274,6 +276,11 @@ install(FILES default.rviz
DESTINATION share/${PROJECT_NAME}
)

install(
DIRECTORY "${CMAKE_SOURCE_DIR}/icons"
DESTINATION "share/${PROJECT_NAME}"
)

# TODO(wjwwood): reenable tests for Windows after resolving building problems
if(BUILD_TESTING AND NOT WIN32)
# TODO(wjwwood): replace this with ament_lint_auto() and/or add the copyright linter back
Expand Down
10 changes: 5 additions & 5 deletions rviz_common/default.rviz
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
Panels:
- Class: rviz/Displays
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expand All @@ -18,7 +18,7 @@ Panels:
# - /Publish Point1
# Name: Tool Properties
# Splitter Ratio: 0.588679
- Class: rviz/Views
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Expand All @@ -32,7 +32,7 @@ Visualization Manager:
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Expand All @@ -57,7 +57,7 @@ Visualization Manager:
# TODO(wjwwood): restore these tools when ported
# - Class: rviz/Interact
# Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz_default_plugins/MoveCamera
# - Class: rviz/Select
# - Class: rviz/FocusCamera
# - Class: rviz/Measure
Expand All @@ -71,7 +71,7 @@ Visualization Manager:
Value: true
Views:
Current:
Class: rviz/Orbit
Class: rviz_default_plugins/Orbit
Distance: 10
Focal Point:
X: 0
Expand Down
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
File renamed without changes
2 changes: 1 addition & 1 deletion rviz_common/src/rviz_common/add_display_dialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -412,7 +412,7 @@ void DisplayTypeTree::onCurrentItemChanged(

void DisplayTypeTree::fillTree(Factory * factory)
{
QIcon default_package_icon = loadPixmap("package://rviz/icons/default_package_icon.png");
QIcon default_package_icon = loadPixmap("package://rviz_common/icons/default_package_icon.png");

QStringList classes = factory->getDeclaredClassIds();
classes.sort();
Expand Down
23 changes: 22 additions & 1 deletion rviz_common/src/rviz_common/config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@

#include <QLocale>

#include "rviz_common/logging.hpp"

namespace rviz_common
{

Expand Down Expand Up @@ -285,11 +287,30 @@ bool Config::isValid() const
return node_.get() != NULL;
}

// TODO(Martin-Idel-SI): This is just a temporary helper to convert old rviz2 configs.
// Remove after next release.
QVariant correctClassNames(const QVariant & value)
{
auto string_representation = value.toString();
if (string_representation.contains(QString("rviz/"))) {
RVIZ_COMMON_LOG_WARNING("Your config contains obsolete class name " +
value.toString().toStdString() + ". Please save your config to correct it.");
if (string_representation == "rviz/Displays" ||
string_representation == "rviz/Views" ||
string_representation == "rviz/DisplayGroup")
{
return string_representation.replace(0, 4, "rviz_common");
}
return string_representation.replace(0, 4, "rviz_default_plugins");
}
return value;
}

void Config::setValue(const QVariant & value)
{
makeValid();
node_->setType(Value);
*node_->data_.value = value;
*node_->data_.value = correctClassNames(value);
}

QVariant Config::getValue() const
Expand Down
3 changes: 1 addition & 2 deletions rviz_common/src/rviz_common/display_factory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,7 @@ static Display * newDisplayGroup()
DisplayFactory::DisplayFactory()
: PluginlibFactory<Display>("rviz_common", "rviz_common::Display")
{
addBuiltInClass("rviz", "Group", "A container for Displays", &newDisplayGroup);
// addBuiltInClass("rviz", "RobotModel", "robot model display", &newRobotModelDisplay);
addBuiltInClass("rviz_common", "Group", "A container for Displays", &newDisplayGroup);
}

Display * DisplayFactory::makeRaw(const QString & class_id, QString * error_return)
Expand Down
2 changes: 1 addition & 1 deletion rviz_common/src/rviz_common/failed_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ FailedDisplay::FailedDisplay(const QString & desired_class_id, const QString & e
: error_message_(error_message)
{
setClassId(desired_class_id);
setIcon(loadPixmap("package://rviz/icons/failed_display.png"));
setIcon(loadPixmap("package://rviz_common/icons/failed_display.png"));
}

QVariant FailedDisplay::getViewData(int column, int role) const
Expand Down
104 changes: 40 additions & 64 deletions rviz_common/src/rviz_common/load_resource.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,65 +30,56 @@

#include "rviz_common/load_resource.hpp"

// #include <boost/filesystem.hpp>
// #include <ros/package.h>
// #include <ros/ros.h>
#include <string>

#include <QPixmapCache>
#include <QPainter>
#include <QFile> // NOLINT: cpplint cannot handle the include order here
#include <QPainter> // NOLINT: cpplint cannot handle the include order here
#include <QPixmapCache> // NOLINT: cpplint cannot handle the include order here

#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
{

// TODO(wjwwood): replace this with ROS 2 and boost-free version
// boost::filesystem::path getPath(QString url)
// {
// boost::filesystem::path path;

// if (url.indexOf("package://", 0, Qt::CaseInsensitive) == 0) {
// QString package_name = url.section('/', 2, 2);
// QString file_name = url.section('/', 3);
// path = ros::package::getPath(package_name.toStdString());
// path = path / file_name.toStdString();
// } else if (url.indexOf("file://", 0, Qt::CaseInsensitive) == 0) {
// path = url.section('/', 2).toStdString();
// } else {
// ROS_ERROR("Invalid or unsupported URL: '%s'", url.toStdString().c_str() );
// }

// return path;
// }
resource_retriever::MemoryResource getResource(const std::string & resource_path)
{
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 res;
}

QPixmap loadPixmap(QString url, bool fill_cache)
{
QPixmap pixmap;

// TODO(wjwwood): reenable this, or in the meantime add a placeholder pixmap
Q_UNUSED(url);
Q_UNUSED(fill_cache);
// RVIZ_COMMON_LOG_WARNING_STREAM("did not load pixmap at " << url.toStdString());
// // if it's in the cache, no need to locate
// if (QPixmapCache::find(url, &pixmap) ) {
// return pixmap;
// }

// boost::filesystem::path path = getPath(url);

// // If something goes wrong here, we go on and store the empty pixmap,
// // so the error won't appear again anytime soon.
// if (boost::filesystem::exists(path) ) {
// ROS_DEBUG_NAMED("load_resource", "Loading '%s'", path.string().c_str() );
// if (!pixmap.load(QString::fromStdString(path.string() ) ) ) {
// ROS_ERROR("Could not load pixmap '%s'", path.string().c_str() );
// }
// }

// if (fill_cache) {
// QPixmapCache::insert(url, pixmap);
// }
// if it's in the cache, no need to locate
if (QPixmapCache::find(url, &pixmap)) {
return pixmap;
}

RVIZ_COMMON_LOG_DEBUG("Load pixmap at " + url.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());
}
}

if (fill_cache) {
QPixmapCache::insert(url, pixmap);
}

return pixmap;
}
Expand All @@ -101,39 +92,25 @@ QCursor getDefaultCursor(bool fill_cache)

QCursor makeIconCursor(QString url, bool fill_cache)
{
// TODO(wjwwood): reenable this
Q_UNUSED(url);
Q_UNUSED(fill_cache);
// RVIZ_COMMON_LOG_WARNING_STREAM("did not load icon as cursor at " << url.toStdString());
return QCursor(Qt::ArrowCursor);
#if 0
QPixmap icon = loadPixmap(url, fill_cache);
if (icon.width() == 0 || icon.height() == 0) {
ROS_ERROR("Could not load pixmap '%s' -- using default cursor instead.",
url.toStdString().c_str() );
RVIZ_COMMON_LOG_ERROR_STREAM("Could not load pixmap " << url.toStdString() << " -- "
"using default cursor instead.");
return getDefaultCursor();
}
QString cache_key = url + ".cursor";
return makeIconCursor(icon, cache_key, fill_cache);
#endif
}

QCursor makeIconCursor(QPixmap icon, QString cache_key, bool fill_cache)
{
// TODO(wjwwood): reenable this
Q_UNUSED(icon);
Q_UNUSED(cache_key);
Q_UNUSED(fill_cache);
// RVIZ_COMMON_LOG_WARNING_STREAM("did not make icon into cursor at " << cache_key.toStdString());
return QCursor(Qt::ArrowCursor);
#if 0
// if it's in the cache, no need to locate
QPixmap cursor_img;
if (QPixmapCache::find(cache_key, &cursor_img) ) {
return QCursor(cursor_img, 0, 0);
}

QPixmap base_cursor = loadPixmap("package://rviz/icons/cursor.svg", fill_cache);
QPixmap base_cursor = loadPixmap("package://rviz_common/icons/cursor.svg", fill_cache);

const int cursor_size = 32;

Expand Down Expand Up @@ -162,7 +139,6 @@ QCursor makeIconCursor(QPixmap icon, QString cache_key, bool fill_cache)
}

return QCursor(cursor_img, 1, 1);
#endif
}

} // namespace rviz_common
2 changes: 1 addition & 1 deletion rviz_common/src/rviz_common/new_object_dialog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ QSize NewObjectDialog::sizeHint() const

void NewObjectDialog::fillTree(QTreeWidget * tree)
{
QIcon default_package_icon = loadPixmap("package://rviz/icons/default_package_icon.png");
QIcon default_package_icon = loadPixmap("package://rviz_common/icons/default_package_icon.png");

QStringList classes = factory_->getDeclaredClassIds();
classes.sort();
Expand Down
12 changes: 6 additions & 6 deletions rviz_common/src/rviz_common/panel_factory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,20 +52,20 @@ static Panel * newViewsPanel() {return new ViewsPanel();}
PanelFactory::PanelFactory(const std::string & node_name)
: PluginlibFactory<Panel>("rviz_common", "rviz_common::Panel")
{
addBuiltInClass("rviz", "Displays",
addBuiltInClass("rviz_common", "Displays",
"Show and edit the list of Displays",
[&node_name]() -> Panel * {
return new DisplaysPanel(node_name, nullptr);
});
// addBuiltInClass("rviz", "Help",
// addBuiltInClass("rviz_common", "Help",
// "Show the key and mouse bindings", &newHelpPanel);
// addBuiltInClass("rviz", "Selection",
// addBuiltInClass("rviz_common", "Selection",
// "Show properties of selected objects", &newSelectionPanel);
// addBuiltInClass("rviz", "Time",
// addBuiltInClass("rviz_common", "Time",
// "Show the current time", &newTimePanel);
// addBuiltInClass("rviz", "Tool Properties",
// addBuiltInClass("rviz_common", "Tool Properties",
// "Show and edit properties of tools", &newToolPropertiesPanel);
addBuiltInClass("rviz", "Views",
addBuiltInClass("rviz_common", "Views",
"Show and edit viewpoints", &newViewsPanel);
}

Expand Down
2 changes: 1 addition & 1 deletion rviz_common/src/rviz_common/pluginlib_factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ class PluginlibFactory : public ClassIdRecordingFactory<Type>
if (icon.isNull()) {
icon = loadPixmap("package://" + package + "/icons/classes/" + class_name + ".png");
if (icon.isNull()) {
icon = loadPixmap("package://rviz/icons/default_class_icon.png");
icon = loadPixmap("package://rviz_common/icons/default_class_icon.png");
}
}
return icon;
Expand Down
6 changes: 3 additions & 3 deletions rviz_common/src/rviz_common/properties/status_property.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +51,9 @@ StatusProperty::StatusProperty(
level_(level)
{
setShouldBeSaved(false);
status_icons_[0] = loadPixmap("package://rviz/icons/ok.png");
status_icons_[1] = loadPixmap("package://rviz/icons/warning.png");
status_icons_[2] = loadPixmap("package://rviz/icons/error.png");
status_icons_[0] = loadPixmap("package://rviz_common/icons/ok.png");
status_icons_[1] = loadPixmap("package://rviz_common/icons/warning.png");
status_icons_[2] = loadPixmap("package://rviz_common/icons/error.png");
}

bool StatusProperty::setValue(const QVariant & new_value)
Expand Down
2 changes: 1 addition & 1 deletion rviz_common/src/rviz_common/splash_screen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ SplashScreen::SplashScreen(const QPixmap & pixmap)

painter.drawPixmap(QPoint(0, 0), pixmap);

QPixmap overlay = loadPixmap("package://rviz/images/splash_overlay.png");
QPixmap overlay = loadPixmap("package://rviz_common/images/splash_overlay.png");
painter.drawTiledPixmap(QRect(0, pixmap.height() - overlay.height(), pixmap.width(),
pixmap.height() ), overlay);

Expand Down
12 changes: 6 additions & 6 deletions rviz_common/src/rviz_common/tool_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,11 +78,11 @@ void ToolManager::initialize()
QStringList class_ids = factory_->getDeclaredClassIds();
// define a list of preferred tool names (they will be listed first in the toolbar)
std::vector<const char *> preferred_tool_names = {
"rviz/MoveCamera",
"rviz/Interact",
"rviz/Select",
"rviz/SetInitialPose",
"rviz/SetGoal",
"rviz_default_plugins/MoveCamera",
"rviz_default_plugins/Interact",
"rviz_default_plugins/Select",
"rviz_default_plugins/SetInitialPose",
"rviz_default_plugins/SetGoal",
};
// attempt to load each preferred tool in order
for (const auto & preferred_tool_name : preferred_tool_names) {
Expand Down Expand Up @@ -272,7 +272,7 @@ Tool * ToolManager::addTool(const QString & class_id)

return tool;
#else
if (class_id == "rviz/MoveCamera") {
if (class_id == "rviz_default_plugins/MoveCamera") {
Tool * tool = new rviz_common::MoveTool();
tools_.append(tool);
tool->setName(addSpaceToCamelCase("MoveTool"));
Expand Down
Loading

0 comments on commit 4aaa893

Please sign in to comment.