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

Add view control gui plugin and support orthographic view #815

Merged
merged 4 commits into from
May 24, 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
88 changes: 78 additions & 10 deletions src/gui/plugins/scene3d/Scene3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@

#include <ignition/rendering/Image.hh>
#include <ignition/rendering/OrbitViewController.hh>
#include <ignition/rendering/OrthoViewController.hh>
#include <ignition/rendering/RayQuery.hh>
#include <ignition/rendering/RenderEngine.hh>
#include <ignition/rendering/RenderingIface.hh>
Expand Down Expand Up @@ -184,8 +185,14 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief User camera
public: rendering::CameraPtr camera;

/// \brief Camera orbit controller
public: rendering::OrbitViewController viewControl;
/// \brief Orbit view controller
public: rendering::OrbitViewController orbitViewControl;

/// \brief Ortho view controller
public: rendering::OrthoViewController orthoViewControl;

/// \brief Camera view controller
public: rendering::ViewController *viewControl{nullptr};

/// \brief Transform controller for models
public: rendering::TransformController transformControl;
Expand Down Expand Up @@ -239,6 +246,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Target to view collisions
public: std::string viewCollisionsTarget;

/// \brief View controller
public: std::string viewController{"orbit"};

/// \brief Helper object to select entities. Only the latest selection
/// request is kept.
public: SelectionHelper selectionHelper;
Expand Down Expand Up @@ -443,6 +453,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {

/// \brief View collisions service
public: std::string viewCollisionsService;

/// \brief Camera view control service
public: std::string cameraViewControlService;
};
}
}
Expand Down Expand Up @@ -503,6 +516,9 @@ void IgnRenderer::Render()
IGN_PROFILE("IgnRenderer::Render Pre-render camera");
this->dataPtr->camera->PreRender();
}
// mark mouse dirty to force update view projection in HandleMouseEvent
this->dataPtr->mouseDirty = true;

this->textureDirty = false;
}

Expand Down Expand Up @@ -1716,39 +1732,54 @@ void IgnRenderer::HandleMouseViewControl()
if (!this->dataPtr->followTarget.empty())
this->dataPtr->camera->WorldPosition();

this->dataPtr->viewControl.SetCamera(this->dataPtr->camera);
if (this->dataPtr->viewController == "ortho")
{
this->dataPtr->viewControl = &this->dataPtr->orthoViewControl;
}
else if (this->dataPtr->viewController == "orbit")
{
this->dataPtr->viewControl = &this->dataPtr->orbitViewControl;
}
else
{
ignerr << "Unknown view controller: " << this->dataPtr->viewController
<< ". Defaulting to orbit view controller" << std::endl;
this->dataPtr->viewController = "orbit";
this->dataPtr->viewControl = &this->dataPtr->orbitViewControl;
}
this->dataPtr->viewControl->SetCamera(this->dataPtr->camera);

if (this->dataPtr->mouseEvent.Type() == common::MouseEvent::SCROLL)
{
this->dataPtr->target =
this->ScreenToScene(this->dataPtr->mouseEvent.Pos());
this->dataPtr->viewControl.SetTarget(this->dataPtr->target);
this->dataPtr->viewControl->SetTarget(this->dataPtr->target);
double distance = this->dataPtr->camera->WorldPosition().Distance(
this->dataPtr->target);
double amount = -this->dataPtr->drag.Y() * distance / 5.0;
this->dataPtr->viewControl.Zoom(amount);
this->dataPtr->viewControl->Zoom(amount);
}
else
{
if (this->dataPtr->mouseEvent.Type() == common::MouseEvent::PRESS)
{
this->dataPtr->target = this->ScreenToScene(
this->dataPtr->mouseEvent.PressPos());
this->dataPtr->viewControl.SetTarget(this->dataPtr->target);
this->dataPtr->viewControl->SetTarget(this->dataPtr->target);
}

// Pan with left button
if (this->dataPtr->mouseEvent.Buttons() & common::MouseEvent::LEFT)
{
if (Qt::ShiftModifier == QGuiApplication::queryKeyboardModifiers())
this->dataPtr->viewControl.Orbit(this->dataPtr->drag);
this->dataPtr->viewControl->Orbit(this->dataPtr->drag);
else
this->dataPtr->viewControl.Pan(this->dataPtr->drag);
this->dataPtr->viewControl->Pan(this->dataPtr->drag);
}
// Orbit with middle button
else if (this->dataPtr->mouseEvent.Buttons() & common::MouseEvent::MIDDLE)
{
this->dataPtr->viewControl.Orbit(this->dataPtr->drag);
this->dataPtr->viewControl->Orbit(this->dataPtr->drag);
}
else if (this->dataPtr->mouseEvent.Buttons() & common::MouseEvent::RIGHT)
{
Expand All @@ -1760,7 +1791,7 @@ void IgnRenderer::HandleMouseViewControl()
double amount = ((-this->dataPtr->drag.Y() /
static_cast<double>(this->dataPtr->camera->ImageHeight()))
* distance * tan(vfov/2.0) * 6.0);
this->dataPtr->viewControl.Zoom(amount);
this->dataPtr->viewControl->Zoom(amount);
}
}
this->dataPtr->drag = 0;
Expand Down Expand Up @@ -2052,6 +2083,17 @@ void IgnRenderer::SetViewCollisionsTarget(const std::string &_target)
this->dataPtr->viewCollisionsTarget = _target;
}

/////////////////////////////////////////////////
void IgnRenderer::SetViewController(const std::string &_controller)
{
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
this->dataPtr->viewController = _controller;

// mark mouse dirty to trigger HandleMouseEvent call and
// set up a new view controller
this->dataPtr->mouseDirty = true;
}

/////////////////////////////////////////////////
void IgnRenderer::SetFollowPGain(double _gain)
{
Expand Down Expand Up @@ -2792,6 +2834,13 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem)
ignmsg << "View collisions service on ["
<< this->dataPtr->viewCollisionsService << "]" << std::endl;

// camera view control mode
this->dataPtr->cameraViewControlService = "/gui/camera/view_control";
this->dataPtr->node.Advertise(this->dataPtr->cameraViewControlService,
&Scene3D::OnViewControl, this);
ignmsg << "Camera view controller topic advertised on ["
<< this->dataPtr->cameraViewControlService << "]" << std::endl;

ignition::gui::App()->findChild<
ignition::gui::MainWindow *>()->QuickWindow()->installEventFilter(this);
ignition::gui::App()->findChild<
Expand Down Expand Up @@ -2971,6 +3020,19 @@ bool Scene3D::OnViewCollisions(const msgs::StringMsg &_msg,
return true;
}

/////////////////////////////////////////////////
bool Scene3D::OnViewControl(const msgs::StringMsg &_msg,
msgs::Boolean &_res)
{
auto renderWindow = this->PluginItem()->findChild<RenderWindowItem *>();

renderWindow->SetViewController(_msg.data());

_res.set_data(true);
return true;
}


/////////////////////////////////////////////////
void Scene3D::OnHovered(int _mouseX, int _mouseY)
{
Expand Down Expand Up @@ -3240,6 +3302,12 @@ void RenderWindowItem::SetViewCollisionsTarget(const std::string &_target)
this->dataPtr->renderThread->ignRenderer.SetViewCollisionsTarget(_target);
}

/////////////////////////////////////////////////
void RenderWindowItem::SetViewController(const std::string &_controller)
{
this->dataPtr->renderThread->ignRenderer.SetViewController(_controller);
}

/////////////////////////////////////////////////
void RenderWindowItem::SetFollowPGain(double _gain)
{
Expand Down
15 changes: 15 additions & 0 deletions src/gui/plugins/scene3d/Scene3D.hh
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,13 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
private: bool OnViewCollisions(const msgs::StringMsg &_msg,
msgs::Boolean &_res);

/// \brief Callback for camera view controller request
/// \param[in] _msg Request message to set the camera view controller
/// \param[in] _res Response data
/// \return True if the request is received
private: bool OnViewControl(const msgs::StringMsg &_msg,
msgs::Boolean &_res);

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<Scene3DPrivate> dataPtr;
Expand Down Expand Up @@ -267,6 +274,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _target Target to view collisions
public: void SetViewCollisionsTarget(const std::string &_target);

/// \brief Set camera view controller
/// \param[in] _viewController. Values are "orbit", and "ortho"
public: void SetViewController(const std::string &_viewController);

/// \brief Set the p gain for the camera follow movement
/// \param[in] _gain Camera follow p gain.
public: void SetFollowPGain(double _gain);
Expand Down Expand Up @@ -617,6 +628,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _target Target to view collisions
public: void SetViewCollisionsTarget(const std::string &_target);

/// \brief Set camera view controller
/// \param[in] _viewController. Values are "orbit", and "ortho"
public: void SetViewController(const std::string &_viewController);

/// \brief Set the p gain for the camera follow movement
/// \param[in] _gain Camera follow p gain.
public: void SetFollowPGain(double _gain);
Expand Down
37 changes: 34 additions & 3 deletions src/gui/plugins/view_angle/ViewAngle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,10 @@ namespace ignition::gazebo
public: std::mutex mutex;

/// \brief View Angle service name
public: std::string service;
public: std::string viewAngleService;

/// \brief View Control service name
public: std::string viewControlService;
};
}

Expand All @@ -61,7 +64,10 @@ void ViewAngle::LoadConfig(const tinyxml2::XMLElement *)
this->title = "View Angle";

// For view angle requests
this->dataPtr->service = "/gui/view_angle";
this->dataPtr->viewAngleService = "/gui/view_angle";

// view control requests
this->dataPtr->viewControlService = "/gui/camera/view_control";
}

/////////////////////////////////////////////////
Expand All @@ -79,7 +85,32 @@ void ViewAngle::OnAngleMode(int _x, int _y, int _z)
req.set_y(_y);
req.set_z(_z);

this->dataPtr->node.Request(this->dataPtr->service, req, cb);
this->dataPtr->node.Request(this->dataPtr->viewAngleService, req, cb);
}

/////////////////////////////////////////////////
void ViewAngle::OnViewControl(const QString &_controller)
{
std::function<void(const ignition::msgs::Boolean &, const bool)> cb =
[](const ignition::msgs::Boolean &/*_rep*/, const bool _result)
{
if (!_result)
ignerr << "Error setting view controller" << std::endl;
};

ignition::msgs::StringMsg req;
std::string str = _controller.toStdString();
if (str.find("Orbit") != std::string::npos)
req.set_data("orbit");
else if (str.find("Ortho") != std::string::npos)
req.set_data("ortho");
else
{
ignerr << "Unknown view controller selected: " << str << std::endl;
return;
}

this->dataPtr->node.Request(this->dataPtr->viewControlService, req, cb);
}

// Register this plugin
Expand Down
4 changes: 4 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,10 @@ namespace gazebo
/// to assume. All 0s for x, y, and z indicate the initial camera pose.
public slots: void OnAngleMode(int _x, int _y, int _z);

/// \brief Callback in Qt thread when camera view controller changes.
/// \param[in] _mode New camera view controller
public slots: void OnViewControl(const QString &_controller);

/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr<ViewAnglePrivate> dataPtr;
Expand Down
Loading