From fa159957cf0babe740e54b269260c8d14a0a2e2c Mon Sep 17 00:00:00 2001 From: youhy Date: Wed, 18 May 2022 10:01:13 -0700 Subject: [PATCH 1/4] FOV gui in viewangle plugin Signed-off-by: youhy --- src/gui/plugins/view_angle/ViewAngle.cc | 49 ++++++++++++++++++++++++ src/gui/plugins/view_angle/ViewAngle.hh | 16 ++++++++ src/gui/plugins/view_angle/ViewAngle.qml | 35 +++++++++++++++++ 3 files changed, 100 insertions(+) diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index 8f3b34f431..c9e7a5f90c 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -73,11 +73,23 @@ namespace ignition::gazebo /// coming from qml side public: bool newCamClipDist = false; + /// \brief GUI camera horizontal FOV in degree + public: double camHFOV = 0; + + /// \brief Flag indicating if there is a new camera horizontal FOV + /// coming from qml + public: bool newCamHFOV = false; + /// \brief Checks if there is new camera clipping distance from gui camera, /// used to update qml side /// \return True if there is a new clipping distance from gui camera public: bool UpdateQtCamClipDist(); + /// \brief Checks if there is a new camera horizontal FOV from gui camera, + /// used to update qml side + /// \return True if there is a new camera horizontal FOV from gui camera + public: bool UpdateQtCamHFOV(); + /// \brief User camera public: rendering::CameraPtr camera{nullptr}; @@ -164,6 +176,11 @@ bool ViewAngle::eventFilter(QObject *_obj, QEvent *_event) { this->CamClipDistChanged(); } + + if (this->dataPtr->UpdateQtCamHFOV()) + { + this->CamHFOVChanged(); + } } else if (_event->type() == ignition::gazebo::gui::events::EntitiesSelected::kType) @@ -307,6 +324,12 @@ QList ViewAngle::CamClipDist() const return this->dataPtr->camClipDist; } +///////////////////////////////////////////////// +double ViewAngle::GetCamHFOV() const +{ + return this->dataPtr->camHFOV; +} + ///////////////////////////////////////////////// void ViewAngle::SetCamClipDist(double _near, double _far) { @@ -315,6 +338,13 @@ void ViewAngle::SetCamClipDist(double _near, double _far) this->dataPtr->newCamClipDist = true; } +///////////////////////////////////////////////// +void ViewAngle::SetCamHFOV(double _fovDeg) +{ + this->dataPtr->camHFOV = _fovDeg; + this->dataPtr->newCamHFOV = true; +} + ///////////////////////////////////////////////// void ViewAnglePrivate::OnRender() { @@ -435,6 +465,12 @@ void ViewAnglePrivate::OnRender() this->camera->SetFarClipPlane(this->camClipDist[1]); this->newCamClipDist = false; } + + if (this->newCamHFOV) + { + // camera used Radian but GUI uses degree. + this->camera->SetHFOV(IGN_DTOR(this->camHFOV)); + } } ///////////////////////////////////////////////// @@ -462,6 +498,19 @@ bool ViewAnglePrivate::UpdateQtCamClipDist() return updated; } +///////////////////////////////////////////////// +bool ViewAnglePrivate::UpdateQtCamHFOV() +{ + bool updated = false; + if (std::abs(this->camera->HFOV().Degree() - this->camHFOV) > 0.1) + { + this->camHFOV = this->camera->HFOV().Degree(); + updated = true; + } + return updated; +} + + // Register this plugin IGNITION_ADD_PLUGIN(ignition::gazebo::ViewAngle, ignition::gui::Plugin) diff --git a/src/gui/plugins/view_angle/ViewAngle.hh b/src/gui/plugins/view_angle/ViewAngle.hh index 155d16ae2e..838de913ba 100644 --- a/src/gui/plugins/view_angle/ViewAngle.hh +++ b/src/gui/plugins/view_angle/ViewAngle.hh @@ -54,6 +54,12 @@ namespace gazebo NOTIFY CamClipDistChanged ) + Q_PROPERTY( + double camHFOV + READ GetCamHFOV + NOTIFY CamHFOVChanged + ) + /// \brief Constructor public: ViewAngle(); @@ -106,6 +112,16 @@ namespace gazebo /// \param[in] _far Far clipping plane distance public slots: void SetCamClipDist(double _near, double _far); + /// \brief Get the current GUI camera's horizontal FOV + public: Q_INVOKABLE double GetCamHFOV() const; + + /// \brief Notify that the GUI camera's horizontal FOV changed + signals: void CamHFOVChanged(); + + /// \brief Update gui camera's FOV + /// \param[in] _fovDeg Horizontal FOV of the camera in degree + public slots: void SetCamHFOV(double _fovDeg); + /// \internal /// \brief Pointer to private data. private: std::unique_ptr dataPtr; diff --git a/src/gui/plugins/view_angle/ViewAngle.qml b/src/gui/plugins/view_angle/ViewAngle.qml index d0839a811a..57a437eb15 100644 --- a/src/gui/plugins/view_angle/ViewAngle.qml +++ b/src/gui/plugins/view_angle/ViewAngle.qml @@ -391,6 +391,41 @@ ColumnLayout { } } + // Set camera's FOV + Text { + text: "Camera FOV" + Layout.fillWidth: true + color: Material.Grey + leftPadding: 5 + topPadding: 10 + font.bold: true + } + + GridLayout { + width: parent.width + columns: 4 + + Text { + text: "horizontal fov (degree)" + color: "dimgrey" + Layout.row: 0 + Layout.column: 0 + leftPadding: 5 + } + IgnSpinBox { + id: hfov + Layout.fillWidth: true + Layout.row: 0 + Layout.column: 1 + value: ViewAngle.camHFOV + maximumValue: 170 + minimumValue: 10 + decimals: 1 + stepSize: 10 + onEditingFinished: ViewAngle.SetCamHFOV(hfov.value) + } + } + // Bottom spacer Item { width: 10 From f7592a3ece11fd8868d97ee292ddd991000b1ce3 Mon Sep 17 00:00:00 2001 From: youhy Date: Thu, 19 May 2022 07:44:17 -0700 Subject: [PATCH 2/4] GUI minor changes Signed-off-by: youhy --- src/gui/plugins/view_angle/ViewAngle.cc | 2 +- src/gui/plugins/view_angle/ViewAngle.hh | 4 ++-- src/gui/plugins/view_angle/ViewAngle.qml | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index c9e7a5f90c..ab534e6d40 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -325,7 +325,7 @@ QList ViewAngle::CamClipDist() const } ///////////////////////////////////////////////// -double ViewAngle::GetCamHFOV() const +double ViewAngle::CamHFOV() const { return this->dataPtr->camHFOV; } diff --git a/src/gui/plugins/view_angle/ViewAngle.hh b/src/gui/plugins/view_angle/ViewAngle.hh index 838de913ba..c8b963c615 100644 --- a/src/gui/plugins/view_angle/ViewAngle.hh +++ b/src/gui/plugins/view_angle/ViewAngle.hh @@ -56,7 +56,7 @@ namespace gazebo Q_PROPERTY( double camHFOV - READ GetCamHFOV + READ CamHFOV NOTIFY CamHFOVChanged ) @@ -113,7 +113,7 @@ namespace gazebo public slots: void SetCamClipDist(double _near, double _far); /// \brief Get the current GUI camera's horizontal FOV - public: Q_INVOKABLE double GetCamHFOV() const; + public: Q_INVOKABLE double CamHFOV() const; /// \brief Notify that the GUI camera's horizontal FOV changed signals: void CamHFOVChanged(); diff --git a/src/gui/plugins/view_angle/ViewAngle.qml b/src/gui/plugins/view_angle/ViewAngle.qml index 57a437eb15..c50344170e 100644 --- a/src/gui/plugins/view_angle/ViewAngle.qml +++ b/src/gui/plugins/view_angle/ViewAngle.qml @@ -24,7 +24,7 @@ import "qrc:/qml" ColumnLayout { Layout.minimumWidth: 320 - Layout.minimumHeight: 530 + Layout.minimumHeight: 600 anchors.fill: parent ToolBar { @@ -406,7 +406,7 @@ ColumnLayout { columns: 4 Text { - text: "horizontal fov (degree)" + text: "Horizontal Fov (degree)" color: "dimgrey" Layout.row: 0 Layout.column: 0 From 19f125901805b968710a7b4e78570156b76b6117 Mon Sep 17 00:00:00 2001 From: youhy Date: Fri, 20 May 2022 15:34:50 -0700 Subject: [PATCH 3/4] add newCamHFOV reset Signed-off-by: youhy --- src/gui/plugins/view_angle/ViewAngle.cc | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index ab534e6d40..974b5fa9ee 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -387,6 +387,14 @@ void ViewAnglePrivate::OnRender() } } + // Update HFOV + if (this->newCamHFOV) + { + // camera used Radian but GUI uses degree. + this->camera->SetHFOV(IGN_DTOR(this->camHFOV)); + this->newCamHFOV = false; + } + // View angle if (this->viewingAngle) { @@ -465,12 +473,6 @@ void ViewAnglePrivate::OnRender() this->camera->SetFarClipPlane(this->camClipDist[1]); this->newCamClipDist = false; } - - if (this->newCamHFOV) - { - // camera used Radian but GUI uses degree. - this->camera->SetHFOV(IGN_DTOR(this->camHFOV)); - } } ///////////////////////////////////////////////// From dcbdfd72815728a07d2fe1a710b1522bea1aea31 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 15 Jun 2022 12:32:11 -0700 Subject: [PATCH 4/4] Depend on rendering 6.5 Signed-off-by: Louise Poubel --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4b9ff4329a..32be95b693 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -147,7 +147,7 @@ set(IGN_SENSORS_VER ${ignition-sensors6_VERSION_MAJOR}) #-------------------------------------- # Find ignition-rendering -ign_find_package(ignition-rendering6 REQUIRED VERSION 6.3) +ign_find_package(ignition-rendering6 REQUIRED VERSION 6.5) set(IGN_RENDERING_VER ${ignition-rendering6_VERSION_MAJOR}) #--------------------------------------