Skip to content

Commit

Permalink
Drop from fuel plugin
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Sep 21, 2021
1 parent 4195c7e commit 44ffff4
Show file tree
Hide file tree
Showing 8 changed files with 349 additions and 0 deletions.
10 changes: 10 additions & 0 deletions examples/worlds/minimal_scene.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,16 @@ Missing for parity with GzScene3D:
<iterations>true</iterations>
</plugin>

<plugin filename="DropFromFuel" name="drop_from_fuel">
<ignition-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</ignition-gui>
</plugin>

<plugin filename="Spawn" name="Spawn Entities">
<ignition-gui>
<anchors target="Select entities">
Expand Down
10 changes: 10 additions & 0 deletions src/gui/gui.config
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,16 @@
</ignition-gui>
</plugin>

<plugin filename="DropFromFuel" name="drop_from_fuel">
<ignition-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</ignition-gui>
</plugin>

<plugin filename="Spawn" name="Spawn Entities">
<ignition-gui>
<anchors target="Select entities">
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(drop_from_fuel)
add_subdirectory(entity_context_menu)
add_subdirectory(entity_tree)
add_subdirectory(joint_position_controller)
Expand Down
8 changes: 8 additions & 0 deletions src/gui/plugins/drop_from_fuel/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
gz_add_gui_plugin(DropFromFuel
SOURCES
DropFromFuel.cc
QT_HEADERS
DropFromFuel.hh
PUBLIC_LINK_LIBS
${PROJECT_LIBRARY_TARGET_NAME}-rendering
)
231 changes: 231 additions & 0 deletions src/gui/plugins/drop_from_fuel/DropFromFuel.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,231 @@
/*
* 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 "DropFromFuel.hh"

#include <string>
#include <vector>

#include <ignition/math/Vector2.hh>

#include <ignition/msgs/boolean.pb.h>

#include <ignition/common/Console.hh>
#include <ignition/common/Profiler.hh>
#include <ignition/common/MeshManager.hh>

#include <ignition/gui/Application.hh>
#include <ignition/gui/GuiEvents.hh>
#include <ignition/gui/Helpers.hh>
#include <ignition/gui/MainWindow.hh>

#include <ignition/plugin/Register.hh>

#include <ignition/rendering/RenderingIface.hh>
#include <ignition/rendering/Utils.hh>

#include <ignition/transport/Node.hh>

#include <sdf/Root.hh>

namespace ignition::gazebo
{
class DropFromFuelPrivate
{
/// \brief Update the 3D scene with new entities
public: void OnRender();

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

/// \brief Pointer to the rendering scene
public: rendering::ScenePtr scene{nullptr};

/// \brief Ray query for mouse clicks
public: rendering::RayQueryPtr rayQuery{nullptr};

/// \brief Transport node for making transform control requests
public: ignition::transport::Node node;

/// \brief Name of the world
public: std::string worldName;
};
}

using namespace ignition;
using namespace gazebo;

/////////////////////////////////////////////////
void DropFromFuelPrivate::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<rendering::Camera>(
this->scene->NodeByIndex(i));
if (cam)
{
if (std::get<bool>(cam->UserData("user-camera")))
{
this->camera = cam;

// Ray Query
this->rayQuery = this->camera->Scene()->CreateRayQuery();

igndbg << "DropFromFuel plugin is using camera ["
<< this->camera->Name() << "]" << std::endl;
break;
}
}
}
}
}

/////////////////////////////////////////////////
DropFromFuel::DropFromFuel()
: ignition::gui::Plugin(),
dataPtr(std::make_unique<DropFromFuelPrivate>())
{
}

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

/////////////////////////////////////////////////
void DropFromFuel::LoadConfig(const tinyxml2::XMLElement *)
{
if (this->title.empty())
this->title = "Drop from fuel";

// World name from window, to construct default topics and services
auto worldNames = gui::worldNames();
if (!worldNames.empty())
this->dataPtr->worldName = worldNames[0].toStdString();

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

////////////////////////////////////////////////
bool DropFromFuel::eventFilter(QObject *_obj, QEvent *_event)
{
if (_event->type() == ignition::gui::events::Render::kType)
{
this->dataPtr->OnRender();
}
else if (_event->type() == ignition::gui::events::DropOnScene::kType)
{
auto dropOnSceneEvent =
reinterpret_cast<ignition::gui::events::DropOnScene *>(_event);
if (dropOnSceneEvent)
{
if (dropOnSceneEvent->DropText().empty())
{
ignerr << "Dropped empty entity URI.\n";
}
else
{
if (this->dataPtr->camera && this->dataPtr->rayQuery)
{
std::function<void(const ignition::msgs::Boolean &, const bool)> 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(
dropOnSceneEvent->Mouse(),
this->dataPtr->camera,
this->dataPtr->rayQuery);

msgs::EntityFactory req;
std::string dropStr = dropOnSceneEvent->DropText();
if (QUrl(QString(dropStr.c_str())).isLocalFile())
{
// mesh to sdf model
common::rtrim(dropStr);

if (!common::MeshManager::Instance()->IsValidFilename(dropStr))
{
ignerr << "Invalid URI: " + dropStr +
"\nOnly Fuel URLs or mesh file types DAE, OBJ, and STL"
"are supported.";
return QObject::eventFilter(_obj, _event);
}

// Fixes whitespace
dropStr = common::replaceAll(dropStr, "%20", " ");

std::string filename = common::basename(dropStr);
std::vector<std::string> splitName = common::split(filename, ".");

std::string sdf = "<?xml version='1.0'?>"
"<sdf version='" + std::string(SDF_PROTOCOL_VERSION) + "'>"
"<model name='" + splitName[0] + "'>"
"<link name='link'>"
"<visual name='visual'>"
"<geometry>"
"<mesh>"
"<uri>" + dropStr + "</uri>"
"</mesh>"
"</geometry>"
"</visual>"
"<collision name='collision'>"
"<geometry>"
"<mesh>"
"<uri>" + dropStr + "</uri>"
"</mesh>"
"</geometry>"
"</collision>"
"</link>"
"</model>"
"</sdf>";

req.set_sdf(sdf);
}
else
{
// model from fuel
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);
}
}
}
}

return QObject::eventFilter(_obj, _event);
}

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

#include <memory>

#include <ignition/gui/Plugin.hh>

namespace ignition
{
namespace gazebo
{
class DropFromFuelPrivate;

/// \brief Allows to DropFromFuel models and lights using te gui event
/// DropFromFuelFromDescription
class DropFromFuel : public ignition::gui::Plugin
{
Q_OBJECT

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

/// \brief Destructor
public: ~DropFromFuel() 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<DropFromFuelPrivate> dataPtr;
};
}
}

#endif
28 changes: 28 additions & 0 deletions src/gui/plugins/drop_from_fuel/DropFromFuel.qml
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
/*
* 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

// TODO: remove invisible rectangle, see
// https://github.com/ignitionrobotics/ign-gui/issues/220
Rectangle {
visible: false
Layout.minimumWidth: 100
Layout.minimumHeight: 100
}
5 changes: 5 additions & 0 deletions src/gui/plugins/drop_from_fuel/DropFromFuel.qrc
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<!DOCTYPE RCC><RCC version="1.0">
<qresource prefix="DropFromFuel/">
<file>DropFromFuel.qml</file>
</qresource>
</RCC>

0 comments on commit 44ffff4

Please sign in to comment.