Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Maliput viewer: Adds UI for layers selection. #382

Merged
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
144 changes: 144 additions & 0 deletions delphyne_gui/visualizer/LayersSelectionArea.qml
Original file line number Diff line number Diff line change
@@ -0,0 +1,144 @@
// Copyright 2021 Toyota Research Institute

import QtQuick 2.9
import QtQuick.Controls 1.4
import QtQuick.Controls.Material 2.1
import QtQuick.Dialogs 1.0
import QtQuick.Layouts 1.3

// Panel that contains checkboxs to enable or disable layers.
GridLayout {
id: filesSelectionArea
columns: 3
anchors.left: parent.left
anchors.leftMargin: 10
anchors.right: parent.right
anchors.rightMargin: 10
anchors.top: parent.top
Layout.fillWidth: true

/**
* Title text
*/
Text {
id: titleText
Layout.columnSpan: 3
anchors.horizontalCenter: parent.horizontalCenter
Layout.alignment: Qt.AlignVTop | Qt.AlignHCenter
font.pointSize: 10
text: "MESH LAYERS"
}

/**
* Ashpalt checkbox
*/
CheckBox {
id: layerAsphalt
text: qsTr("Asphalt")
checked: true
onClicked : {
MaliputViewerPlugin.OnNewMeshLayerSelection("asphalt", checked);
}
}

/**
* Lane checkbox
*/
CheckBox {
id: layerLane
text: qsTr("Lane")
checked: true
onClicked : {
MaliputViewerPlugin.OnNewMeshLayerSelection("lane_all", checked);
}
}

/**
* Marker checkbox
*/
CheckBox {
id: layerMarker
text: qsTr("Marker")
checked: true
onClicked : {
MaliputViewerPlugin.OnNewMeshLayerSelection("marker_all", checked);
}
}

/**
* HBounds checkbox
*/
CheckBox {
id: layerHBounds
text: qsTr("HBounds")
checked: true
onClicked : {
MaliputViewerPlugin.OnNewMeshLayerSelection("h_bounds", checked);
}
}

/**
* BranchPoint checkbox
*/
CheckBox {
id: layerBranchPoint
text: qsTr("Branch Point")
checked: true
onClicked : {
MaliputViewerPlugin.OnNewMeshLayerSelection("branch_point_all", checked);
}
}

/**
* GrayedAsphalt checkbox
*/
CheckBox {
id: layerGrayedAsphalt
text: qsTr("Grayed asphalt")
checked: false
onClicked : {
MaliputViewerPlugin.OnNewMeshLayerSelection("grayed_asphalt", checked);
}
}

/**
* GrayedLane checkbox
*/
CheckBox {
id: layerGrayedLane
text: qsTr("Grayed lane")
checked: false
onClicked : {
MaliputViewerPlugin.OnNewMeshLayerSelection("grayed_lane_all", checked);
}
}

/**
* GrayedMarker checkbox
*/
CheckBox {
id: layerGrayedMarker
text: qsTr("Grayed marker")
checked: false
onClicked : {
MaliputViewerPlugin.OnNewMeshLayerSelection("grayed_marker_all", checked);
}
}

/*
* Update checkboxes' state.
*/
Connections {
target: MaliputViewerPlugin
onLayerCheckboxesChanged: {
layerAsphalt.checked = MaliputViewerPlugin.layerCheckboxes[0]
layerLane.checked = MaliputViewerPlugin.layerCheckboxes[1]
layerMarker.checked = MaliputViewerPlugin.layerCheckboxes[2]
layerHBounds.checked = MaliputViewerPlugin.layerCheckboxes[3]
layerBranchPoint.checked = MaliputViewerPlugin.layerCheckboxes[4]
layerGrayedAsphalt.checked = MaliputViewerPlugin.layerCheckboxes[5]
layerGrayedLane.checked = MaliputViewerPlugin.layerCheckboxes[6]
layerGrayedMarker.checked = MaliputViewerPlugin.layerCheckboxes[7]
}
}
}
10 changes: 10 additions & 0 deletions delphyne_gui/visualizer/MaliputViewerPlugin.qml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ Rectangle {
source: "FileSelectionArea.qml"
}
ToolSeparator {
id: fileSectionSeparator
orientation: Qt.Horizontal
anchors.top: filesLoader.bottom
anchors.topMargin: 15
Expand All @@ -27,4 +28,13 @@ Rectangle {
anchors.right: parent.right
anchors.rightMargin: 10
}
// Layers Selection Panel
Loader {
id: layersLoader
width: parent.width
source: "LayersSelectionArea.qml"
anchors.top: fileSectionSeparator.bottom
anchors.left: parent.left
anchors.right: parent.right
}
}
101 changes: 68 additions & 33 deletions delphyne_gui/visualizer/maliput_viewer_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,11 @@ namespace delphyne {
namespace gui {
namespace {

// \returns True when @p keyword is found in @p word.
bool FoundKeyword(const std::string& word, const std::string& keyword) {
return word.find(keyword) != std::string::npos;
}

// \brief Returns the absolute path from @p fileUrl.
// \details `fileUrl` is expected to be conformed as:
// "file://" + "absolute path"
Expand Down Expand Up @@ -48,6 +53,25 @@ void MaliputViewerPlugin::OnNewRoadNetwork(const QString& _mapFile, const QStrin
trafficLightBookFile = GetPathFromFileUrl(_trafficLightBookFile.toStdString());
phaseRingBookFile = GetPathFromFileUrl(_phaseRingBookFile.toStdString());
model->Load(mapFile, roadRulebookFile, trafficLightBookFile, phaseRingBookFile);
emit LayerCheckboxesChanged();
RenderMeshes();
}

void MaliputViewerPlugin::OnNewMeshLayerSelection(const QString& _layer, bool _state) {
static constexpr char const* kAll{"all"};
const std::string layer{_layer.toStdString()};
const std::size_t all_keyword = layer.find(kAll);
// If the keyword "all" is found, enable all of the parsed type.
if (FoundKeyword(layer, kAll)) {
const std::string keyword = layer.substr(0, all_keyword);
for (auto const& it : this->model->Meshes()) {
if (FoundKeyword(it.first, keyword)) {
this->model->SetLayerState(it.first, _state);
}
}
} else {
this->model->SetLayerState(layer, _state);
}
RenderMeshes();
}

Expand Down Expand Up @@ -80,45 +104,56 @@ void MaliputViewerPlugin::RenderMeshes() {
void MaliputViewerPlugin::RenderRoadMeshes(const std::map<std::string, std::unique_ptr<MaliputMesh>>& _maliputMeshes) {
for (const auto& id_mesh : _maliputMeshes) {
ignmsg << "Rendering road mesh: " << id_mesh.first << std::endl;

// Checks if the mesh to be rendered already exists or not.
const auto meshExists = meshes.find(id_mesh.first);

if (!id_mesh.second->enabled) {
ignmsg << "Road mesh " << id_mesh.first << " is disabled." << std::endl;
// If the mesh already exists, set visibility to false.
if (meshExists != this->meshes.end()) {
meshes[id_mesh.first]->SetVisible(false);
}
continue;
}
ignition::rendering::VisualPtr visual;
// Creates a material for the visual.
ignition::rendering::MaterialPtr material = scene->CreateMaterial();
if (!material) {
ignerr << "Failed to create material.\n";
continue;
}
visual = scene->CreateVisual();
if (!visual) {
ignerr << "Failed to create visual.\n";
continue;
}
// Adds the visual to the map for later reference.
meshes[id_mesh.first] = visual;
// Sets the pose of the mesh.
visual->SetLocalPose(ignition::math::Pose3d(0, 0, 0, 1, 0, 0, 0));
// Loads the mesh into the visual.
if (id_mesh.second->mesh.get() == nullptr) {
ignerr << id_mesh.first << "'s mesh pointer is nullptr" << std::endl;
continue;
}
ignition::rendering::MeshDescriptor descriptor(id_mesh.second->mesh.get());
descriptor.Load();
ignition::rendering::MeshPtr meshGeom = scene->CreateMesh(descriptor);
visual->AddGeometry(meshGeom);
// Adds the mesh to the parent root visual.
rootVisual->AddChild(visual);
// If the mesh doesn't exist, it creates new one.
if (meshExists == this->meshes.end()) {
ignition::rendering::VisualPtr visual;
// Creates a material for the visual.
ignition::rendering::MaterialPtr material = scene->CreateMaterial();
if (!material) {
ignerr << "Failed to create material.\n";
continue;
}
visual = scene->CreateVisual();
if (!visual) {
ignerr << "Failed to create visual.\n";
continue;
}
// Adds the visual to the map for later reference.
meshes[id_mesh.first] = visual;
// Sets the pose of the mesh.
visual->SetLocalPose(ignition::math::Pose3d(0, 0, 0, 1, 0, 0, 0));
// Loads the mesh into the visual.
if (id_mesh.second->mesh.get() == nullptr) {
ignerr << id_mesh.first << "'s mesh pointer is nullptr" << std::endl;
continue;
}
ignition::rendering::MeshDescriptor descriptor(id_mesh.second->mesh.get());
descriptor.Load();
ignition::rendering::MeshPtr meshGeom = scene->CreateMesh(descriptor);
visual->AddGeometry(meshGeom);
// Adds the mesh to the parent root visual.
rootVisual->AddChild(visual);

// Applies the correct material to the mesh.
if (!FillMaterial(id_mesh.second->material.get(), material)) {
ignerr << "Failed to fill " << id_mesh.first << " material information.\n";
continue;
// Applies the correct material to the mesh.
if (!FillMaterial(id_mesh.second->material.get(), material)) {
ignerr << "Failed to fill " << id_mesh.first << " material information.\n";
continue;
}
visual->SetMaterial(material);
}
visual->SetMaterial(material);
visual->SetVisible(id_mesh.second->visible);
meshes.at(id_mesh.first)->SetVisible(id_mesh.second->visible);
}
}

Expand Down
19 changes: 19 additions & 0 deletions delphyne_gui/visualizer/maliput_viewer_plugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@ namespace gui {
class MaliputViewerPlugin : public ignition::gui::Plugin {
Q_OBJECT

/// Property used to load the default state of layers visualization in its correspondant UI's checkboxes.
Q_PROPERTY(QList<bool> layerCheckboxes READ LayerCheckboxes NOTIFY LayerCheckboxesChanged)

public:
/// \brief Default constructor.
MaliputViewerPlugin();
Expand All @@ -28,6 +31,11 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
/// \param[in] _pluginElem XML configuration for this plugin.
void LoadConfig(const tinyxml2::XMLElement* _pluginElem) override;

Q_INVOKABLE QList<bool> LayerCheckboxes() { return kDefaultLayersSelection; }
francocipollone marked this conversation as resolved.
Show resolved Hide resolved

signals:
void LayerCheckboxesChanged();
francocipollone marked this conversation as resolved.
Show resolved Hide resolved

protected:
/// @brief Timer event callback which handles the logic to load the meshes when
/// the scene is not ready yet.
Expand All @@ -42,6 +50,11 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
void OnNewRoadNetwork(const QString& _mapFile, const QString& _roadRulebookFile, const QString& _trafficLightBookFile,
const QString& _phaseRingBookFile);

/// \brief Change the visibility of the layers.
/// \param[in] _layer The layer to change its visibility.
/// \param[in] _state The state of the visibility checkbox.
void OnNewMeshLayerSelection(const QString& _layer, bool _state);

private:
/// @brief The period in milliseconds of the timer to try to load the meshes.
static constexpr int kTimerPeriodInMs{500};
Expand Down Expand Up @@ -86,6 +99,12 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
/// \brief Configurate scene.
void ConfigurateScene();

/// \brief Default layer selection for UI's checkboxes.
francocipollone marked this conversation as resolved.
Show resolved Hide resolved
const QList<bool> kDefaultLayersSelection{true /* asphalt */, true /* lane */,
true /* marker */, true /* h_bounds */,
true /* branchpoint */, false /* grayed_asphalt */,
false /* grayed_lane */, false /* grayed_marker */};

/// \brief Holds the map file path.
std::string mapFile{""};

Expand Down
1 change: 1 addition & 0 deletions delphyne_gui/visualizer/maliput_viewer_plugin.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,6 @@
<qresource prefix="MaliputViewerPlugin/">
<file>MaliputViewerPlugin.qml</file>
<file>FileSelectionArea.qml</file>
<file>LayersSelectionArea.qml</file>
</qresource>
</RCC>