Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions rviz_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ find_package(geometry_msgs REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(resource_retriever REQUIRED)
find_package(rviz_resource_interfaces REQUIRED)
find_package(rviz_rendering REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
Expand Down Expand Up @@ -260,6 +261,7 @@ target_link_libraries(rviz_common PUBLIC
tf2::tf2
tf2_ros::tf2_ros
yaml-cpp::yaml-cpp
${rviz_resource_interfaces_TARGETS}
)

target_link_libraries(rviz_common PRIVATE
Expand All @@ -286,6 +288,7 @@ ament_export_dependencies(
tf2_ros
yaml_cpp_vendor
yaml-cpp
rviz_resource_interfaces
)

# Export old-style CMake variables
Expand Down
12 changes: 11 additions & 1 deletion rviz_common/include/rviz_common/visualization_frame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@
#include <QMainWindow> // NOLINT: cpplint is unable to handle the include order here
#include <QString> // NOLINT: cpplint is unable to handle the include order here
#include <Qt> // NOLINT: cpplint is unable to handle the include order here
#include <rclcpp/service.hpp>
#include <rviz_resource_interfaces/srv/load_config.hpp>

#include "rviz_common/config.hpp"
#include "rviz_rendering/render_window.hpp"
Expand Down Expand Up @@ -83,6 +85,7 @@ class WidgetGeometryChangeDetector;
*/
class RVIZ_COMMON_PUBLIC VisualizationFrame : public QMainWindow, public WindowManagerInterface
{
using LoadConfig = rviz_resource_interfaces::srv::LoadConfig;
Q_OBJECT

public:
Expand Down Expand Up @@ -172,12 +175,19 @@ class RVIZ_COMMON_PUBLIC VisualizationFrame : public QMainWindow, public WindowM
void
savePersistentSettings();

rclcpp::Service<LoadConfig>::SharedPtr load_config_service_;

void
loadDisplayConfigService(
const std::shared_ptr<LoadConfig::Request> request,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

include <memory>

std::shared_ptr<LoadConfig::Response> response);

/// Load display settings from the given file.
/**
* \param path The full path of the config file to load from.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

update docs

*/
void
loadDisplayConfig(const QString & path);
loadDisplayConfig(const QString & config_string);

// TODO(wjwwood): consider changing this function to raise an exception
// when there is a failure, rather than the getErrorMessage()
Expand Down
1 change: 1 addition & 0 deletions rviz_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>resource_retriever</depend>
<depend>rviz_resource_interfaces</depend>
<depend>rviz_ogre_vendor</depend>
<depend>rviz_rendering</depend>
<depend>sensor_msgs</depend>
Expand Down
51 changes: 40 additions & 11 deletions rviz_common/src/rviz_common/visualization_frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@
#include <QTimer> // NOLINT cpplint cannot handle include order here
#include <QToolBar> // NOLINT cpplint cannot handle include order here
#include <QToolButton> // NOLINT cpplint cannot handle include order here
#include <rclcpp/service.hpp>
#include <rviz_resource_interfaces/srv/load_config.hpp>

#include "rclcpp/clock.hpp"
#include "tf2_ros/buffer.hpp"
Expand Down Expand Up @@ -351,6 +353,14 @@ void VisualizationFrame::initialize(
loadDisplayConfig(QString::fromStdString(default_display_config_file_));
}

auto node_abstraction = rviz_ros_node.lock();
auto node = node_abstraction->get_raw_node();
load_config_service_ = node->create_service<LoadConfig>(
node_abstraction->get_node_name() + "/load_config",
std::bind(
&VisualizationFrame::loadDisplayConfigService, this,
std::placeholders::_1, std::placeholders::_2));

// Periodically process events for the splash screen.
QCoreApplication::processEvents();

Expand Down Expand Up @@ -670,14 +680,28 @@ void VisualizationFrame::markRecentConfig(const std::string & path)
updateRecentConfigMenu();
}

void VisualizationFrame::loadDisplayConfig(const QString & qpath)
void VisualizationFrame::loadDisplayConfigService(
const std::shared_ptr<LoadConfig::Request> request,
std::shared_ptr<LoadConfig::Response> response)
{
std::string path = qpath.toStdString();
QFileInfo path_info(qpath);
RVIZ_COMMON_LOG_INFO_STREAM(
"Requested loadConfig" << request->config_string.c_str()
);
loadDisplayConfig(QString::fromStdString(request->config_string));
response->success = true;
response->message = "Loaded display config.";
}

void VisualizationFrame::loadDisplayConfig(const QString & config_string)
{
std::string path = config_string.toStdString();
QFileInfo path_info(config_string);
std::string actual_load_path = path;
if (!path_info.exists() || path_info.isDir()) {
bool is_loadable_path = (path_info.exists() && !path_info.isDir());
if (!is_loadable_path) {
actual_load_path = package_path_ + "/default.rviz";
if (!QFile(QString::fromStdString(actual_load_path)).exists()) {
is_loadable_path = QFile(QString::fromStdString(actual_load_path)).exists();
if (!is_loadable_path) {
RVIZ_COMMON_LOG_ERROR_STREAM(
"Default display config '" <<
actual_load_path.c_str() << "' not found. RViz will be very empty at first.");
Expand Down Expand Up @@ -705,7 +729,12 @@ void VisualizationFrame::loadDisplayConfig(const QString & qpath)

YamlConfigReader reader;
Config config;
reader.readFile(config, QString::fromStdString(actual_load_path));
if (is_loadable_path) {
reader.readFile(config, QString::fromStdString(actual_load_path));
} else { // Treat as yaml string content
reader.readString(config, config_string);
}

if (!reader.error()) {
try {
load(config);
Expand All @@ -714,11 +743,11 @@ void VisualizationFrame::loadDisplayConfig(const QString & qpath)
}
}

markRecentConfig(path);

setDisplayConfigFile(path);

last_config_dir_ = path_info.absolutePath().toStdString();
if (is_loadable_path) {
markRecentConfig(path);
setDisplayConfigFile(path);
last_config_dir_ = path_info.absolutePath().toStdString();
}

post_load_timer_->start(1000);
}
Expand Down
1 change: 1 addition & 0 deletions rviz_resource_interfaces/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"srv/GetResource.srv"
"srv/LoadConfig.srv"
)

ament_export_dependencies(rosidl_default_runtime)
Expand Down
4 changes: 4 additions & 0 deletions rviz_resource_interfaces/srv/LoadConfig.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
string config_string
---
bool success
string message