Skip to content
Open
Show file tree
Hide file tree
Changes from 16 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
1 change: 1 addition & 0 deletions src/gui/plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,7 @@ add_subdirectory(entity_context_menu)
add_subdirectory(entity_tree)
add_subdirectory(environment_loader)
add_subdirectory(environment_visualization)
add_subdirectory(export_occupancy)
add_subdirectory(global_illumination_civct)
add_subdirectory(global_illumination_vct)
add_subdirectory(joint_position_controller)
Expand Down
8 changes: 8 additions & 0 deletions src/gui/plugins/export_occupancy/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
gz_add_gui_plugin(ExportOccupancy
SOURCES ExportOccupancy.cc
QT_HEADERS ExportOccupancy.hh
PRIVATE_LINK_LIBS
gz-common::gz-common
gz-common::io
gz-math::gz-math
)
158 changes: 158 additions & 0 deletions src/gui/plugins/export_occupancy/ExportOccupancy.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,158 @@
/*
* Copyright (C) 2025 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 "ExportOccupancy.hh"
#include <gz/msgs/entity_factory.pb.h>
#include <gz/gui/Application.hh>
#include <gz/gui/MainWindow.hh>
#include <gz/plugin/Register.hh>
#include <gz/transport/Node.hh>

#include "gz/sim/Util.hh"
#include "gz/sim/World.hh"

#include <sstream>
#include <string>

using namespace gz;
using namespace sim;

class gz::sim::ExportOccupancyUiPrivate
{
public: std::string worldName;
};

ExportOccupancyUi::ExportOccupancyUi() :
dataPtr(std::make_unique<ExportOccupancyUiPrivate>())
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

include <memory>

{
gui::App()->Engine()->rootContext()->setContextProperty(
"exportOccupancy", this);
}

ExportOccupancyUi::~ExportOccupancyUi()
{

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change

}

void ExportOccupancyUi::LoadConfig(
const tinyxml2::XMLElement *_pluginElem)
{
if (this->title.empty())
this->title = "Export Occupancy";

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

void ExportOccupancyUi::Update(const UpdateInfo &,
EntityComponentManager &_ecm)
{
auto world = World(worldEntity(_ecm));
if (!world.Valid(_ecm)) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (!world.Valid(_ecm)) {
if (!world.Valid(_ecm))
{

gzerr << "Could not get running world" << std::endl;
return;
}
if (!world.Name(_ecm).has_value())
{
return;
}
this->dataPtr->worldName = world.Name(_ecm).value();
}

void ExportOccupancyUi::StartExport(double _samples, double _range,
double _rangeRes, double _angularRes,
double _distanceFromGround, double _gridResolution,
std::size_t _numWidth, std::size_t _numHeight)
{
gz::msgs::EntityFactory factoryReq;
std::stringstream ss;
ss << R"(
<sdf version="1.6">
<model name="model_with_lidar">
<pose>-1.5 -1.5 )" << _distanceFromGround << R"( 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.1</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>

<sensor name='gpu_lidar' type='gpu_lidar'>
<topic>freespace_explorer/scan</topic>
<update_rate>10</update_rate>
<lidar>
<scan>
<horizontal>
<samples>)"<< _samples << R"(</samples>
<resolution>)" << _angularRes << R"(</resolution>
<min_angle>0</min_angle>
<max_angle>6.28</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>)"<< _range << R"(</max>
<resolution>)"<< _rangeRes <<R"(</resolution>
</range>
</lidar>
<visualize>true</visualize>
</sensor>
</link>
<static>true</static>

<plugin
filename="gz-sim-free-space-explorer-system"
name="gz::sim::systems::FreeSpaceExplorer">
<lidar_topic>freespace_explorer/scan</lidar_topic>
<width>)" << _numWidth << R"(</width>
<height>)" << _numHeight << R"(</height>
<resolution>)" << _gridResolution << R"(</resolution>
<sensor_link>link</sensor_link>
</plugin>
</model>
</sdf>
)";

gzerr << ss.str() <<std::endl;
factoryReq.set_sdf(ss.str());

gz::transport::Node node;
std::function<void(const msgs::Boolean &, const bool)> cb =
[](const msgs::Boolean &/*_rep*/, const bool _result)
{};
node.Request("/world/" + this->dataPtr->worldName + "/create",
factoryReq, cb);
}

// Register this plugin
GZ_ADD_PLUGIN(gz::sim::ExportOccupancyUi, gz::gui::Plugin)
66 changes: 66 additions & 0 deletions src/gui/plugins/export_occupancy/ExportOccupancy.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
/*
* Copyright (C) 2025 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 GZ_SIM_GUI_EXPORT_OCCUPANCY_HH_
#define GZ_SIM_GUI_EXPORT_OCCUPANCY_HH_

#include <memory>

#include "gz/sim/gui/GuiSystem.hh"
#include "gz/gui/qt.h"

namespace gz
{
namespace sim
{
// Inline bracket to help doxygen filtering.
inline namespace GZ_SIM_VERSION_NAMESPACE
{
class ExportOccupancyUiPrivate;

/// \brief A GUI plugin for a user to export the occupancy
/// grid of the current world.
class ExportOccupancyUi : public gz::sim::GuiSystem
{
Q_OBJECT
/// \brief Constructor
public: ExportOccupancyUi();

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

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

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

/// Triggers the export of our
public: Q_INVOKABLE void StartExport(double _samples, double _range,
double _rangeRes, double _angularRes,
double _distanceFromGround, double _gridResolution,
std::size_t _numWidth, std::size_t _numHeight);

/// \internal
/// \brief Pointer to private data
private: std::unique_ptr<ExportOccupancyUiPrivate> dataPtr;
};
}
}
}
#endif
Loading
Loading