diff --git a/Migration.md b/Migration.md
index 7430a11cc1..ed95d13afe 100644
--- a/Migration.md
+++ b/Migration.md
@@ -47,6 +47,24 @@ since pose information is being logged in the `changed_state` topic.
this type is discouraged (see the **Deprecated** section above for more
information about how to replace usage of `ComponentKey`).
+* The `GzScene3D` GUI plugin is being deprecated in favor of `MinimalScene`. In
+ order to get the same functionality as `GzScene3D`, users need to add the
+ following plugins:
+ + `MinimalScene`: base rendering functionality
+ + `GzSceneManager`: adds / removes / moves entities in the scene
+ + `EntityContextMenuPlugin`: right-click menu
+ + `InteractiveViewControl`: orbit controls
+ + `CameraTracking`: Move to, follow, set camera pose
+ + `MarkerManager`: Enables the use of markers
+ + `SelectEntities`: Select entities clicking on the scene
+ + `Spawn`: Functionality to spawn entities into the scene via GUI
+ + `VisualizationCapabilities`: View collisions, inertial, CoM, joints, etc.
+
+ Moreover, legacy mode needs to be turned off for the following plugins
+ for them to work with `MinimalScene` (set `false`):
+ + `TransformControl`: Translate and rotate
+ + `ViewAndle`: Move camera to preset angles
+
## Ignition Gazebo 4.x to 5.x
* Use `cli` component of `ignition-utils1`.
diff --git a/examples/worlds/minimal_scene.sdf b/examples/worlds/minimal_scene.sdf
index 4b21d84cec..7d6afdae56 100644
--- a/examples/worlds/minimal_scene.sdf
+++ b/examples/worlds/minimal_scene.sdf
@@ -46,6 +46,14 @@ Missing for parity with GzScene3D:
+
+
+ floating
+ 5
+ 5
+ false
+
+
diff --git a/src/gui/gui.config b/src/gui/gui.config
index 137c55e648..a250a3c1a9 100644
--- a/src/gui/gui.config
+++ b/src/gui/gui.config
@@ -27,7 +27,7 @@
-
+
3D View
false
@@ -38,10 +38,113 @@
scene
0.4 0.4 0.4
0.8 0.8 0.8
- 6 0 6 0 0.5 3.14
+ -6 0 6 0 0.5 0
-
+
+
+
+ floating
+ 5
+ 5
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
World control
@@ -64,7 +167,7 @@
-
+
World stats
@@ -85,7 +188,6 @@
true
true
true
-
@@ -128,6 +230,9 @@
false
#777777
+
+
+ false
@@ -159,3 +264,13 @@
docked
+
+
+
+
+ docked
+
+
+
+ false
+
diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt
index 6643b4b251..d74c63cca3 100644
--- a/src/gui/plugins/CMakeLists.txt
+++ b/src/gui/plugins/CMakeLists.txt
@@ -121,6 +121,7 @@ add_subdirectory(modules)
add_subdirectory(align_tool)
add_subdirectory(banana_for_scale)
add_subdirectory(component_inspector)
+add_subdirectory(entity_context_menu)
add_subdirectory(entity_tree)
add_subdirectory(joint_position_controller)
add_subdirectory(lights)
diff --git a/src/gui/plugins/entity_context_menu/CMakeLists.txt b/src/gui/plugins/entity_context_menu/CMakeLists.txt
new file mode 100644
index 0000000000..85dddd702a
--- /dev/null
+++ b/src/gui/plugins/entity_context_menu/CMakeLists.txt
@@ -0,0 +1,8 @@
+gz_add_gui_plugin(EntityContextMenuPlugin
+ SOURCES
+ EntityContextMenuPlugin.cc
+ QT_HEADERS
+ EntityContextMenuPlugin.hh
+ PUBLIC_LINK_LIBS
+ ${PROJECT_LIBRARY_TARGET_NAME}-rendering
+)
diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc
new file mode 100644
index 0000000000..8fa76f2669
--- /dev/null
+++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.cc
@@ -0,0 +1,210 @@
+/*
+ * Copyright (C) 2021 Open Source Robotics Foundation
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+*/
+
+#include "EntityContextMenuPlugin.hh"
+
+#include
+#include
+
+#include
+
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+
+#include
+#include
+#include
+
+namespace ignition::gazebo
+{
+ class EntityContextMenuPrivate
+ {
+ /// \brief Perform operations in the render thread.
+ public: void OnRender();
+
+ /// \brief Pointer to the rendering scene
+ public: rendering::ScenePtr scene{nullptr};
+
+ /// \brief User camera
+ public: rendering::CameraPtr camera{nullptr};
+
+ /// \brief Entity context menu handler
+ public: EntityContextMenuHandler entityContextMenuHandler;
+ };
+}
+
+using namespace ignition;
+using namespace gazebo;
+
+/////////////////////////////////////////////////
+void EntityContextMenuPrivate::OnRender()
+{
+ if (nullptr == this->scene)
+ {
+ this->scene = rendering::sceneFromFirstRenderEngine();
+ if (nullptr == this->scene)
+ {
+ return;
+ }
+
+ for (unsigned int i = 0; i < this->scene->NodeCount(); ++i)
+ {
+ auto cam = std::dynamic_pointer_cast(
+ this->scene->NodeByIndex(i));
+ if (cam)
+ {
+ if (std::get(cam->UserData("user-camera")))
+ {
+ this->camera = cam;
+
+ igndbg << "Entity context menu plugin is using camera ["
+ << this->camera->Name() << "]" << std::endl;
+ break;
+ }
+ }
+ }
+ }
+}
+
+/////////////////////////////////////////////////
+EntityContextMenu::EntityContextMenu()
+ : gui::Plugin(), dataPtr(std::make_unique())
+{
+ qmlRegisterType(
+ "RenderWindowOverlay", 1, 0, "RenderWindowOverlay");
+}
+
+EntityContextMenu::~EntityContextMenu() = default;
+
+/////////////////////////////////////////////////
+void EntityContextMenu::LoadConfig(const tinyxml2::XMLElement *)
+{
+ EntityContextMenuItem *renderWindowOverlay =
+ this->PluginItem()->findChild();
+ if (!renderWindowOverlay)
+ {
+ ignerr << "Unable to find Render Window Overlay item. "
+ << "Render window overlay will not be created" << std::endl;
+ return;
+ }
+
+ renderWindowOverlay->SetEntityContextMenuHandler(
+ this->dataPtr->entityContextMenuHandler);
+
+ if (this->title.empty())
+ this->title = "EntityContextMenu";
+
+ ignition::gui::App()->findChild
+ ()->installEventFilter(this);
+}
+
+////////////////////////////////////////////////
+bool EntityContextMenu::eventFilter(QObject *_obj, QEvent *_event)
+{
+ if (_event->type() == ignition::gui::events::Render::kType)
+ {
+ this->dataPtr->OnRender();
+ }
+ else if (_event->type() == ignition::gui::events::RightClickOnScene::kType)
+ {
+ ignition::gui::events::RightClickOnScene *_e =
+ static_cast(_event);
+ if (_e)
+ {
+ this->dataPtr->entityContextMenuHandler.HandleMouseContextMenu(
+ _e->Mouse(), this->dataPtr->camera);
+ }
+ }
+
+ return QObject::eventFilter(_obj, _event);
+}
+
+
+/////////////////////////////////////////////////
+EntityContextMenuItem::EntityContextMenuItem(QQuickItem *_parent)
+ : QQuickItem(_parent)
+{
+ this->setAcceptedMouseButtons(Qt::AllButtons);
+ this->setFlag(ItemHasContents);
+}
+
+/////////////////////////////////////////////////
+void EntityContextMenuItem::SetEntityContextMenuHandler(
+ const EntityContextMenuHandler &_entityContextMenuHandler)
+{
+ this->connect(
+ &_entityContextMenuHandler,
+ &EntityContextMenuHandler::ContextMenuRequested,
+ this,
+ &EntityContextMenuItem::OnContextMenuRequested,
+ Qt::QueuedConnection);
+}
+
+///////////////////////////////////////////////////
+void EntityContextMenuItem::OnContextMenuRequested(
+ QString _entity, int _mouseX, int _mouseY)
+{
+ emit openContextMenu(std::move(_entity), _mouseX, _mouseY);
+}
+
+/////////////////////////////////////////////////
+EntityContextMenuHandler::EntityContextMenuHandler()
+{
+}
+
+void EntityContextMenuHandler::HandleMouseContextMenu(
+ const common::MouseEvent &_mouseEvent, const rendering::CameraPtr &_camera)
+{
+ if (!_mouseEvent.Dragging() &&
+ _mouseEvent.Type() == common::MouseEvent::RELEASE &&
+ _mouseEvent.Button() == common::MouseEvent::RIGHT)
+ {
+ math::Vector2i dt =
+ _mouseEvent.PressPos() - _mouseEvent.Pos();
+
+ // check for click with some tol for mouse movement
+ if (dt.Length() > 5.0)
+ return;
+
+ rendering::VisualPtr visual = _camera->Scene()->VisualAt(
+ _camera,
+ _mouseEvent.Pos());
+
+ if (!visual)
+ return;
+
+ // get model visual
+ while (visual->HasParent() && visual->Parent() !=
+ visual->Scene()->RootVisual())
+ {
+ visual = std::dynamic_pointer_cast(visual->Parent());
+ }
+
+ emit ContextMenuRequested(
+ visual->Name().c_str(), _mouseEvent.Pos().X(), _mouseEvent.Pos().Y());
+ }
+}
+
+// Register this plugin
+IGNITION_ADD_PLUGIN(ignition::gazebo::EntityContextMenu,
+ ignition::gui::Plugin)
diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh
new file mode 100644
index 0000000000..4ed5858f3a
--- /dev/null
+++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.hh
@@ -0,0 +1,111 @@
+/*
+ * Copyright (C) 2021 Open Source Robotics Foundation
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+*/
+
+#ifndef IGNITION_GUI_PLUGINS_ENTITY_CONTEXT_MENU_HH_
+#define IGNITION_GUI_PLUGINS_ENTITY_CONTEXT_MENU_HH_
+
+#include
+
+#include
+
+#include
+
+#include
+
+namespace ignition
+{
+namespace gazebo
+{
+ class EntityContextMenuPrivate;
+
+ /// \brief This plugin is in charge of showing the entity context menu when
+ /// the right button is clicked on a visual.
+ class EntityContextMenu : public ignition::gui::Plugin
+ {
+ Q_OBJECT
+
+ /// \brief Constructor
+ public: EntityContextMenu();
+
+ /// \brief Destructor
+ public: ~EntityContextMenu() override;
+
+ // Documentation inherited
+ public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override;
+
+ // Documentation inherited
+ protected: bool eventFilter(QObject *_obj, QEvent *_event) override;
+
+ /// \internal
+ /// \brief Pointer to private data.
+ private: std::unique_ptr dataPtr;
+ };
+
+ class EntityContextMenuHandler : public QObject
+ {
+ Q_OBJECT
+
+ /// \brief Constructor
+ public: EntityContextMenuHandler();
+
+ /// \brief Handle mouse event for context menu
+ /// \param[in] _mouseEvent Right click mouse event
+ /// \param[in] _camera User camera
+ public: void HandleMouseContextMenu(const common::MouseEvent &_mouseEvent,
+ const rendering::CameraPtr &_camera);
+
+ /// \brief Signal fired when context menu event is triggered
+ /// \param[in] _entity Scoped name of entity.
+ /// \param[in] _mouseX X coordinate of the right click
+ /// \param[in] _mouseY Y coordinate of the right click
+ signals: void ContextMenuRequested(
+ QString _entity, int _mouseX, int _mouseY);
+ };
+
+ /// \brief A QQUickItem that manages the render window
+ class EntityContextMenuItem : public QQuickItem
+ {
+ Q_OBJECT
+
+ /// \brief Constructor
+ /// \param[in] _parent Parent item
+ public: explicit EntityContextMenuItem(QQuickItem *_parent = nullptr);
+
+ /// \brief Set the entity context menu handler
+ /// \param[in] _entityContextMenuHandler Entity context menu handler
+ public: void SetEntityContextMenuHandler(
+ const EntityContextMenuHandler &_entityContextMenuHandler);
+
+ /// \brief Signal fired to open context menu
+ /// Note that the function name needs to start with lowercase in order for
+ /// the connection to work on the QML side
+ /// \param[in] _entity Scoped name of entity.
+ /// \param[in] _mouseX X coordinate of the right click
+ /// \param[in] _mouseY Y coordinate of the right click
+ signals: void openContextMenu(QString _entity, int _mouseX, int _mouseY); // NOLINT
+
+ /// \brief Qt callback when context menu request is received
+ /// \param[in] _entity Scoped name of entity.
+ /// \param[in] _mouseX X coordinate of the right click
+ /// \param[in] _mouseY Y coordinate of the right click
+ public slots: void OnContextMenuRequested(
+ QString _entity, int _mouseX, int _mouseY);
+ };
+}
+}
+
+#endif
diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qml b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qml
new file mode 100644
index 0000000000..66e2f56d28
--- /dev/null
+++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qml
@@ -0,0 +1,47 @@
+/*
+ * Copyright (C) 2021 Open Source Robotics Foundation
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+*/
+
+import QtQuick 2.0
+import QtQuick.Controls 2.0
+import QtQuick.Layouts 1.3
+import RenderWindowOverlay 1.0
+import IgnGazebo 1.0 as IgnGazebo
+
+Rectangle {
+ visible: false
+ color: "transparent"
+
+ RenderWindowOverlay {
+ id: renderWindowOverlay
+ objectName: "renderWindowOverlay"
+ anchors.fill: parent
+
+ Connections {
+ target: renderWindowOverlay
+ onOpenContextMenu:
+ {
+ entityContextMenu.open(_entity, "model",
+ _mouseX, _mouseY);
+ }
+ }
+ }
+
+ IgnGazebo.EntityContextMenu {
+ id: entityContextMenu
+ anchors.fill: parent
+ }
+}
diff --git a/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qrc b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qrc
new file mode 100644
index 0000000000..96bffedd5e
--- /dev/null
+++ b/src/gui/plugins/entity_context_menu/EntityContextMenuPlugin.qrc
@@ -0,0 +1,5 @@
+
+
+ EntityContextMenuPlugin.qml
+
+
diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc
index 32bd92ac91..18e0fa9a77 100644
--- a/src/gui/plugins/scene3d/Scene3D.cc
+++ b/src/gui/plugins/scene3d/Scene3D.cc
@@ -86,6 +86,7 @@ namespace gazebo
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Helper to store selection requests to be handled in the render
/// thread by `IgnRenderer::HandleEntitySelection`.
+ // SelectEntities
struct SelectionHelper
{
/// \brief Entity to be selected
@@ -101,26 +102,8 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Private data class for IgnRenderer
class IgnRendererPrivate
{
- /// \brief Flag to indicate if mouse event is dirty
- public: bool mouseDirty = false;
-
- /// \brief Flag to indicate if hover event is dirty
- public: bool hoverDirty = false;
-
- /// \brief Mouse event
- public: common::MouseEvent mouseEvent;
-
- /// \brief Key event
- public: common::KeyEvent keyEvent;
-
- /// \brief Mouse move distance since last event.
- public: math::Vector2d drag;
-
- /// \brief Mutex to protect mouse events
- public: std::mutex mutex;
-
- /// \brief User camera
- public: rendering::CameraPtr camera;
+ // --------------------------------------------------------------
+ // InteractiveViewControl
/// \brief Orbit view controller
public: rendering::OrbitViewController orbitViewControl;
@@ -131,6 +114,25 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Camera view controller
public: rendering::ViewController *viewControl{nullptr};
+ /// \brief View controller
+ public: std::string viewController{"orbit"};
+
+ /// \brief View control focus target
+ public: math::Vector3d target = math::Vector3d(
+ math::INF_D, math::INF_D, math::INF_D);
+
+ // --------------------------------------------------------------
+ // TransformControl
+
+ /// \brief The xyz values by which to snap the object.
+ public: math::Vector3d xyzSnap = math::Vector3d::One;
+
+ /// \brief The rpy values by which to snap the object.
+ public: math::Vector3d rpySnap = {45, 45, 45};
+
+ /// \brief The scale values by which to snap the object.
+ public: math::Vector3d scaleSnap = math::Vector3d::One;
+
/// \brief Transform controller for models
public: rendering::TransformController transformControl;
@@ -142,6 +144,28 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
public: rendering::TransformMode transformMode =
rendering::TransformMode::TM_NONE;
+ /// \brief Name of service for setting entity pose
+ public: std::string poseCmdService;
+
+ /// \brief Flag to indicate whether the x key is currently being pressed
+ public: bool xPressed = false;
+
+ /// \brief Flag to indicate whether the y key is currently being pressed
+ public: bool yPressed = false;
+
+ /// \brief Flag to indicate whether the z key is currently being pressed
+ public: bool zPressed = false;
+
+ /// \brief The starting world pose of a clicked visual.
+ public: ignition::math::Vector3d startWorldPos = math::Vector3d::Zero;
+
+ /// \brief Flag to keep track of world pose setting used
+ /// for button translating.
+ public: bool isStartWorldPosSet = false;
+
+ // --------------------------------------------------------------
+ // VideoRecorder
+
/// \brief True to record a video from the user camera
public: bool recordVideo = false;
@@ -171,12 +195,52 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Camera pose publisher
public: transport::Node::Publisher recorderStatsPub;
+ /// \brief Image from user camera
+ public: rendering::Image cameraImage;
+
+ /// \brief Video encoder
+ public: common::VideoEncoder videoEncoder;
+
+ // --------------------------------------------------------------
+ // CameraTracking
+
/// \brief Target to move the user camera to
public: std::string moveToTarget;
/// \brief Helper object to move user camera
public: ignition::rendering::MoveToHelper moveToHelper;
+ /// \brief Target to follow
+ public: std::string followTarget;
+
+ /// \brief Wait for follow target
+ public: bool followTargetWait = false;
+
+ /// \brief Offset of camera from target being followed
+ public: math::Vector3d followOffset = math::Vector3d(-5, 0, 3);
+
+ /// \brief Flag to indicate the follow offset needs to be updated
+ public: bool followOffsetDirty = false;
+
+ /// \brief Flag to indicate the follow offset has been updated
+ public: bool newFollowOffset = true;
+
+ /// \brief Follow P gain
+ public: double followPGain = 0.01;
+
+ /// \brief True follow the target at an offset that is in world frame,
+ /// false to follow in target's local frame
+ public: bool followWorldFrame = false;
+
+ /// \brief The pose set from the move to pose service.
+ public: std::optional moveToPoseValue;
+
+ /// \brief Last move to animation time
+ public: std::chrono::time_point prevMoveToTime;
+
+ // --------------------------------------------------------------
+ // VisualizationCapabilities
+
/// \brief Target to view as transparent
public: std::string viewTransparentTarget;
@@ -195,37 +259,15 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Target to view collisions
public: std::string viewCollisionsTarget;
- /// \brief View controller
- public: std::string viewController{"orbit"};
+ // --------------------------------------------------------------
+ // SelectEntities
/// \brief Helper object to select entities. Only the latest selection
/// request is kept.
public: SelectionHelper selectionHelper;
- /// \brief Target to follow
- public: std::string followTarget;
-
- /// \brief Wait for follow target
- public: bool followTargetWait = false;
-
- /// \brief Offset of camera from target being followed
- public: math::Vector3d followOffset = math::Vector3d(-5, 0, 3);
-
- /// \brief Flag to indicate the follow offset needs to be updated
- public: bool followOffsetDirty = false;
-
- /// \brief Flag to indicate the follow offset has been updated
- public: bool newFollowOffset = true;
-
- /// \brief Follow P gain
- public: double followPGain = 0.01;
-
- /// \brief True follow the target at an offset that is in world frame,
- /// false to follow in target's local frame
- public: bool followWorldFrame = false;
-
- /// \brief Flag for indicating whether we are in view angle mode or not
- public: bool viewAngle = false;
+ // --------------------------------------------------------------
+ // Spawn
/// \brief Flag for indicating whether we are spawning or not.
public: bool isSpawning = false;
@@ -234,10 +276,6 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// resource with the shapes plugin or not
public: bool isPlacing = false;
- /// \brief Atomic bool indicating whether the dropdown menu
- /// is currently enabled or disabled.
- public: std::atomic_bool dropdownMenuEnabled = true;
-
/// \brief The SDF string of the resource to be used with plugins that spawn
/// entities.
public: std::string spawnSdfString;
@@ -249,9 +287,6 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
public: ignition::math::Pose3d spawnPreviewPose =
ignition::math::Pose3d::Zero;
- /// \brief The currently hovered mouse position in screen coordinates
- public: math::Vector2i mouseHoverPos = math::Vector2i::Zero;
-
/// \brief The visual generated from the spawnSdfString / spawnSdfPath
public: rendering::NodePtr spawnPreview = nullptr;
@@ -259,78 +294,71 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// for easy deletion of visuals later
public: std::vector previewIds;
+ /// \brief Name of service for creating entity
+ public: std::string createCmdService;
+
+ // --------------------------------------------------------------
+ // ViewAngle
+
+ /// \brief Flag for indicating whether we are in view angle mode or not
+ public: bool viewAngle = false;
+
/// \brief The pose set during a view angle button press that holds
/// the pose the camera should assume relative to the entit(y/ies).
/// The vector (0, 0, 0) indicates to return the camera back to the home
/// pose originally loaded from the sdf.
public: math::Vector3d viewAngleDirection = math::Vector3d::Zero;
- /// \brief The pose set from the move to pose service.
- public: std::optional moveToPoseValue;
+ // --------------------------------------------------------------
+ // Common to various plugins
- /// \brief Last move to animation time
- public: std::chrono::time_point prevMoveToTime;
+ /// \brief Flag to indicate if mouse event is dirty
+ public: bool mouseDirty = false;
- /// \brief Image from user camera
- public: rendering::Image cameraImage;
+ /// \brief Flag to indicate if hover event is dirty
+ public: bool hoverDirty = false;
- /// \brief Video encoder
- public: common::VideoEncoder videoEncoder;
+ /// \brief Mouse event
+ public: common::MouseEvent mouseEvent;
+
+ /// \brief Key event
+ public: common::KeyEvent keyEvent;
+
+ /// \brief Mouse move distance since last event.
+ public: math::Vector2d drag;
+
+ /// \brief Mutex to protect mouse events
+ public: std::mutex mutex;
+
+ /// \brief User camera
+ public: rendering::CameraPtr camera;
+
+ /// \brief Atomic bool indicating whether the dropdown menu
+ /// is currently enabled or disabled.
+ public: std::atomic_bool dropdownMenuEnabled = true;
+
+ /// \brief The currently hovered mouse position in screen coordinates
+ public: math::Vector2i mouseHoverPos = math::Vector2i::Zero;
/// \brief Ray query for mouse clicks
public: rendering::RayQueryPtr rayQuery;
- /// \brief View control focus target
- public: math::Vector3d target = math::Vector3d(
- math::INF_D, math::INF_D, math::INF_D);
-
/// \brief Rendering utility
public: RenderUtil renderUtil;
/// \brief Transport node for making transform control requests
public: transport::Node node;
- /// \brief Name of service for setting entity pose
- public: std::string poseCmdService;
-
- /// \brief Name of service for creating entity
- public: std::string createCmdService;
-
- /// \brief The starting world pose of a clicked visual.
- public: ignition::math::Vector3d startWorldPos = math::Vector3d::Zero;
-
- /// \brief Flag to keep track of world pose setting used
- /// for button translating.
- public: bool isStartWorldPosSet = false;
-
/// \brief Where the mouse left off - used to continue translating
/// smoothly when switching axes through keybinding and clicking
/// Updated on an x, y, or z, press or release and a mouse press
public: math::Vector2i mousePressPos = math::Vector2i::Zero;
- /// \brief Flag to indicate whether the x key is currently being pressed
- public: bool xPressed = false;
-
- /// \brief Flag to indicate whether the y key is currently being pressed
- public: bool yPressed = false;
-
- /// \brief Flag to indicate whether the z key is currently being pressed
- public: bool zPressed = false;
-
/// \brief Flag to indicate whether the escape key has been released.
public: bool escapeReleased = false;
/// \brief ID of thread where render calls can be made.
public: std::thread::id renderThreadId;
-
- /// \brief The xyz values by which to snap the object.
- public: math::Vector3d xyzSnap = math::Vector3d::One;
-
- /// \brief The rpy values by which to snap the object.
- public: math::Vector3d rpySnap = {45, 45, 45};
-
- /// \brief The scale values by which to snap the object.
- public: math::Vector3d scaleSnap = math::Vector3d::One;
};
/// \brief Qt and Ogre rendering is happening in different threads
@@ -438,21 +466,30 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Private data class for Scene3D
class Scene3DPrivate
{
- /// \brief Transport node
- public: transport::Node node;
-
- /// \brief Name of the world
- public: std::string worldName;
-
- /// \brief Rendering utility
- public: RenderUtil *renderUtil = nullptr;
+ // --------------------------------------------------------------
+ // TransformControl
/// \brief Transform mode service
public: std::string transformModeService;
+ // --------------------------------------------------------------
+ // VideoRecorder
+
/// \brief Record video service
public: std::string recordVideoService;
+ /// \brief lockstep ECM updates with rendering
+ public: bool recordVideoLockstep = false;
+
+ /// \brief True to indicate video recording in progress
+ public: bool recording = false;
+
+ /// \brief mutex to protect the recording variable
+ public: std::mutex recordMutex;
+
+ // --------------------------------------------------------------
+ // CameraTracking
+
/// \brief Move to service
public: std::string moveToService;
@@ -462,33 +499,17 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Follow offset service
public: std::string followOffsetService;
- /// \brief View angle service
- public: std::string viewAngleService;
-
/// \brief Move to pose service
public: std::string moveToPoseService;
- /// \brief Shapes service
- public: std::string shapesService;
-
/// \brief Camera pose topic
public: std::string cameraPoseTopic;
/// \brief Camera pose publisher
public: transport::Node::Publisher cameraPosePub;
- /// \brief lockstep ECM updates with rendering
- public: bool recordVideoLockstep = false;
-
- /// \brief True to indicate video recording in progress
- public: bool recording = false;
-
- /// \brief mutex to protect the recording variable
- public: std::mutex recordMutex;
-
- /// \brief mutex to protect the render condition variable
- /// Used when recording in lockstep mode.
- public: std::mutex renderMutex;
+ // --------------------------------------------------------------
+ // VisualizationCapabilities
/// \brief View transparent service
public: std::string viewTransparentService;
@@ -508,11 +529,39 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief View collisions service
public: std::string viewCollisionsService;
- /// \brief Text for popup error message
- public: QString errorPopupText;
+ // --------------------------------------------------------------
+ // InteractiveViewControl
/// \brief Camera view control service
public: std::string cameraViewControlService;
+
+ // --------------------------------------------------------------
+ // GzSceneManager
+
+ /// \brief Rendering utility
+ public: RenderUtil *renderUtil = nullptr;
+
+ // --------------------------------------------------------------
+ // ViewAngle
+
+ /// \brief View angle service
+ public: std::string viewAngleService;
+
+ // --------------------------------------------------------------
+ // Common to various plugins
+
+ /// \brief Transport node
+ public: transport::Node node;
+
+ /// \brief Name of the world
+ public: std::string worldName;
+
+ /// \brief mutex to protect the render condition variable
+ /// Used when recording in lockstep mode.
+ public: std::mutex renderMutex;
+
+ /// \brief Text for popup error message
+ public: QString errorPopupText;
};
}
}
@@ -2860,10 +2909,12 @@ RenderUtil *RenderWindowItem::RenderUtil() const
Scene3D::Scene3D()
: GuiSystem(), dataPtr(new Scene3DPrivate)
{
+ ignwarn << "The GzScene3D plugin is deprecated on v6 and will be removed on "
+ << "v7. Use MinimalScene together with other plugins as needed."
+ << std::endl;
qmlRegisterType("RenderWindow", 1, 0, "RenderWindow");
}
-
/////////////////////////////////////////////////
Scene3D::~Scene3D() = default;
diff --git a/src/gui/plugins/spawn/Spawn.cc b/src/gui/plugins/spawn/Spawn.cc
index eaac31e183..18d937c161 100644
--- a/src/gui/plugins/spawn/Spawn.cc
+++ b/src/gui/plugins/spawn/Spawn.cc
@@ -27,6 +27,7 @@
#include
#include
+#include
#include
#include
@@ -43,6 +44,7 @@
#include
#include
#include
+#include
#include
#include
@@ -149,6 +151,9 @@ namespace ignition::gazebo
/// \brief Name of the world
public: std::string worldName;
+
+ /// \brief Text for popup error message
+ public: QString errorPopupText;
};
}
@@ -501,10 +506,121 @@ bool Spawn::eventFilter(QObject *_obj, QEvent *_event)
this->dataPtr->escapeReleased = true;
}
}
+ else if (_event->type() == ignition::gui::events::DropOnScene::kType)
+ {
+ auto dropOnSceneEvent =
+ reinterpret_cast(_event);
+ if (dropOnSceneEvent)
+ {
+ this->OnDropped(dropOnSceneEvent);
+ }
+ }
return QObject::eventFilter(_obj, _event);
}
+/////////////////////////////////////////////////
+void Spawn::OnDropped(const ignition::gui::events::DropOnScene *_event)
+{
+ if (nullptr == _event || nullptr == this->dataPtr->camera ||
+ nullptr == this->dataPtr->rayQuery)
+ {
+ return;
+ }
+
+ if (_event->DropText().empty())
+ {
+ this->SetErrorPopupText("Dropped empty entity URI.");
+ return;
+ }
+
+ std::function cb =
+ [](const ignition::msgs::Boolean &_res, const bool _result)
+ {
+ if (!_result || !_res.data())
+ ignerr << "Error creating dropped entity." << std::endl;
+ };
+
+ math::Vector3d pos = ignition::rendering::screenToScene(
+ _event->Mouse(),
+ this->dataPtr->camera,
+ this->dataPtr->rayQuery);
+
+ msgs::EntityFactory req;
+ std::string dropStr = _event->DropText();
+
+ // Local meshes
+ if (QUrl(QString::fromStdString(dropStr)).isLocalFile())
+ {
+ // mesh to sdf model
+ common::rtrim(dropStr);
+
+ if (!common::MeshManager::Instance()->IsValidFilename(dropStr))
+ {
+ QString errTxt = QString::fromStdString("Invalid URI: " + dropStr +
+ "\nOnly Fuel URLs or mesh file types DAE, OBJ, and STL are supported.");
+ this->SetErrorPopupText(errTxt);
+ return;
+ }
+
+ // Fixes whitespace
+ dropStr = common::replaceAll(dropStr, "%20", " ");
+
+ std::string filename = common::basename(dropStr);
+ std::vector splitName = common::split(filename, ".");
+
+ std::string sdf = ""
+ ""
+ ""
+ ""
+ ""
+ ""
+ ""
+ "" + dropStr + ""
+ ""
+ ""
+ ""
+ ""
+ ""
+ ""
+ "" + dropStr + ""
+ ""
+ ""
+ ""
+ ""
+ ""
+ "";
+
+ req.set_sdf(sdf);
+ }
+ // Resource from fuel
+ else
+ {
+ req.set_sdf_filename(dropStr);
+ }
+
+ req.set_allow_renaming(true);
+ msgs::Set(req.mutable_pose(),
+ math::Pose3d(pos.X(), pos.Y(), pos.Z(), 1, 0, 0, 0));
+
+ this->dataPtr->node.Request("/world/" + this->dataPtr->worldName + "/create",
+ req, cb);
+}
+
+/////////////////////////////////////////////////
+QString Spawn::ErrorPopupText() const
+{
+ return this->dataPtr->errorPopupText;
+}
+
+/////////////////////////////////////////////////
+void Spawn::SetErrorPopupText(const QString &_errorTxt)
+{
+ this->dataPtr->errorPopupText = _errorTxt;
+ this->ErrorPopupTextChanged();
+ this->popupError();
+}
+
// Register this plugin
IGNITION_ADD_PLUGIN(ignition::gazebo::Spawn,
ignition::gui::Plugin)
diff --git a/src/gui/plugins/spawn/Spawn.hh b/src/gui/plugins/spawn/Spawn.hh
index b4c0380db1..f87ec4c160 100644
--- a/src/gui/plugins/spawn/Spawn.hh
+++ b/src/gui/plugins/spawn/Spawn.hh
@@ -20,6 +20,7 @@
#include
+#include
#include
namespace ignition
@@ -28,12 +29,20 @@ namespace gazebo
{
class SpawnPrivate;
- /// \brief Allows to spawn models and lights using the spawn gui events.
- // TODO(anyone) Support drag and drop
+ /// \brief Allows to spawn models and lights using the spawn gui events or
+ /// drag and drop.
class Spawn : public ignition::gui::Plugin
{
Q_OBJECT
+ /// \brief Text for popup error
+ Q_PROPERTY(
+ QString errorPopupText
+ READ ErrorPopupText
+ WRITE SetErrorPopupText
+ NOTIFY ErrorPopupTextChanged
+ )
+
/// \brief Constructor
public: Spawn();
@@ -43,9 +52,29 @@ namespace gazebo
// Documentation inherited
public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override;
+ /// \brief Handle drop events.
+ /// \param[in] _event Event with drop information.
+ public: void OnDropped(const ignition::gui::events::DropOnScene *_event);
+
+ /// \brief Get the text for the popup error message
+ /// \return The error text
+ public: Q_INVOKABLE QString ErrorPopupText() const;
+
+ /// \brief Set the text for the popup error message
+ /// \param[in] _errorTxt The error text
+ public: Q_INVOKABLE void SetErrorPopupText(const QString &_errorTxt);
+
// Documentation inherited
protected: bool eventFilter(QObject *_obj, QEvent *_event) override;
+ /// \brief Notify the popup error text has changed
+ signals: void ErrorPopupTextChanged();
+
+ /// \brief Notify that an error has occurred (opens popup)
+ /// Note that the function name needs to start with lowercase in order for
+ /// the connection to work on the QML side
+ signals: void popupError();
+
/// \internal
/// \brief Pointer to private data.
private: std::unique_ptr dataPtr;
diff --git a/src/gui/plugins/spawn/Spawn.qml b/src/gui/plugins/spawn/Spawn.qml
index 873da30014..6f5999a000 100644
--- a/src/gui/plugins/spawn/Spawn.qml
+++ b/src/gui/plugins/spawn/Spawn.qml
@@ -15,14 +15,34 @@
*
*/
-import QtQuick 2.0
-import QtQuick.Controls 2.0
+import QtQuick 2.9
+import QtQuick.Controls 2.2
+import QtQuick.Dialogs 1.0
import QtQuick.Layouts 1.3
-// TODO: remove invisible rectangle, see
-// https://github.com/ignitionrobotics/ign-gui/issues/220
Rectangle {
visible: false
Layout.minimumWidth: 100
Layout.minimumHeight: 100
+
+ Connections {
+ target: Spawn
+ onPopupError: errorPopup.open()
+ }
+
+ Dialog {
+ id: errorPopup
+ parent: ApplicationWindow.overlay
+ modal: true
+ focus: true
+ width: 500
+ height: 200
+ x: (parent.width - width) / 2
+ y: (parent.height - height) / 2
+ title: "Error"
+ Text {
+ text: Spawn.errorPopupText
+ }
+ standardButtons: Dialog.Ok
+ }
}