Skip to content

Commit

Permalink
Add EnvironmentalData component (#1616)
Browse files Browse the repository at this point in the history
* Add EnvironmentalData component
* Add EnvironmentalDataPreload plugin
* Add EnvironmentalDataLoader GUI plugin
* Add spatial reference to EnvironmentData
* Resolve paths relative to SDF parent path
* Avoid template instantiation in plugins
* Make EnvironmentData visible in Windows
* Disable EnvironmentPreload test on Windows

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic committed Nov 14, 2022
1 parent 39520a1 commit 2d19f93
Show file tree
Hide file tree
Showing 19 changed files with 1,269 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,7 @@ gz_find_package(gz-common5
profiler
events
av
io
REQUIRED
)
set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR})
Expand Down
77 changes: 77 additions & 0 deletions include/gz/sim/components/Environment.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
/*
* Copyright (C) 2022 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_ENVIRONMENT_HH_
#define GZ_SIM_ENVIRONMENT_HH_

#include <memory>
#include <string>

#include <gz/common/DataFrame.hh>
#include <gz/math/SphericalCoordinates.hh>
#include <gz/math/TimeVaryingVolumetricGrid.hh>

#include <gz/sim/components/Factory.hh>
#include <gz/sim/components/Component.hh>
#include <gz/sim/Export.hh>

namespace gz
{
namespace sim
{
// Inline bracket to help doxygen filtering.
inline namespace GZ_SIM_VERSION_NAMESPACE {
namespace components
{
/// \brief Environment data across time and space. This is useful to
/// introduce physical quantities that may be of interest even if not
/// modelled in simulation.
struct GZ_SIM_VISIBLE EnvironmentalData
{
using T = math::InMemoryTimeVaryingVolumetricGrid<double>;
using FrameT = common::DataFrame<std::string, T>;
using ReferenceT = math::SphericalCoordinates::CoordinateType;

/// \brief Instantiate environmental data.
///
/// An std::make_shared equivalent that ensures
/// dynamically loaded call sites use a template
/// instantiation that is guaranteed to outlive
/// them.
static std::shared_ptr<EnvironmentalData>
MakeShared(FrameT _frame, ReferenceT _reference);

/// \brief Environmental data frame.
FrameT frame;

/// \brief Spatial reference for data coordinates.
ReferenceT reference;
};

/// \brief A component type that contains a environment data.
/// Ownership is shared to avoid data copies unless necessary.
using Environment =
Component<std::shared_ptr<EnvironmentalData>, class EnvironmentalDataTag>;

GZ_SIM_REGISTER_COMPONENT(
"gz_sim_components.Environment", Environment)
}
}
}
}

#endif
5 changes: 5 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,10 @@ set(comms_sources
comms/MsgManager.cc
)

set(component_sources
components/Environment.cc
)

set(gui_sources
${gui_sources}
PARENT_SCOPE
Expand Down Expand Up @@ -68,6 +72,7 @@ set (sources
${PROTO_PRIVATE_SRC}
${network_sources}
${comms_sources}
${component_sources}
)

set (gtest_sources
Expand Down
32 changes: 32 additions & 0 deletions src/components/Environment.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
/*
* Copyright (C) 2022 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 "gz/sim/components/Environment.hh"

#include <memory>
#include <utility>

using namespace gz::sim::components;

std::shared_ptr<EnvironmentalData>
EnvironmentalData::MakeShared(FrameT _frame, ReferenceT _reference)
{
auto data = std::make_shared<EnvironmentalData>();
data->frame = std::move(_frame);
data->reference = _reference;
return data;
}
1 change: 1 addition & 0 deletions src/gui/plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,7 @@ add_subdirectory(component_inspector_editor)
add_subdirectory(copy_paste)
add_subdirectory(entity_context_menu)
add_subdirectory(entity_tree)
add_subdirectory(environment_loader)
add_subdirectory(joint_position_controller)
add_subdirectory(lights)
add_subdirectory(playback_scrubber)
Expand Down
8 changes: 8 additions & 0 deletions src/gui/plugins/environment_loader/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
gz_add_gui_plugin(EnvironmentLoader
SOURCES EnvironmentLoader.cc
QT_HEADERS EnvironmentLoader.hh
PRIVATE_LINK_LIBS
gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
gz-common${GZ_COMMON_VER}::io
gz-math${GZ_MATH_VER}::gz-math${GZ_MATH_VER}
)
Loading

0 comments on commit 2d19f93

Please sign in to comment.