diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index b4fc5d014f..8f3b34f431 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -66,6 +66,18 @@ namespace ignition::gazebo /// \brief gui camera pose public: math::Pose3d camPose; + /// \brief GUI camera near/far clipping distance (QList order is near, far) + public: QList camClipDist{0.0, 0.0}; + + /// \brief Flag indicating if there is a new camera clipping distance + /// coming from qml side + public: bool newCamClipDist = 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 User camera public: rendering::CameraPtr camera{nullptr}; @@ -146,6 +158,12 @@ bool ViewAngle::eventFilter(QObject *_obj, QEvent *_event) if (_event->type() == ignition::gui::events::Render::kType) { this->dataPtr->OnRender(); + + // updates qml cam clip distance spin boxes if changed + if (this->dataPtr->UpdateQtCamClipDist()) + { + this->CamClipDistChanged(); + } } else if (_event->type() == ignition::gazebo::gui::events::EntitiesSelected::kType) @@ -283,6 +301,20 @@ void ViewAngle::CamPoseCb(const msgs::Pose &_msg) } } +///////////////////////////////////////////////// +QList ViewAngle::CamClipDist() const +{ + return this->dataPtr->camClipDist; +} + +///////////////////////////////////////////////// +void ViewAngle::SetCamClipDist(double _near, double _far) +{ + this->dataPtr->camClipDist[0] = _near; + this->dataPtr->camClipDist[1] = _far; + this->dataPtr->newCamClipDist = true; +} + ///////////////////////////////////////////////// void ViewAnglePrivate::OnRender() { @@ -395,6 +427,14 @@ void ViewAnglePrivate::OnRender() this->prevMoveToTime = now; } } + + // Camera clipping plane distance + if (this->newCamClipDist) + { + this->camera->SetNearClipPlane(this->camClipDist[0]); + this->camera->SetFarClipPlane(this->camClipDist[1]); + this->newCamClipDist = false; + } } ///////////////////////////////////////////////// @@ -404,6 +444,24 @@ void ViewAnglePrivate::OnComplete() this->moveToPoseValue.reset(); } +///////////////////////////////////////////////// +bool ViewAnglePrivate::UpdateQtCamClipDist() +{ + bool updated = false; + if (std::abs(this->camera->NearClipPlane() - this->camClipDist[0]) > 0.0001) + { + this->camClipDist[0] = this->camera->NearClipPlane(); + updated = true; + } + + if (std::abs(this->camera->FarClipPlane() - this->camClipDist[1]) > 0.0001) + { + this->camClipDist[1] = this->camera->FarClipPlane(); + 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 e209b729bc..155d16ae2e 100644 --- a/src/gui/plugins/view_angle/ViewAngle.hh +++ b/src/gui/plugins/view_angle/ViewAngle.hh @@ -47,6 +47,13 @@ namespace gazebo NOTIFY CamPoseChanged ) + /// \brief gui camera near/far clipping distance (QList order is near, far) + Q_PROPERTY( + QList camClipDist + READ CamClipDist + NOTIFY CamClipDistChanged + ) + /// \brief Constructor public: ViewAngle(); @@ -88,6 +95,17 @@ namespace gazebo /// \param[in] _msg Pose message public: void CamPoseCb(const msgs::Pose &_msg); + /// \brief Get the current gui camera's near and far clipping distances + public: Q_INVOKABLE QList CamClipDist() const; + + /// \brief Notify that the gui camera's near/far clipping distances changed + signals: void CamClipDistChanged(); + + /// \brief Updates gui camera's near/far clipping distances + /// \param[in] _near Near clipping plane distance + /// \param[in] _far Far clipping plane distance + public slots: void SetCamClipDist(double _near, double _far); + /// \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 54a2de4dbc..9f7213f488 100644 --- a/src/gui/plugins/view_angle/ViewAngle.qml +++ b/src/gui/plugins/view_angle/ViewAngle.qml @@ -213,6 +213,7 @@ ColumnLayout { Layout.fillWidth: true color: Material.Grey leftPadding: 5 + font.bold: true } GridLayout { @@ -336,6 +337,60 @@ ColumnLayout { } } + // Set camera's near/far clipping distance + Text { + text: "Camera's clipping plane distance" + Layout.fillWidth: true + color: Material.Grey + leftPadding: 5 + topPadding: 10 + font.bold: true + } + + GridLayout { + width: parent.width + columns: 4 + + Text { + text: "Near (m)" + color: "dimgrey" + Layout.row: 0 + Layout.column: 0 + leftPadding: 5 + } + IgnSpinBox { + id: nearClip + Layout.fillWidth: true + Layout.row: 0 + Layout.column: 1 + value: ViewAngle.camClipDist[0] + maximumValue: farClip.value + minimumValue: 0.000001 + decimals: 6 + stepSize: 0.01 + onEditingFinished: ViewAngle.SetCamClipDist(nearClip.value, farClip.value) + } + Text { + text: "Far (m)" + color: "dimgrey" + Layout.row: 0 + Layout.column: 2 + leftPadding: 5 + } + IgnSpinBox { + id: farClip + Layout.fillWidth: true + Layout.row: 0 + Layout.column: 3 + value: ViewAngle.camClipDist[1] + maximumValue: 1000000 + minimumValue: nearClip.value + decimals: 6 + stepSize: 0.01 + onEditingFinished: ViewAngle.SetCamClipDist(nearClip.value, farClip.value) + } + } + // Bottom spacer Item { width: 10