Skip to content

Commit

Permalink
Detect wayland and make sure X rendering is used. (#1253)
Browse files Browse the repository at this point in the history
rviz2 does not work under wayland unless using X compatibility.
The current workaround on wayland is to set the QT_QPA_PLATFORM
environment variable to xcb.  This patch now detects
if rviz2 is started in a wayland session and if so sets that
variable automatically.

Signed-off-by: Matthew Elwin <[email protected]>
  • Loading branch information
m-elwin authored Jul 26, 2024
1 parent a38e9af commit 72c0826
Showing 1 changed file with 15 additions and 0 deletions.
15 changes: 15 additions & 0 deletions rviz2/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <vector>

#include <QApplication> // NOLINT: cpplint is unable to handle the include order here
#include <QProcessEnvironment> // NOLINT: cpplint is unable to hande the include order here

#include "rclcpp/rclcpp.hpp"
#include "rviz_common/logging.hpp"
Expand All @@ -44,6 +45,20 @@ int main(int argc, char ** argv)
{
// remove ROS arguments before passing to QApplication
std::vector<std::string> non_ros_args = rclcpp::remove_ros_arguments(argc, argv);

// check for wayland and if so force the use of X to render everything
// but only if the user hasn't already tried to specify -platform
// or override QT_QPA_PLATFORM
auto env = QProcessEnvironment::systemEnvironment();
if(env.value("XDG_SESSION_TYPE") == "wayland" &&
non_ros_args.end() == std::find(non_ros_args.begin(), non_ros_args.end(),
"-platform") &&
!env.contains("QT_QPA_PLATFORM"))
{
non_ros_args.push_back("-platform");
non_ros_args.push_back("xcb");
}

std::vector<char *> non_ros_args_c_strings;
for (auto & arg : non_ros_args) {
non_ros_args_c_strings.push_back(&arg.front());
Expand Down

0 comments on commit 72c0826

Please sign in to comment.