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

OriginGrid plugin: Sync with Render event. #473

Merged
merged 3 commits into from
Oct 7, 2021
Merged
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
49 changes: 32 additions & 17 deletions delphyne_gui/visualizer/display_plugins/origin_display.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@
#include <cmath>

#include <ignition/common/Console.hh>
#include <ignition/gui/Application.hh>
#include <ignition/gui/GuiEvents.hh>
#include <ignition/gui/MainWindow.hh>
#include <ignition/math/Color.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/plugin/Register.hh>
Expand All @@ -29,23 +32,30 @@ void OriginDisplay::LoadConfig(const tinyxml2::XMLElement* _pluginElem) {
IsVisibleChanged();
}
}
// Install event filter.
ignition::gui::App()->findChild<ignition::gui::MainWindow*>()->installEventFilter(this);

// Get the render engine.
// Note: we don't support other engines than Ogre.
auto engine = ignition::rendering::engine(kEngineName);
if (!engine) {
ignerr << "Engine \"" << kEngineName << "\" not supported, origin display plugin won't work." << std::endl;
return;
}
// Get the scene.
auto scene = engine->SceneByName(sceneName);
if (!scene) {
ignwarn << "Scene \"" << sceneName << "\" not found, origin display plugin won't work until the scene is created."
<< " Trying again in " << kTimerPeriodInMs << "ms" << std::endl;
timer.start(kTimerPeriodInMs, this);
return;
// Set timer to get the scene.
timer.start(kTimerPeriodInMs, this);
}

bool OriginDisplay::eventFilter(QObject* _obj, QEvent* _event) {
// Hooking to the Render event to safely make rendering calls.
// See https://github.com/ignitionrobotics/ign-gui/blob/ign-gui3/include/ignition/gui/GuiEvents.hh#L36-L37
if (_event->type() == ignition::gui::events::Render::kType) {
if (scene != nullptr) {
if (!areAxesDrawn) {
this->DrawAxes(scene);
areAxesDrawn = true;
}
if (isDirty) {
ChangeAxesVisibility();
isDirty = false;
}
}
}
DrawAxes(scene);
// Standard event processing
return QObject::eventFilter(_obj, _event);
}

void OriginDisplay::timerEvent(QTimerEvent* _event) {
Expand All @@ -56,14 +66,19 @@ void OriginDisplay::timerEvent(QTimerEvent* _event) {
// Get the render engine.
// Note: we don't support other engines than Ogre.
auto engine = ignition::rendering::engine(kEngineName);
auto scene = engine->SceneByName(sceneName);
scene = engine->SceneByName(sceneName);
if (!scene) {
ignwarn << "Scene \"" << sceneName << "\" not found yet. Trying again in "
<< " Trying again in " << kTimerPeriodInMs << "ms" << std::endl;
return;
}
timer.stop();
DrawAxes(scene);
}

void OriginDisplay::SetIsVisible(bool _isVisible) {
isVisible = _isVisible;
IsVisibleChanged();
isDirty = true;
}

void OriginDisplay::DrawAxes(ignition::rendering::ScenePtr scene) {
Expand Down
26 changes: 18 additions & 8 deletions delphyne_gui/visualizer/display_plugins/origin_display.hh
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
#pragma once

#include <array>
#include <atomic>
#include <string>

#include <ignition/gui/Plugin.hh>
Expand Down Expand Up @@ -39,21 +40,21 @@ class OriginDisplay : public ignition::gui::Plugin {
/// @{ isVisible accessors.
Q_INVOKABLE bool IsVisible() const { return isVisible; }

Q_INVOKABLE void SetIsVisible(bool _isVisible) {
isVisible = _isVisible;
IsVisibleChanged();
ChangeAxesVisibility();
}
Q_INVOKABLE void SetIsVisible(bool _isVisible);
/// @}

signals:
void IsVisibleChanged();

protected:
/// @brief Timer event callback which handles the logic to draw the axes when
/// the scene is not ready yet.
/// @brief Timer event callback which handles the logic to get the scene.
void timerEvent(QTimerEvent* _event) override;

/// \brief Filters ignition::gui::events::Render events to update the visualization of the axis if needed.
/// \details To make this method be called by Qt Event System, install the event filter in target object.
/// \see QObject::installEventFilter() method.
bool eventFilter(QObject* _obj, QEvent* _event) override;

private:
/// @brief The period in milliseconds of the timer to try to draw the axes.
static constexpr int kTimerPeriodInMs{500};
Expand All @@ -68,7 +69,7 @@ class OriginDisplay : public ignition::gui::Plugin {
/// @brief Toggles the visibility of the axes.
void ChangeAxesVisibility();

/// @brief Triggers an event every `kTimerPeriodInMs` to try to draw the axes.
/// @brief Triggers an event every `kTimerPeriodInMs` to try to get the scene.
QBasicTimer timer;

/// @brief The scene name.
Expand All @@ -79,6 +80,15 @@ class OriginDisplay : public ignition::gui::Plugin {

/// @brief Pointers to the visual axes
std::array<ignition::rendering::VisualPtr, 3> axes{nullptr, nullptr, nullptr};

/// @brief Indicates whether the axes are drawn.
std::atomic<bool> areAxesDrawn{false};

/// @brief Indicates whether the axes visibility should be updated.
std::atomic<bool> isDirty{true};

/// @brief Holds a pointer to the scene.
ignition::rendering::ScenePtr scene{nullptr};
};

} // namespace gui
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -464,51 +464,27 @@ void MaliputViewerPlugin::LoadConfig(const tinyxml2::XMLElement* _pluginElem) {
return;
}

// Initialization process based on Grid3D plugin implementation.
// See https://github.com/ignitionrobotics/ign-gui/blob/ign-gui3/src/plugins/grid_3d/Grid3D.cc#L187.
this->connect(this->PluginItem(), &QQuickItem::windowChanged, [this](QQuickWindow* _window) {
if (!_window) {
igndbg << "Changed to null window" << std::endl;
return;
}

this->quickWindow = _window;
// Install event filter.
ignition::gui::App()->findChild<ignition::gui::MainWindow*>()->installEventFilter(this);

// Initialize after Scene3D plugins
this->connect(this->quickWindow, &QQuickWindow::beforeRendering, this, &MaliputViewerPlugin::Initialize,
Qt::DirectConnection);
});
// Set timer to get the scene.
timer.start(kTimerPeriodInMs, this);
}

void MaliputViewerPlugin::Initialize() {
// Get engine.
auto loadedEngNames = ignition::rendering::loadedEngines();
if (loadedEngNames.empty()) {
// Keep trying until an engine is loaded
void MaliputViewerPlugin::timerEvent(QTimerEvent* _event) {
if (_event->timerId() != timer.timerId()) {
return;
}
if (this->engine == nullptr) this->engine = ignition::rendering::engine(this->kEngineName);

if (this->engine == nullptr) {
ignerr << "Failed to get engine [" + std::string(this->kEngineName) + "]" << std::endl;

this->disconnect(this->quickWindow, &QQuickWindow::beforeRendering, this, &MaliputViewerPlugin::Initialize);

return;
}
if (this->engine->SceneCount() == 0) {
// Scene may not be loaded yet, keep trying
return;
}
// Get the scene.
// Get the render engine.
// Note: we don't support other engines than Ogre.
auto engine = ignition::rendering::engine(kEngineName);
scene = engine->SceneByName(kSceneName);
if (!scene) {
ignwarn << "Scene \"" << kSceneName << "\" not found, meshes won't be loaded until the scene is created."
<< std::endl;
// Scene may not be loaded yet, keep trying
ignwarn << "Scene \"" << kSceneName << "\" not found yet. Trying again in "
<< " Trying again in " << kTimerPeriodInMs << "ms" << std::endl;
return;
}

// Get root visual.
rootVisual = scene->RootVisual();
if (!rootVisual) {
Expand All @@ -525,15 +501,9 @@ void MaliputViewerPlugin::Initialize() {
ignwarn << "Failed to find the camera, trying again" << std::endl;
return;
}

// Install event filter.
ignition::gui::App()->findChild<ignition::gui::MainWindow*>()->installEventFilter(this);

// Disconnect method.
this->disconnect(this->quickWindow, &QQuickWindow::beforeRendering, this, &MaliputViewerPlugin::Initialize);

setUpScene = true;
ignmsg << "MaliputViewerPlugin has been initialized." << std::endl;
timer.stop();
}

ignition::gui::Plugin* MaliputViewerPlugin::FilterPluginsByTitle(const std::string& _pluginTitle) {
Expand Down Expand Up @@ -574,7 +544,7 @@ void MaliputViewerPlugin::SetUpScene() {
}

bool MaliputViewerPlugin::eventFilter(QObject* _obj, QEvent* _event) {
if (isRoadNetworkLoaded) {
if (this->scene != nullptr && isRoadNetworkLoaded) {
if (_event->type() == ignition::gui::events::LeftClickToScene::kType) {
auto leftClickToScene = static_cast<ignition::gui::events::LeftClickToScene*>(_event);
// TODO(https://github.com/ignitionrobotics/ign-gui/issues/209): use distance to camera once
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -146,13 +146,16 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
void tableLaneIdSelection(int _index);

protected:
/// \brief Filters QMouseEvents from a Scene3D plugin whose title matches with `<main_scene_plugin_title>`.
/// \brief Filters ignition::gui::events::LeftClickToScene to get the clicks events.
/// Filters ignition::gui::events::Render events to update the meshes and labels of the roads and the animation
/// of the arrow mesh.
/// \details To make this method be called by Qt Event System, install the event filter in target object.
/// \see QObject::installEventFilter() method.
bool eventFilter(QObject* _obj, QEvent* _event) override;

/// @brief Timer event callback which handles the logic to get the scene.
void timerEvent(QTimerEvent* _event) override;

protected slots:
/// \brief Clears the visualizer, loads a RoadNetwork and update the GUI with meshes and labels.
/// \param[in] _mapFile The path to the map file to load and visualize.
Expand Down Expand Up @@ -184,12 +187,12 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
/// @brief The scene name.
static constexpr char const* kSceneName = "scene";

/// @brief The Scene3D instance holding the main scene.
static constexpr char const* kMainScene3dPlugin = "Main3DScene";

/// @brief The rendering engine name.
static constexpr char const* kEngineName = "ogre";

/// @brief The period in milliseconds of the timer to try to get the scene.
static constexpr int kTimerPeriodInMs{500};

/// \brief Holds a maliput::api::RoadPositionResult which results from the
/// mapped scene click position into the Inertial frame and the
/// distance to the camera.
Expand Down Expand Up @@ -269,9 +272,6 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
/// \brief Clears all the references to text labels, meshes and the scene.
void Clear();

/// \brief Get properties from the scene and install event filter for filtering QMouseEvents.
void Initialize();

/// \brief Set up the scene modifying the light and instantiating the ArrowMesh, Selector and TrafficLightManager.
void SetUpScene();

Expand All @@ -284,12 +284,6 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
/// \brief Handles the left click mouse event and populates roadPositionResultValue.
void UpdateLaneSelectionOnLeftClick();

/// \brief Performs a raycast on the screen.
/// \param[in] screenX X screen's coordinate.
/// \param[in] screenY Y screen's coordinate.
/// \return A ignition::rendering::RayQueryResult.
ignition::rendering::RayQueryResult ScreenToScene(int _screenX, int _screenY) const;

/// \brief Filters by title all the children of the parent plugin.
/// \param _pluginTitle Title of the ignition::gui::plugin.
/// \return A pointer to the plugin if found, nullptr otherwise.
Expand Down Expand Up @@ -368,6 +362,9 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
/// \brief Holds the info about the clicked surface that is displayed in the UI.
QString laneInfo{};

/// @brief Triggers an event every `kTimerPeriodInMs` to try to get the scene.
QBasicTimer timer;

/// \brief Holds the model of the tree view table where the phases are listed.
PhaseTreeModel phaseTreeModel{this};

Expand All @@ -386,18 +383,9 @@ class MaliputViewerPlugin : public ignition::gui::Plugin {
/// \brief A map that contains the default of the checkbox for meshes and labels.
std::unordered_map<std::string, bool> objectVisualDefaults;

/// \brief Pointer to the render engine.
ignition::rendering::RenderEngine* engine{nullptr};

/// \brief Pointer to the QuickWindow instance.
QQuickWindow* quickWindow{nullptr};

/// \brief Holds a pointer to the scene.
ignition::rendering::ScenePtr scene{nullptr};

/// \brief Holds a pointer to a ray query.
ignition::rendering::RayQueryPtr rayQuery{nullptr};

/// \brief Holds a pointer to the camera.
ignition::rendering::CameraPtr camera{};

Expand Down