Skip to content

Commit

Permalink
Support copy/paste (#1013)
Browse files Browse the repository at this point in the history
Signed-off-by: Ashton Larkin <[email protected]>
  • Loading branch information
adlarkin authored Nov 9, 2021
1 parent a28b4a0 commit 3944134
Show file tree
Hide file tree
Showing 17 changed files with 706 additions and 24 deletions.
31 changes: 31 additions & 0 deletions include/ignition/gazebo/rendering/SceneManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include <sdf/Geometry.hh>
#include <sdf/Actor.hh>
Expand Down Expand Up @@ -127,6 +129,30 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
public: rendering::VisualPtr CreateLink(Entity _id,
const sdf::Link &_link, Entity _parentId = 0);

/// \brief Filter a node and its children according to specific criteria.
/// \param[in] _node The name of the node where filtering should start.
/// \param[in] _filter Callback function that defines how _node and its
/// children should be filtered. The function parameter is a node. The
/// callback returns true if the node should be filtered; false otherwise.
/// \return A list of filtered nodes in top level order. This list can
/// contain _node itself, or child nodes of _node. An empty list means no
/// nodes were filtered.
public: std::vector<rendering::NodePtr> Filter(const std::string &_node,
std::function<bool(
const rendering::NodePtr _nodeToFilter)> _filter) const;

/// \brief Copy a visual that currently exists in the scene
/// \param[in] _id Unique visual id of the copied visual
/// \param[in] _visual Name of the visual to copy
/// \param[in] _parentId Parent id of the copied visual
/// \return A pair with the first element being the copied visual object,
/// and the second element being a list of the entity IDs for the copied
/// visual's children, in level order. If copying the visual failed, the
/// first element will be nullptr. If the copied visual has no children, the
/// second element will be empty.
public: std::pair<rendering::VisualPtr, std::vector<Entity>> CopyVisual(
Entity _id, const std::string &_visual, Entity _parentId = 0);

/// \brief Create a visual
/// \param[in] _id Unique visual id
/// \param[in] _visual Visual sdf dom
Expand Down Expand Up @@ -316,6 +342,11 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _jointId Joint visual id.
public: void UpdateJointParentPose(Entity _jointId);

/// \brief Create a unique entity ID
/// \return A unique entity ID. kNullEntity is returned if no unique entity
/// IDs are available
public: Entity UniqueId() const;

/// \internal
/// \brief Pointer to private data class
private: std::unique_ptr<SceneManagerPrivate> dataPtr;
Expand Down
14 changes: 14 additions & 0 deletions src/gui/gui.config
Original file line number Diff line number Diff line change
Expand Up @@ -222,6 +222,20 @@
</ignition-gui>
</plugin>

<!-- Copy/Paste -->
<plugin filename="CopyPaste" name="CopyPaste">
<ignition-gui>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">300</property>
<property key="y" type="double">50</property>
<property key="width" type="double">100</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#777777</property>
</ignition-gui>
</plugin>

<!-- Inspector -->
<plugin filename="ComponentInspector" name="Component inspector">
<ignition-gui>
Expand Down
1 change: 1 addition & 0 deletions src/gui/plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,7 @@ add_subdirectory(modules)
add_subdirectory(align_tool)
add_subdirectory(banana_for_scale)
add_subdirectory(component_inspector)
add_subdirectory(copy_paste)
add_subdirectory(entity_context_menu)
add_subdirectory(entity_tree)
add_subdirectory(joint_position_controller)
Expand Down
4 changes: 4 additions & 0 deletions src/gui/plugins/copy_paste/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
gz_add_gui_plugin(CopyPaste
SOURCES CopyPaste.cc
QT_HEADERS CopyPaste.hh
)
185 changes: 185 additions & 0 deletions src/gui/plugins/copy_paste/CopyPaste.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,185 @@
/*
* 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 <memory>
#include <mutex>
#include <string>

#include <ignition/common/Console.hh>
#include <ignition/gui/Application.hh>
#include <ignition/gui/GuiEvents.hh>
#include <ignition/gui/MainWindow.hh>
#include <ignition/plugin/Register.hh>
#include <ignition/transport.hh>

#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/gui/GuiEvents.hh"

#include "CopyPaste.hh"

namespace ignition::gazebo
{
class CopyPastePrivate
{
/// \brief The entity that is currently selected
public: Entity selectedEntity = kNullEntity;

/// \brief The name of the entity that is currently selected
public: std::string selectedEntityName = "";

/// \brief The name of the entity that is copied
public: std::string copiedData = "";

/// \brief Transport node for handling service calls
public: transport::Node node;

/// \brief Name of the copy service
public: const std::string copyService = "/gui/copy";

/// \brief Name of the paste service
public: const std::string pasteService = "/gui/paste";

/// \brief A mutex to ensure that there are no race conditions between
/// copy/paste
public: std::mutex mutex;
};
}

using namespace ignition;
using namespace gazebo;

/////////////////////////////////////////////////
CopyPaste::CopyPaste()
: GuiSystem(), dataPtr(std::make_unique<CopyPastePrivate>())
{
if (!this->dataPtr->node.Advertise(this->dataPtr->copyService,
&CopyPaste::CopyServiceCB, this))
{
ignerr << "Error advertising service [" << this->dataPtr->copyService
<< "]" << std::endl;
}

if (!this->dataPtr->node.Advertise(this->dataPtr->pasteService,
&CopyPaste::PasteServiceCB, this))
{
ignerr << "Error advertising service [" << this->dataPtr->pasteService
<< "]" << std::endl;
}
}

/////////////////////////////////////////////////
CopyPaste::~CopyPaste() = default;

/////////////////////////////////////////////////
void CopyPaste::LoadConfig(const tinyxml2::XMLElement *)
{
if (this->title.empty())
this->title = "Copy/Paste";

ignition::gui::App()->findChild<
ignition::gui::MainWindow *>()->installEventFilter(this);
ignition::gui::App()->findChild<
ignition::gui::MainWindow *>()->QuickWindow()->installEventFilter(this);
}

/////////////////////////////////////////////////
void CopyPaste::Update(const UpdateInfo &/*_info*/,
EntityComponentManager &_ecm)
{
std::lock_guard<std::mutex> guard(this->dataPtr->mutex);
auto nameComp =
_ecm.Component<components::Name>(this->dataPtr->selectedEntity);
if (!nameComp)
return;
this->dataPtr->selectedEntityName = nameComp->Data();
}

/////////////////////////////////////////////////
void CopyPaste::OnCopy()
{
std::lock_guard<std::mutex> guard(this->dataPtr->mutex);
this->dataPtr->copiedData = this->dataPtr->selectedEntityName;
}

/////////////////////////////////////////////////
void CopyPaste::OnPaste()
{
std::lock_guard<std::mutex> guard(this->dataPtr->mutex);

// we should only paste if something has been copied
if (!this->dataPtr->copiedData.empty())
{
ignition::gui::events::SpawnCloneFromName event(this->dataPtr->copiedData);
ignition::gui::App()->sendEvent(
ignition::gui::App()->findChild<ignition::gui::MainWindow *>(),
&event);
}
}

/////////////////////////////////////////////////
bool CopyPaste::eventFilter(QObject *_obj, QEvent *_event)
{
if (_event->type() == ignition::gazebo::gui::events::EntitiesSelected::kType)
{
std::lock_guard<std::mutex> guard(this->dataPtr->mutex);

auto selectedEvent =
reinterpret_cast<gui::events::EntitiesSelected *>(_event);
if (selectedEvent && (selectedEvent->Data().size() == 1u))
this->dataPtr->selectedEntity = selectedEvent->Data()[0];
}
if (_event->type() == QEvent::KeyPress)
{
QKeyEvent *keyEvent = static_cast<QKeyEvent *>(_event);
if (keyEvent && keyEvent->matches(QKeySequence::Copy))
{
this->OnCopy();
}
else if (keyEvent && keyEvent->matches(QKeySequence::Paste))
{
this->OnPaste();
}
}

// Standard event processing
return QObject::eventFilter(_obj, _event);
}

/////////////////////////////////////////////////
bool CopyPaste::CopyServiceCB(const ignition::msgs::StringMsg &_req,
ignition::msgs::Boolean &_resp)
{
{
std::lock_guard<std::mutex> guard(this->dataPtr->mutex);
this->dataPtr->copiedData = _req.data();
}
_resp.set_data(true);
return true;
}

/////////////////////////////////////////////////
bool CopyPaste::PasteServiceCB(const ignition::msgs::Empty &/*_req*/,
ignition::msgs::Boolean &_resp)
{
this->OnPaste();
_resp.set_data(true);
return true;
}

// Register this plugin
IGNITION_ADD_PLUGIN(ignition::gazebo::CopyPaste,
ignition::gui::Plugin)
83 changes: 83 additions & 0 deletions src/gui/plugins/copy_paste/CopyPaste.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
/*
* 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_GAZEBO_GUI_COPYPASTE_HH_
#define IGNITION_GAZEBO_GUI_COPYPASTE_HH_

#include <memory>

#include <ignition/msgs.hh>

#include "ignition/gazebo/gui/GuiSystem.hh"

namespace ignition
{
namespace gazebo
{
class CopyPastePrivate;

/// \brief Plugin for copying/pasting entities in the GUI.
class CopyPaste : public ignition::gazebo::GuiSystem
{
Q_OBJECT

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

/// \brief Destructor
public: ~CopyPaste() override;

// Documentation inherited
public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override;

// Documentation inherited
public: void Update(const UpdateInfo &_info,
EntityComponentManager &_ecm) override;

/// \brief Callback to copy the selected entity
public slots: void OnCopy();

/// \brief Callback to paste the data that has been copied, if copied data
/// exists.
public slots: void OnPaste();

// Documentation inherited
protected: bool eventFilter(QObject *_obj, QEvent *_event) override;

/// \brief Callback for handling a copy service request
/// \param[in] _req The service request, which contains the name of the
/// entity to be copied
/// \param[out] _resp The service response
/// \return Whether the service was successful (true) or not (false)
private: bool CopyServiceCB(const ignition::msgs::StringMsg &_req,
ignition::msgs::Boolean &_resp);

/// \brief Callback for handling a paste service request
/// \param[in] _req The service request
/// \param[out] _resp The service response
/// \return Whether the service was successful (true) or not (false)
private: bool PasteServiceCB(const ignition::msgs::Empty &_req,
ignition::msgs::Boolean &_resp);

/// \internal
/// \brief Pointer to private data
private: std::unique_ptr<CopyPastePrivate> dataPtr;
};
}
}

#endif
Loading

0 comments on commit 3944134

Please sign in to comment.