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

Allow to change camera user hfov in camera_view plugin #1807

Merged
merged 4 commits into from
Mar 3, 2023
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
51 changes: 51 additions & 0 deletions src/gui/plugins/view_angle/ViewAngle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <ignition/gui/Application.hh>
#include <ignition/gui/GuiEvents.hh>
#include <ignition/gui/MainWindow.hh>
#include <ignition/math/Angle.hh>
#include <ignition/plugin/Register.hh>
#include <ignition/rendering/MoveToHelper.hh>
#include <ignition/rendering/RenderingIface.hh>
Expand Down Expand Up @@ -78,6 +79,13 @@ namespace ignition::gazebo
/// \brief Distance of the camera to the model
public: double distanceMoveToModel = 0.0;

/// \brief Camera horizontal fov
public: double horizontalFov = 0.0;

/// \brief Flag indicating if there is a new camera horizontalFOV
/// coming from qml side
public: bool newHorizontalFOV = false;

/// \brief gui camera pose
public: math::Pose3d camPose;

Expand All @@ -101,6 +109,11 @@ namespace ignition::gazebo
/// \return True if there is a new view controller from gui camera
public: bool UpdateQtViewControl();

/// \brief Checks if there is new camera horizontal fov from gui camera,
/// used to update qml side
/// \return True if there is a new horizontal fov from gui camera
public: bool UpdateQtCamHorizontalFOV();

/// \brief User camera
public: rendering::CameraPtr camera{nullptr};

Expand Down Expand Up @@ -203,6 +216,12 @@ bool ViewAngle::eventFilter(QObject *_obj, QEvent *_event)
this->CamClipDistChanged();
}

// updates qml cam horizontal fov spin boxes if changed
if (this->dataPtr->UpdateQtCamHorizontalFOV())
{
this->CamHorizontalFOVChanged();
}

if (this->dataPtr->UpdateQtViewControl())
{
this->ViewControlIndexChanged();
Expand Down Expand Up @@ -462,6 +481,19 @@ void ViewAngle::CamPoseCb(const msgs::Pose &_msg)
}
}

/////////////////////////////////////////////////
double ViewAngle::HorizontalFOV() const
{
return this->dataPtr->horizontalFov;
}

/////////////////////////////////////////////////
void ViewAngle::SetHorizontalFOV(double _horizontalFOV)
{
this->dataPtr->horizontalFov = _horizontalFOV;
this->dataPtr->newHorizontalFOV = true;
}

/////////////////////////////////////////////////
QList<double> ViewAngle::CamClipDist() const
{
Expand Down Expand Up @@ -596,6 +628,13 @@ void ViewAnglePrivate::OnRender()
this->camera->SetFarClipPlane(this->camClipDist[1]);
this->newCamClipDist = false;
}

// Camera horizontalFOV
if (this->newHorizontalFOV)
{
this->camera->SetHFOV(gz::math::Angle(this->horizontalFov));
this->newHorizontalFOV = false;
}
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -634,6 +673,18 @@ void ViewAnglePrivate::OnComplete()
}
}

/////////////////////////////////////////////////
bool ViewAnglePrivate::UpdateQtCamHorizontalFOV()
{
bool updated = false;
if (std::abs(this->camera->HFOV().Radian() - this->horizontalFov) > 0.0001)
{
this->horizontalFov = this->camera->HFOV().Radian();
updated = true;
}
return updated;
}

/////////////////////////////////////////////////
bool ViewAnglePrivate::UpdateQtCamClipDist()
{
Expand Down
17 changes: 17 additions & 0 deletions src/gui/plugins/view_angle/ViewAngle.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,13 @@ namespace gazebo
NOTIFY ViewControlIndexChanged
)

/// \brief gui camera horizontal fov
Q_PROPERTY(
double horizontalFOV
READ HorizontalFOV
NOTIFY CamHorizontalFOVChanged
)

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

Expand Down Expand Up @@ -98,6 +105,16 @@ namespace gazebo
/// \param[in] _sensitivity View control sensitivity vlaue
public slots: void OnViewControlSensitivity(double _sensitivity);

/// \brief Updates gui camera's Horizontal fov
/// \param[in] _horizontalFOV Horizontal fov
public slots: void SetHorizontalFOV(double _horizontalFOV);

/// \brief Get the current gui horizontal fov.
public: Q_INVOKABLE double HorizontalFOV() const;

/// \brief Notify that the gui camera's horizontal fov changed
signals: void CamHorizontalFOVChanged();

/// \brief Get the current gui camera pose.
public: Q_INVOKABLE QList<double> CamPose() const;

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 @@ -326,6 +326,41 @@ ColumnLayout {
}
}

// Set camera's horizontal FOV
Text {
text: "Horizontal FOV"
Layout.fillWidth: true
color: Material.Grey
leftPadding: 5
topPadding: 10
font.bold: true
}

GridLayout {
width: parent.width
columns: 2

Text {
text: "HorizontalFOV (rads)"
color: "dimgrey"
Layout.row: 0
Layout.column: 0
leftPadding: 5
}
IgnSpinBox {
id: horizontalFOV
Layout.fillWidth: true
Layout.row: 0
Layout.column: 1
value: ViewAngle.horizontalFOV
maximumValue: 3.14159
minimumValue: 0.000001
decimals: 6
stepSize: 0.01
onEditingFinished: ViewAngle.SetHorizontalFOV(horizontalFOV.value)
}
}

// Bottom spacer
Item {
width: 10
Expand Down