Skip to content

Commit

Permalink
Wireframe mode (#816)
Browse files Browse the repository at this point in the history
* Visualize wireframes

Signed-off-by: Atharva Pusalkar <[email protected]>

* Fix nested models

Signed-off-by: Atharva Pusalkar <[email protected]>

* Reorder menu items

Signed-off-by: Atharva Pusalkar <[email protected]>

* Style fix

Signed-off-by: Atharva Pusalkar <[email protected]>
  • Loading branch information
atharva-18 committed May 17, 2021
1 parent d19dda1 commit c2a4a40
Show file tree
Hide file tree
Showing 6 changed files with 300 additions and 0 deletions.
4 changes: 4 additions & 0 deletions include/ignition/gazebo/rendering/RenderUtil.hh
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
public : void SetRemoveSensorCb(
std::function<void(const gazebo::Entity &)> _removeSensorCb);

/// \brief View wireframes of specified entity
/// \param[in] _entity Entity to view wireframes
public: void ViewWireframes(const Entity &_entity);

/// \brief View collisions of specified entity which are shown in orange
/// \param[in] _entity Entity to view collisions
public: void ViewCollisions(const Entity &_entity);
Expand Down
12 changes: 12 additions & 0 deletions src/gui/plugins/modules/EntityContextMenu.cc
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,9 @@ namespace ignition::gazebo
/// \brief Remove service name
public: std::string removeService;

/// \brief View wireframes service name
public: std::string viewWireframesService;

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

Expand Down Expand Up @@ -79,6 +82,9 @@ EntityContextMenu::EntityContextMenu()
// For remove service requests
this->dataPtr->removeService = "/world/default/remove";

// For view wireframes service requests
this->dataPtr->viewWireframesService = "/gui/view/wireframes";

// For view collisions service requests
this->dataPtr->viewCollisionsService = "/gui/view/collisions";
}
Expand Down Expand Up @@ -152,6 +158,12 @@ void EntityContextMenu::OnRequest(const QString &_request, const QString &_data)
req.set_data(_data.toStdString());
this->dataPtr->node.Request(this->dataPtr->followService, req, cb);
}
else if (request == "view_wireframes")
{
ignition::msgs::StringMsg req;
req.set_data(_data.toStdString());
this->dataPtr->node.Request(this->dataPtr->viewWireframesService, req, cb);
}
else if (request == "view_collisions")
{
ignition::msgs::StringMsg req;
Expand Down
10 changes: 10 additions & 0 deletions src/gui/plugins/modules/EntityContextMenu.qml
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,14 @@ Item {
context.OnRequest("view_collisions", context.entity)
}
}
MenuItem {
id: viewWireframesMenu
text: "Wireframe"
onTriggered: {
menu.close()
context.OnRequest("view_wireframes", context.entity)
}
}
}

function open(_entity, _type, _x, _y) {
Expand All @@ -81,6 +89,7 @@ Item {
moveToMenu.enabled = false
followMenu.enabled = false
removeMenu.enabled = false
viewWireframesMenu.enabled = false;
viewCollisionsMenu.enabled = false;

// enable / disable menu items
Expand All @@ -99,6 +108,7 @@ Item {

if (context.type == "model" || context.type == "link")
{
viewWireframesMenu.enabled = true;
viewCollisionsMenu.enabled = true;
}

Expand Down
64 changes: 64 additions & 0 deletions src/gui/plugins/scene3d/Scene3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -233,6 +233,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Helper object to move user camera
public: MoveToHelper moveToHelper;

/// \brief Target to view wireframes
public: std::string viewWireframesTarget;

/// \brief Target to view collisions
public: std::string viewCollisionsTarget;

Expand Down Expand Up @@ -435,6 +438,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// Used when recording in lockstep mode.
public: std::mutex renderMutex;

/// \brief View wireframes service
public: std::string viewWireframesService;

/// \brief View collisions service
public: std::string viewCollisionsService;
};
Expand Down Expand Up @@ -811,6 +817,32 @@ void IgnRenderer::Render()
}
}

// View wireframes
{
IGN_PROFILE("IgnRenderer::Render ViewWireframes");
if (!this->dataPtr->viewWireframesTarget.empty())
{
rendering::NodePtr targetNode =
scene->NodeByName(this->dataPtr->viewWireframesTarget);
auto targetVis = std::dynamic_pointer_cast<rendering::Visual>(targetNode);

if (targetVis)
{
Entity targetEntity =
std::get<int>(targetVis->UserData("gazebo-entity"));
this->dataPtr->renderUtil.ViewWireframes(targetEntity);
}
else
{
ignerr << "Unable to find node name ["
<< this->dataPtr->viewWireframesTarget
<< "] to view wireframes" << std::endl;
}

this->dataPtr->viewWireframesTarget.clear();
}
}

// View collisions
{
IGN_PROFILE("IgnRenderer::Render ViewCollisions");
Expand Down Expand Up @@ -2006,6 +2038,13 @@ void IgnRenderer::SetMoveToPose(const math::Pose3d &_pose)
this->dataPtr->moveToPoseValue = _pose;
}

/////////////////////////////////////////////////
void IgnRenderer::SetViewWireframesTarget(const std::string &_target)
{
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
this->dataPtr->viewWireframesTarget = _target;
}

/////////////////////////////////////////////////
void IgnRenderer::SetViewCollisionsTarget(const std::string &_target)
{
Expand Down Expand Up @@ -2739,6 +2778,13 @@ void Scene3D::LoadConfig(const tinyxml2::XMLElement *_pluginElem)
ignmsg << "Camera pose topic advertised on ["
<< this->dataPtr->cameraPoseTopic << "]" << std::endl;

// view wireframes service
this->dataPtr->viewWireframesService = "/gui/view/wireframes";
this->dataPtr->node.Advertise(this->dataPtr->viewWireframesService,
&Scene3D::OnViewWireframes, this);
ignmsg << "View wireframes service on ["
<< this->dataPtr->viewWireframesService << "]" << std::endl;

// view collisions service
this->dataPtr->viewCollisionsService = "/gui/view/collisions";
this->dataPtr->node.Advertise(this->dataPtr->viewCollisionsService,
Expand Down Expand Up @@ -2901,6 +2947,18 @@ bool Scene3D::OnMoveToPose(const msgs::GUICamera &_msg, msgs::Boolean &_res)
return true;
}

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

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

_res.set_data(true);
return true;
}

/////////////////////////////////////////////////
bool Scene3D::OnViewCollisions(const msgs::StringMsg &_msg,
msgs::Boolean &_res)
Expand Down Expand Up @@ -3170,6 +3228,12 @@ void RenderWindowItem::SetMoveToPose(const math::Pose3d &_pose)
this->dataPtr->renderThread->ignRenderer.SetMoveToPose(_pose);
}

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

/////////////////////////////////////////////////
void RenderWindowItem::SetViewCollisionsTarget(const std::string &_target)
{
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 @@ -154,6 +154,13 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
private: bool OnMoveToPose(const msgs::GUICamera &_msg,
msgs::Boolean &_res);

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

/// \brief Callback for view collisions request
/// \param[in] _msg Request message to set the target to view collisions
/// \param[in] _res Response data
Expand Down Expand Up @@ -252,6 +259,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _pose The world pose to set the camera to.
public: void SetMoveToPose(const math::Pose3d &_pose);

/// \brief View wireframes of the specified target
/// \param[in] _target Target to view wireframes
public: void SetViewWireframesTarget(const std::string &_target);

/// \brief View collisions of the specified target
/// \param[in] _target Target to view collisions
public: void SetViewCollisionsTarget(const std::string &_target);
Expand Down Expand Up @@ -598,6 +609,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _pose The new camera pose in the world frame.
public: void SetMoveToPose(const math::Pose3d &_pose);

/// \brief View wireframes of the specified target
/// \param[in] _target Target to view wireframes
public: void SetViewWireframesTarget(const std::string &_target);

/// \brief View collisions of the specified target
/// \param[in] _target Target to view collisions
public: void SetViewCollisionsTarget(const std::string &_target);
Expand Down
Loading

0 comments on commit c2a4a40

Please sign in to comment.