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

GUI for adjusting FOV #1499

Closed
wants to merge 11 commits into from
49 changes: 49 additions & 0 deletions src/gui/plugins/view_angle/ViewAngle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
chapulina marked this conversation as resolved.
Show resolved Hide resolved

/// \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};

Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -307,6 +324,12 @@ QList<double> ViewAngle::CamClipDist() const
return this->dataPtr->camClipDist;
}

/////////////////////////////////////////////////
double ViewAngle::GetCamHFOV() const
{
return this->dataPtr->camHFOV;
}

/////////////////////////////////////////////////
void ViewAngle::SetCamClipDist(double _near, double _far)
{
Expand All @@ -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()
{
Expand Down Expand Up @@ -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));
}
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -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)
16 changes: 16 additions & 0 deletions src/gui/plugins/view_angle/ViewAngle.hh
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,12 @@ namespace gazebo
NOTIFY CamClipDistChanged
)

Q_PROPERTY(
double camHFOV
READ GetCamHFOV
chapulina marked this conversation as resolved.
Show resolved Hide resolved
NOTIFY CamHFOVChanged
)

/// \brief Constructor
public: ViewAngle();

Expand Down Expand Up @@ -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<ViewAnglePrivate> dataPtr;
Expand Down
35 changes: 35 additions & 0 deletions src/gui/plugins/view_angle/ViewAngle.qml
Original file line number Diff line number Diff line change
Expand Up @@ -391,6 +391,41 @@ ColumnLayout {
}
}

// Set camera's FOV
Text {
chapulina marked this conversation as resolved.
Show resolved Hide resolved
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)"
chapulina marked this conversation as resolved.
Show resolved Hide resolved
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
Expand Down