From 2d19f9312c87752f50a6b9792bccc46519ed940d Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Mon, 14 Nov 2022 20:08:29 -0300 Subject: [PATCH 1/6] Add EnvironmentalData component (#1616) * 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 --- CMakeLists.txt | 1 + include/gz/sim/components/Environment.hh | 77 +++++ src/CMakeLists.txt | 5 + src/components/Environment.cc | 32 ++ src/gui/plugins/CMakeLists.txt | 1 + .../plugins/environment_loader/CMakeLists.txt | 8 + .../environment_loader/EnvironmentLoader.cc | 319 ++++++++++++++++++ .../environment_loader/EnvironmentLoader.hh | 206 +++++++++++ .../environment_loader/EnvironmentLoader.qml | 216 ++++++++++++ .../environment_loader/EnvironmentLoader.qrc | 5 + src/systems/CMakeLists.txt | 1 + .../environment_preload/CMakeLists.txt | 8 + .../environment_preload/EnvironmentPreload.cc | 172 ++++++++++ .../environment_preload/EnvironmentPreload.hh | 70 ++++ test/integration/CMakeLists.txt | 1 + .../integration/environment_preload_system.cc | 92 +++++ test/worlds/CMakeLists.txt | 1 + test/worlds/environmental_data.csv | 9 + test/worlds/environmental_data.sdf.in | 45 +++ 19 files changed, 1269 insertions(+) create mode 100644 include/gz/sim/components/Environment.hh create mode 100644 src/components/Environment.cc create mode 100644 src/gui/plugins/environment_loader/CMakeLists.txt create mode 100644 src/gui/plugins/environment_loader/EnvironmentLoader.cc create mode 100644 src/gui/plugins/environment_loader/EnvironmentLoader.hh create mode 100644 src/gui/plugins/environment_loader/EnvironmentLoader.qml create mode 100644 src/gui/plugins/environment_loader/EnvironmentLoader.qrc create mode 100644 src/systems/environment_preload/CMakeLists.txt create mode 100644 src/systems/environment_preload/EnvironmentPreload.cc create mode 100644 src/systems/environment_preload/EnvironmentPreload.hh create mode 100644 test/integration/environment_preload_system.cc create mode 100644 test/worlds/environmental_data.csv create mode 100644 test/worlds/environmental_data.sdf.in diff --git a/CMakeLists.txt b/CMakeLists.txt index cd4d24b1bd..ac5b635f3b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -93,6 +93,7 @@ gz_find_package(gz-common5 profiler events av + io REQUIRED ) set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR}) diff --git a/include/gz/sim/components/Environment.hh b/include/gz/sim/components/Environment.hh new file mode 100644 index 0000000000..a0e721e8cd --- /dev/null +++ b/include/gz/sim/components/Environment.hh @@ -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 +#include + +#include +#include +#include + +#include +#include +#include + +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; + using FrameT = common::DataFrame; + 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 + 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, class EnvironmentalDataTag>; + + GZ_SIM_REGISTER_COMPONENT( + "gz_sim_components.Environment", Environment) +} +} +} +} + +#endif diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 9ff752e95a..05dc466ccc 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -32,6 +32,10 @@ set(comms_sources comms/MsgManager.cc ) +set(component_sources + components/Environment.cc +) + set(gui_sources ${gui_sources} PARENT_SCOPE @@ -68,6 +72,7 @@ set (sources ${PROTO_PRIVATE_SRC} ${network_sources} ${comms_sources} + ${component_sources} ) set (gtest_sources diff --git a/src/components/Environment.cc b/src/components/Environment.cc new file mode 100644 index 0000000000..65232966c4 --- /dev/null +++ b/src/components/Environment.cc @@ -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 +#include + +using namespace gz::sim::components; + +std::shared_ptr +EnvironmentalData::MakeShared(FrameT _frame, ReferenceT _reference) +{ + auto data = std::make_shared(); + data->frame = std::move(_frame); + data->reference = _reference; + return data; +} diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt index e79bf59acb..7d092c36dc 100644 --- a/src/gui/plugins/CMakeLists.txt +++ b/src/gui/plugins/CMakeLists.txt @@ -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) diff --git a/src/gui/plugins/environment_loader/CMakeLists.txt b/src/gui/plugins/environment_loader/CMakeLists.txt new file mode 100644 index 0000000000..dbd24887ce --- /dev/null +++ b/src/gui/plugins/environment_loader/CMakeLists.txt @@ -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} +) diff --git a/src/gui/plugins/environment_loader/EnvironmentLoader.cc b/src/gui/plugins/environment_loader/EnvironmentLoader.cc new file mode 100644 index 0000000000..c7ec575e0f --- /dev/null +++ b/src/gui/plugins/environment_loader/EnvironmentLoader.cc @@ -0,0 +1,319 @@ +/* + * 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 "EnvironmentLoader.hh" + +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include + +#include +#include + +using namespace gz; +using namespace sim; + +namespace gz +{ +namespace sim +{ +inline namespace GZ_SIM_VERSION_NAMESPACE +{ +/// \brief Private data class for EnvironmentLoader +class EnvironmentLoaderPrivate +{ + /// \brief Path to environmental data file to load. + public: QString dataPath; + + /// \brief List of environmental data dimensions + /// (ie. columns if dealing with CSV data). + public: QStringList dimensionList; + + /// \brief Index of data dimension to be used as time. + public: int timeIndex{-1}; + + /// \brief Index of data dimension to be used as x coordinate. + public: int xIndex{-1}; + + /// \brief Index of data dimension to be used as y coordinate. + public: int yIndex{-1}; + + /// \brief Index of data dimension to be used as z coordinate. + public: int zIndex{-1}; + + public: using ReferenceT = math::SphericalCoordinates::CoordinateType; + + /// \brief Map of supported spatial references. + public: const QMap referenceMap{ + {QString("global"), math::SphericalCoordinates::GLOBAL}, + {QString("spherical"), math::SphericalCoordinates::SPHERICAL}, + {QString("ecef"), math::SphericalCoordinates::ECEF}}; + + /// \brief Spatial reference. + public: QString reference; + + /// \brief To synchronize member access. + public: std::mutex mutex; + + /// \brief Whether to attempt an environmental data load. + public: std::atomic needsLoad{false}; +}; +} +} +} + +///////////////////////////////////////////////// +EnvironmentLoader::EnvironmentLoader() + : GuiSystem(), dataPtr(new EnvironmentLoaderPrivate) +{ + gui::App()->Engine()->rootContext()->setContextProperty( + "EnvironmentLoader", this); +} + +///////////////////////////////////////////////// +EnvironmentLoader::~EnvironmentLoader() +{ +} + +///////////////////////////////////////////////// +void EnvironmentLoader::LoadConfig(const tinyxml2::XMLElement *) +{ + if (this->title.empty()) + this->title = "Environment Loader"; + + gui::App()->findChild()->installEventFilter(this); +} + +///////////////////////////////////////////////// +void EnvironmentLoader::Update(const UpdateInfo &, + EntityComponentManager &_ecm) +{ + if (this->dataPtr->needsLoad) + { + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->needsLoad = false; + + std::ifstream dataFile(this->dataPtr->dataPath.toStdString()); + gzmsg << "Loading environmental data from " + << this->dataPtr->dataPath.toStdString() + << std::endl; + try + { + using ComponentDataT = components::EnvironmentalData; + auto data = ComponentDataT::MakeShared( + common::IO::ReadFrom( + common::CSVIStreamIterator(dataFile), + common::CSVIStreamIterator(), + this->dataPtr->timeIndex, { + static_cast(this->dataPtr->xIndex), + static_cast(this->dataPtr->yIndex), + static_cast(this->dataPtr->zIndex)}), + this->dataPtr->referenceMap[this->dataPtr->reference]); + + using ComponentT = components::Environment; + _ecm.CreateComponent(worldEntity(_ecm), ComponentT{std::move(data)}); + } + catch (const std::invalid_argument &exc) + { + gzerr << "Failed to load environmental data" << std::endl + << exc.what() << std::endl; + } + } +} + +///////////////////////////////////////////////// +void EnvironmentLoader::ScheduleLoad() +{ + this->dataPtr->needsLoad = this->IsConfigured(); +} + +///////////////////////////////////////////////// +QString EnvironmentLoader::DataPath() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->dataPath; +} + +///////////////////////////////////////////////// +void EnvironmentLoader::SetDataUrl(QUrl _dataUrl) +{ + this->SetDataPath(_dataUrl.path()); +} + +///////////////////////////////////////////////// +void EnvironmentLoader::SetDataPath(QString _dataPath) +{ + { + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->dataPath = _dataPath; + + std::ifstream dataFile(_dataPath.toStdString()); + if (!dataFile.is_open()) + { + gzerr << "No environmental data file was found at " + << this->dataPtr->dataPath.toStdString() + << std::endl; + this->dataPtr->dataPath.clear(); + return; + } + const common::CSVIStreamIterator iterator(dataFile); + if (iterator == common::CSVIStreamIterator()) + { + gzerr << "Failed to load environmental data at " + << this->dataPtr->dataPath.toStdString() + << std::endl; + this->dataPtr->dataPath.clear(); + return; + } + const std::vector &header = *iterator; + this->dataPtr->dimensionList.clear(); + this->dataPtr->dimensionList.reserve(header.size()); + for (const std::string &dimension : header) + { + this->dataPtr->dimensionList.push_back( + QString::fromStdString(dimension)); + } + } + + this->DataPathChanged(); + this->DimensionListChanged(); + this->IsConfiguredChanged(); +} + +///////////////////////////////////////////////// +QStringList EnvironmentLoader::DimensionList() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->dimensionList; +} + +///////////////////////////////////////////////// +int EnvironmentLoader::TimeIndex() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->timeIndex; +} + +///////////////////////////////////////////////// +void EnvironmentLoader::SetTimeIndex(int _timeIndex) +{ + { + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->timeIndex = _timeIndex; + } + this->IsConfiguredChanged(); +} + +///////////////////////////////////////////////// +int EnvironmentLoader::XIndex() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->xIndex; +} + +///////////////////////////////////////////////// +void EnvironmentLoader::SetXIndex(int _xIndex) +{ + { + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->xIndex = _xIndex; + } + this->IsConfiguredChanged(); +} + +///////////////////////////////////////////////// +int EnvironmentLoader::YIndex() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->yIndex; +} + +///////////////////////////////////////////////// +void EnvironmentLoader::SetYIndex(int _yIndex) +{ + { + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->yIndex = _yIndex; + } + this->IsConfiguredChanged(); +} + +///////////////////////////////////////////////// +int EnvironmentLoader::ZIndex() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->zIndex; +} + +///////////////////////////////////////////////// +void EnvironmentLoader::SetZIndex(int _zIndex) +{ + { + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->zIndex = _zIndex; + } + this->IsConfiguredChanged(); +} + +///////////////////////////////////////////////// +QStringList EnvironmentLoader::ReferenceList() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->referenceMap.keys(); +} + +///////////////////////////////////////////////// +QString EnvironmentLoader::Reference() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->reference; +} + +///////////////////////////////////////////////// +void EnvironmentLoader::SetReference(QString _reference) +{ + { + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->reference = _reference; + } + this->IsConfiguredChanged(); +} + +///////////////////////////////////////////////// +bool EnvironmentLoader::IsConfigured() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return ( + !this->dataPtr->dataPath.isEmpty() && + this->dataPtr->timeIndex != -1 && + this->dataPtr->xIndex != -1 && + this->dataPtr->yIndex != -1 && + this->dataPtr->zIndex != -1 && + !this->dataPtr->reference.isEmpty()); +} + +// Register this plugin +GZ_ADD_PLUGIN(gz::sim::EnvironmentLoader, gz::gui::Plugin) diff --git a/src/gui/plugins/environment_loader/EnvironmentLoader.hh b/src/gui/plugins/environment_loader/EnvironmentLoader.hh new file mode 100644 index 0000000000..08ab2b773c --- /dev/null +++ b/src/gui/plugins/environment_loader/EnvironmentLoader.hh @@ -0,0 +1,206 @@ +/* + * 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_GUI_ENVIRONMENTLOADER_HH_ +#define GZ_SIM_GUI_ENVIRONMENTLOADER_HH_ + +#include + +#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 EnvironmentLoaderPrivate; + + /// \class EnvironmentLoader EnvironmentLoader.hh + /// gz/sim/systems/EnvironmentLoader.hh + /// \brief A GUI plugin for a user to load an Environment + /// component into the ECM on a live simulation. + class EnvironmentLoader : public gz::sim::GuiSystem + { + Q_OBJECT + + /// \brief Data path + Q_PROPERTY( + QString dataPath + READ DataPath + WRITE SetDataPath + NOTIFY DataPathChanged + ) + + /// \brief Dimension list + Q_PROPERTY( + QStringList dimensionList + READ DimensionList + NOTIFY DimensionListChanged + ) + + /// \brief Time index + Q_PROPERTY( + int timeIndex + READ TimeIndex + WRITE SetTimeIndex + NOTIFY TimeIndexChanged + ) + + /// \brief X dimension + Q_PROPERTY( + int xIndex + READ XIndex + WRITE SetXIndex + NOTIFY XIndexChanged + ) + + /// \brief Y dimension + Q_PROPERTY( + int yIndex + READ YIndex + WRITE SetYIndex + NOTIFY YIndexChanged + ) + + /// \brief Z dimension + Q_PROPERTY( + int zIndex + READ ZIndex + WRITE SetZIndex + NOTIFY ZIndexChanged + ) + + /// \brief Spatial reference type list + Q_PROPERTY( + QStringList referenceList + READ ReferenceList + ) + + /// \brief Spatial reference + Q_PROPERTY( + QString reference + READ Reference + WRITE SetReference + NOTIFY ReferenceChanged + ) + + /// \brief Configuration ready + Q_PROPERTY( + bool configured + READ IsConfigured + NOTIFY IsConfiguredChanged + ) + + /// \brief Constructor + public: EnvironmentLoader(); + + /// \brief Destructor + public: ~EnvironmentLoader() override; + + // Documentation inherited + public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; + + // Documentation inherited + public: void Update(const UpdateInfo &, + EntityComponentManager &_ecm) override; + + /// \brief Get path to the data file to be loaded + public: Q_INVOKABLE QString DataPath() const; + + /// \brief Notify that the path to the data file (potentially) changed + signals: void DataPathChanged(); + + /// \brief Set the path to the data file to be loaded + public: Q_INVOKABLE void SetDataPath(QString _dataPath); + + /// \brief Set the URL pointing to the data file to be loaded + public: Q_INVOKABLE void SetDataUrl(QUrl _dataUrl); + + /// \brief Get dimensions available in the data file + public: Q_INVOKABLE QStringList DimensionList() const; + + /// \brief Notify that the list of dimensions has changed + signals: void DimensionListChanged(); + + /// \brief Get index of the time dimension in the list + public: Q_INVOKABLE int TimeIndex() const; + + /// \brief Set index of the time dimension in the list + public: Q_INVOKABLE void SetTimeIndex(int _timeIndex); + + /// \brief Notify the time dimension index has changed + signals: void TimeIndexChanged() const; + + /// \brief Get index of the x dimension in the list + public: Q_INVOKABLE int XIndex() const; + + /// \brief Set index of the x dimension in the list + public: Q_INVOKABLE void SetXIndex(int _xIndex); + + /// \brief Notify the x dimension index has changed + signals: void XIndexChanged() const; + + /// \brief Get index of the y dimension in the list + public: Q_INVOKABLE int YIndex() const; + + /// \brief Notify the y dimension index has changed + signals: void YIndexChanged() const; + + /// \brief Set index of the y dimension in the list + public: Q_INVOKABLE void SetYIndex(int _yIndex); + + /// \brief Get index of the z dimension in the list + public: Q_INVOKABLE int ZIndex() const; + + /// \brief Set index of the z dimension in the list + public: Q_INVOKABLE void SetZIndex(int _zIndex); + + /// \brief Notify the z dimension index has changed + signals: void ZIndexChanged() const; + + /// \brief Get supported spatial references + public: Q_INVOKABLE QStringList ReferenceList() const; + + /// \brief Get spatial reference + public: Q_INVOKABLE QString Reference() const; + + /// \brief Set spatial reference + public: Q_INVOKABLE void SetReference(QString _reference); + + /// \brief Notify the spatial reference has changed + signals: void ReferenceChanged() const; + + /// \brief Get configuration status + public: Q_INVOKABLE bool IsConfigured() const; + + /// \brief Notify configuration status changed + signals: void IsConfiguredChanged(); + + /// \brief Schedule an update + public: Q_INVOKABLE void ScheduleLoad(); + + /// \internal + /// \brief Pointer to private data + private: std::unique_ptr dataPtr; + }; +} +} +} +#endif diff --git a/src/gui/plugins/environment_loader/EnvironmentLoader.qml b/src/gui/plugins/environment_loader/EnvironmentLoader.qml new file mode 100644 index 0000000000..cd8b1001f6 --- /dev/null +++ b/src/gui/plugins/environment_loader/EnvironmentLoader.qml @@ -0,0 +1,216 @@ +/* + * 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. + * +*/ +import QtQuick 2.9 +import QtQuick.Controls 2.1 +import QtQuick.Dialogs 1.0 +import QtQuick.Controls.Material 2.1 +import QtQuick.Layouts 1.3 +import "qrc:/qml" + + +GridLayout { + columns: 8 + columnSpacing: 10 + Layout.minimumWidth: 350 + Layout.minimumHeight: 400 + anchors.fill: parent + anchors.leftMargin: 10 + anchors.rightMargin: 10 + + Label { + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: dataFileText + color: "dimgrey" + text: qsTr("Data file path") + } + + RowLayout { + Layout.column: 2 + Layout.columnSpan: 6 + + TextField { + id: dataFilePathInput + Layout.fillWidth: true + text: EnvironmentLoader.dataPath + placeholderText: qsTr("Path to data file") + onEditingFinished: { + EnvironmentLoader.dataPath = text + } + } + + Button { + id: browseDataFile + Layout.preferredWidth: 20 + display: AbstractButton.IconOnly + text: EnvironmentLoader.dataFileName + onClicked: dataFileDialog.open() + icon.source: "qrc:/Gazebo/images/chevron-right.svg" + ToolTip.visible: hovered + ToolTip.text: qsTr("Browse files...") + } + } + + FileDialog { + Layout.columnSpan: 8 + id: dataFileDialog + title: qsTr("Please choose a data file") + folder: shortcuts.home + visible: false + onAccepted: { + EnvironmentLoader.SetDataUrl(dataFileDialog.fileUrl) + } + onRejected: { + } + Component.onCompleted: visible = false + } + + Label { + Layout.row: 1 + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: timeDimensionText + color: "dimgrey" + text: qsTr("Time dimension") + } + + ComboBox { + Layout.row: 1 + Layout.column: 2 + Layout.columnSpan: 6 + id: timeDimensionCombo + Layout.fillWidth: true + enabled: EnvironmentLoader.configured + model: EnvironmentLoader.dimensionList + currentIndex: EnvironmentLoader.timeIndex + onCurrentIndexChanged: { + EnvironmentLoader.timeIndex = currentIndex + } + ToolTip.visible: hovered + ToolTip.text: qsTr("Data field to be used as time dimension") + } + + Label { + Layout.row: 2 + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: xDimensionText + color: "dimgrey" + text: qsTr("X dimension") + } + + ComboBox { + Layout.row: 2 + Layout.column: 2 + Layout.columnSpan: 6 + id: xDimensionCombo + Layout.fillWidth: true + enabled: EnvironmentLoader.configured + model: EnvironmentLoader.dimensionList + currentIndex: EnvironmentLoader.xIndex + onCurrentIndexChanged: { + EnvironmentLoader.xIndex = currentIndex + } + ToolTip.visible: hovered + ToolTip.text: qsTr("Data field to be used as x dimension") + } + + Label { + Layout.row: 3 + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: yDimensionText + color: "dimgrey" + text: qsTr("Y dimension") + } + + ComboBox { + Layout.row: 3 + Layout.column: 2 + Layout.columnSpan: 6 + id: yDimensionCombo + Layout.fillWidth: true + enabled: EnvironmentLoader.configured + model: EnvironmentLoader.dimensionList + currentIndex: EnvironmentLoader.yIndex + onCurrentIndexChanged: { + EnvironmentLoader.yIndex = currentIndex + } + ToolTip.visible: hovered + ToolTip.text: qsTr("Data field to be used as y dimension") + } + + Label { + Layout.row: 4 + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: zDimensionText + color: "dimgrey" + text: qsTr("Z dimension") + } + + ComboBox { + Layout.row: 4 + Layout.column: 2 + Layout.columnSpan: 6 + id: zDimensionCombo + Layout.fillWidth: true + enabled: EnvironmentLoader.configured + model: EnvironmentLoader.dimensionList + currentIndex: EnvironmentLoader.zIndex + onCurrentIndexChanged: { + EnvironmentLoader.zIndex = currentIndex + } + ToolTip.visible: hovered + ToolTip.text: qsTr("Data field to be used as z dimension") + } + + Label { + Layout.row: 5 + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: refText + color: "dimgrey" + text: qsTr("Reference") + } + + ComboBox { + Layout.row: 5 + Layout.column: 2 + Layout.columnSpan: 6 + id: referenceCombo + Layout.fillWidth: true + enabled: EnvironmentLoader.configured + model: EnvironmentLoader.referenceList + onCurrentTextChanged: { + EnvironmentLoader.reference = currentText + } + ToolTip.visible: hovered + ToolTip.text: qsTr("Reference for spatial dimensions") + } + + Button { + text: qsTr("Load") + Layout.row: 6 + Layout.columnSpan: 8 + Layout.fillWidth: true + enabled: EnvironmentLoader.configured + onClicked: function() { + EnvironmentLoader.ScheduleLoad() + } + } +} diff --git a/src/gui/plugins/environment_loader/EnvironmentLoader.qrc b/src/gui/plugins/environment_loader/EnvironmentLoader.qrc new file mode 100644 index 0000000000..1f66f199b8 --- /dev/null +++ b/src/gui/plugins/environment_loader/EnvironmentLoader.qrc @@ -0,0 +1,5 @@ + + + EnvironmentLoader.qml + + diff --git a/src/systems/CMakeLists.txt b/src/systems/CMakeLists.txt index 92ee225c60..352a00c1fa 100644 --- a/src/systems/CMakeLists.txt +++ b/src/systems/CMakeLists.txt @@ -114,6 +114,7 @@ add_subdirectory(diff_drive) if (NOT WIN32) add_subdirectory(elevator) endif() +add_subdirectory(environment_preload) add_subdirectory(follow_actor) add_subdirectory(force_torque) add_subdirectory(hydrodynamics) diff --git a/src/systems/environment_preload/CMakeLists.txt b/src/systems/environment_preload/CMakeLists.txt new file mode 100644 index 0000000000..178ec5ec32 --- /dev/null +++ b/src/systems/environment_preload/CMakeLists.txt @@ -0,0 +1,8 @@ +gz_add_system(environment-preload + SOURCES + EnvironmentPreload.cc + PUBLIC_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} +) diff --git a/src/systems/environment_preload/EnvironmentPreload.cc b/src/systems/environment_preload/EnvironmentPreload.cc new file mode 100644 index 0000000000..92926d0746 --- /dev/null +++ b/src/systems/environment_preload/EnvironmentPreload.cc @@ -0,0 +1,172 @@ +/* + * 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 "EnvironmentPreload.hh" + +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include "gz/sim/components/Environment.hh" +#include "gz/sim/components/World.hh" +#include "gz/sim/Util.hh" + +using namespace gz; +using namespace sim; +using namespace systems; + +////////////////////////////////////////////////// +class gz::sim::systems::EnvironmentPreloadPrivate +{ + public: bool loaded{false}; + + public: std::shared_ptr sdf; +}; + +////////////////////////////////////////////////// +EnvironmentPreload::EnvironmentPreload() + : System(), dataPtr(new EnvironmentPreloadPrivate) +{ +} + +////////////////////////////////////////////////// +EnvironmentPreload::~EnvironmentPreload() = default; + +////////////////////////////////////////////////// +void EnvironmentPreload::Configure( + const Entity &/*_entity*/, + const std::shared_ptr &_sdf, + EntityComponentManager &/*_ecm*/, + EventManager &/*_eventMgr*/) +{ + this->dataPtr->sdf = _sdf; +} + +////////////////////////////////////////////////// +void EnvironmentPreload::PreUpdate( + const gz::sim::UpdateInfo &, + gz::sim::EntityComponentManager &_ecm) +{ + if (!std::exchange(this->dataPtr->loaded, true)) + { + if (!this->dataPtr->sdf->HasElement("data")) + { + gzerr << "No environmental data file was specified"; + return; + } + + std::string dataPath = + this->dataPtr->sdf->Get("data"); + if (common::isRelativePath(dataPath)) + { + auto * component = + _ecm.Component(worldEntity(_ecm)); + const std::string rootPath = + common::parentPath(component->Data().Element()->FilePath()); + dataPath = common::joinPaths(rootPath, dataPath); + } + + std::ifstream dataFile(dataPath); + if (!dataFile.is_open()) + { + gzerr << "No environmental data file was found at " << dataPath; + return; + } + + std::string timeColumnName{"t"}; + std::array spatialColumnNames{"x", "y", "z"}; + auto spatialReference = math::SphericalCoordinates::GLOBAL; + + sdf::ElementConstPtr elem = + this->dataPtr->sdf->FindElement("dimensions"); + if (elem) + { + if (elem->HasElement("time")) + { + timeColumnName = elem->Get("time"); + } + elem = elem->FindElement("space"); + if (elem) + { + if (elem->HasAttribute("reference")) + { + const std::string referenceName = + elem->Get("reference"); + if (referenceName == "global") + { + spatialReference = math::SphericalCoordinates::GLOBAL; + } + else if (referenceName == "spherical") + { + spatialReference = math::SphericalCoordinates::SPHERICAL; + } + else if (referenceName == "ecef") + { + spatialReference = math::SphericalCoordinates::ECEF; + } + else + { + gzerr << "Unknown reference '" << referenceName << "'" + << std::endl; + return; + } + } + for (size_t i = 0; i < spatialColumnNames.size(); ++i) + { + if (elem->HasElement(spatialColumnNames[i])) + { + spatialColumnNames[i] = + elem->Get(spatialColumnNames[i]); + } + } + } + } + + try + { + using ComponentDataT = components::EnvironmentalData; + auto data = ComponentDataT::MakeShared( + common::IO::ReadFrom( + common::CSVIStreamIterator(dataFile), + common::CSVIStreamIterator(), + timeColumnName, spatialColumnNames), + spatialReference); + + using ComponentT = components::Environment; + auto component = ComponentT{std::move(data)}; + _ecm.CreateComponent(worldEntity(_ecm), std::move(component)); + } + catch (const std::invalid_argument &exc) + { + gzerr << "Failed to load environment data" << std::endl + << exc.what() << std::endl; + } + } +} + +// Register this plugin +GZ_ADD_PLUGIN(EnvironmentPreload, System, + EnvironmentPreload::ISystemConfigure, + EnvironmentPreload::ISystemPreUpdate) +GZ_ADD_PLUGIN_ALIAS(EnvironmentPreload, + "gz::sim::systems::EnvironmentPreload") diff --git a/src/systems/environment_preload/EnvironmentPreload.hh b/src/systems/environment_preload/EnvironmentPreload.hh new file mode 100644 index 0000000000..16a9793cc0 --- /dev/null +++ b/src/systems/environment_preload/EnvironmentPreload.hh @@ -0,0 +1,70 @@ +/* + * 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_SYSTEMS_ENVIRONMENTPRELOAD_HH_ +#define GZ_SIM_SYSTEMS_ENVIRONMENTPRELOAD_HH_ + +#include + +#include "gz/sim/config.hh" +#include "gz/sim/System.hh" + +namespace gz +{ +namespace sim +{ +// Inline bracket to help doxygen filtering. +inline namespace GZ_SIM_VERSION_NAMESPACE { +namespace systems +{ + class EnvironmentPreloadPrivate; + + /// \class EnvironmentPreload EnvironmentPreload.hh + /// gz/sim/systems/EnvironmentPreload.hh + /// \brief A plugin to preload an Environment component + /// into the ECM upon simulation start-up. + class EnvironmentPreload : + public System, + public ISystemConfigure, + public ISystemPreUpdate + { + /// \brief Constructor + public: explicit EnvironmentPreload(); + + /// \brief Destructor + public: ~EnvironmentPreload() override; + + // Documentation inherited + public: void Configure( + const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + sim::EventManager &_eventMgr) final; + + // Documentation inherited + public: void PreUpdate( + const UpdateInfo &_info, + EntityComponentManager &_ecm) final; + + /// \internal + /// \brief Pointer to private data + private: std::unique_ptr dataPtr; + }; + } +} +} +} +#endif diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index f3b611d73f..1ee62ed9b7 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -19,6 +19,7 @@ set(tests each_new_removed.cc entity_erase.cc entity_system.cc + environment_preload_system.cc events.cc examples_build.cc follow_actor_system.cc diff --git a/test/integration/environment_preload_system.cc b/test/integration/environment_preload_system.cc new file mode 100644 index 0000000000..bc4ee515d2 --- /dev/null +++ b/test/integration/environment_preload_system.cc @@ -0,0 +1,92 @@ +/* + * 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 + +#include + +#include "gz/sim/components/Environment.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/TestFixture.hh" + +#include + +#include "test_config.hh" +#include "../helpers/EnvTestFixture.hh" +#include "../helpers/Relay.hh" + +using namespace gz; +using namespace sim; + +/// \brief Test EnvironmentPreload system +class EnvironmentPreloadTest : public InternalFixture<::testing::Test> +{ +}; + +///////////////////////////////////////////////// +TEST_F(EnvironmentPreloadTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(CanPreload)) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = common::joinPaths( + std::string(PROJECT_BINARY_PATH), "test", + "worlds", "environmental_data.sdf"); + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + bool dataLoaded{false}; + + // Create a system that looks for environmental data components + test::Relay testSystem; + testSystem.OnPostUpdate( + [&](const sim::UpdateInfo &, + const sim::EntityComponentManager &_ecm) + { + _ecm.EachNew( + [&](const gz::sim::Entity &, + const components::Environment *_component) -> bool + { + auto data = _component->Data(); + EXPECT_TRUE(data->frame.Has("humidity")); + const auto &humidityData = data->frame["humidity"]; + auto humiditySession = humidityData.StepTo( + humidityData.CreateSession(), 1658923062.5); + EXPECT_TRUE(humiditySession.has_value()); + if (humiditySession.has_value()) + { + const math::Vector3d position{36.80079505, -121.789472517, 0.8}; + auto humidity = + humidityData.LookUp(humiditySession.value(), position); + EXPECT_NEAR(89.5, humidity.value_or(0.), 1e-6); + dataLoaded = true; + } + EXPECT_EQ(data->reference, math::SphericalCoordinates::SPHERICAL); + + return true; + }); + }); + + server.AddSystem(testSystem.systemPtr); + + // Run server + server.RunOnce(); + + EXPECT_TRUE(dataLoaded); +} diff --git a/test/worlds/CMakeLists.txt b/test/worlds/CMakeLists.txt index 70e61f51f3..cddef0af3b 100644 --- a/test/worlds/CMakeLists.txt +++ b/test/worlds/CMakeLists.txt @@ -2,3 +2,4 @@ configure_file (buoyancy.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/buoyancy.sdf) configure_file (mesh.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/mesh.sdf) configure_file (thermal.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/thermal.sdf) configure_file (heightmap.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/heightmap.sdf) +configure_file (environmental_data.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/environmental_data.sdf) diff --git a/test/worlds/environmental_data.csv b/test/worlds/environmental_data.csv new file mode 100644 index 0000000000..923bd22a53 --- /dev/null +++ b/test/worlds/environmental_data.csv @@ -0,0 +1,9 @@ +timestamp,humidity,latitude,longitude,altitude +1658923062,91,36.80029505,-121.788972517,0.8 +1658923062,88,36.80129505,-121.788972517,0.8 +1658923062,89,36.80029505,-121.789972517,0.8 +1658923062,92,36.80129505,-121.789972517,0.8 +1658923063,90,36.80029505,-121.788972517,0.8 +1658923063,85,36.80129505,-121.788972517,0.8 +1658923063,87,36.80029505,-121.789972517,0.8 +1658923063,94,36.80129505,-121.789972517,0.8 diff --git a/test/worlds/environmental_data.sdf.in b/test/worlds/environmental_data.sdf.in new file mode 100644 index 0000000000..ac3ec2a73d --- /dev/null +++ b/test/worlds/environmental_data.sdf.in @@ -0,0 +1,45 @@ + + + + + 0.001 + 0 + + + + + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + @CMAKE_SOURCE_DIR@/test/worlds/environmental_data.csv + + + + latitude + longitude + altitude + + + + + From af1ac2ffabd4c6397781902492e62fce66cacb66 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 17 Nov 2022 09:08:03 -0600 Subject: [PATCH 2/6] Add pre-commit hooks configuration (#1792) Signed-off-by: Michael Carroll --- .github/ci-focal/before_cmake.sh | 0 .github/ci/after_make.sh | 0 .github/workflows/ci.yml | 8 +++ .github/workflows/triage.yml | 1 - .pre-commit-config.yaml | 18 +++++ COPYING | 2 - api.md.in | 2 +- docker/Dockerfile.base | 1 - .../custom_component/CustomComponentPlugin.cc | 1 - examples/plugin/hello_world/HelloWorld.cc | 3 - examples/plugin/reset_plugin/CMakeLists.txt | 2 +- examples/plugin/reset_plugin/README.md | 2 +- examples/scripts/blender/distort_mesh.py | 0 examples/scripts/distributed/README.md | 1 - examples/scripts/distributed/primary.sh | 1 - examples/scripts/distributed/secondary.sh | 1 - .../scripts/distributed_levels/primary.sh | 1 - .../scripts/distributed_levels/secondary.sdf | 66 +++++++++---------- .../scripts/distributed_levels/secondary.sh | 1 - .../log_video_recorder/log_video_recorder.sdf | 1 - .../log_video_recorder/record_one_run.bash | 1 - examples/scripts/python_api/testFixture.py | 0 .../each_performance/CMakeLists.txt | 1 - .../standalone/each_performance/README.md | 1 - examples/standalone/gtest_setup/README.md | 1 - .../standalone/joy_to_twist/CMakeLists.txt | 1 - .../standalone/joy_to_twist/joy_to_twist.cc | 1 - .../standalone/joy_to_twist/joy_to_twist.sdf | 1 - examples/standalone/joystick/joystick.cc | 1 - examples/standalone/joystick/joystick.sdf | 1 - examples/standalone/keyboard/keyboard.cc | 14 ++-- examples/standalone/keyboard/keyboard.sdf | 1 - .../standalone/scene_requester/CMakeLists.txt | 1 - examples/worlds/boundingbox_camera.sdf | 1 - examples/worlds/collada_world_exporter.sdf | 2 +- examples/worlds/kinetic_energy_monitor.sdf | 1 - examples/worlds/linear_battery_demo.sdf | 4 +- include/gz/sim/Primitives.hh | 2 - include/gz/sim/SystemLoader.hh | 1 - include/gz/sim/components/DetachableJoint.hh | 1 - .../sim/components/ExternalWorldWrenchCmd.hh | 1 - include/gz/sim/components/LevelBuffer.hh | 1 - include/gz/sim/components/LevelEntityNames.hh | 1 - .../gz/sim/components/PerformerAffinity.hh | 1 - include/gz/sim/components/PerformerLevels.hh | 1 - include/gz/sim/components/components.hh.in | 1 - python/test/testFixture_TEST.py | 1 + src/Barrier.cc | 1 - src/EventManager_TEST.cc | 1 - src/LevelManager.hh | 1 - src/SystemManager_TEST.cc | 1 - src/TestFixture.cc | 1 - src/World.cc | 1 - src/cmd/ModelCommandAPI.hh | 1 - src/cmd/cmdmodel.rb.in | 0 src/cmd/cmdsim.rb.in | 2 +- src/cmd/model.bash_completion.sh | 0 src/cmd/sim.bash_completion.sh | 0 src/gui/GuiFileHandler.cc | 1 - src/gui/PathManager.cc | 1 - src/gui/plugins/align_tool/AlignTool.qml | 2 +- .../component_inspector/SystemPluginInfo.cc | 1 - src/gui/plugins/component_inspector/Types.hh | 1 - .../component_inspector_editor/Altimeter.qml | 2 +- .../ComponentInspectorEditor.qml | 14 ++-- .../component_inspector_editor/Lidar.cc | 1 - .../component_inspector_editor/Lidar.qml | 42 ++++++------ .../component_inspector_editor/LidarScan.qml | 14 ++-- .../Magnetometer.qml | 2 +- .../component_inspector_editor/Noise.qml | 12 ++-- .../StateAwareSpin.qml | 6 +- src/gui/plugins/entity_tree/EntityTree.qml | 16 ++--- src/gui/plugins/modules/TypeIcon.qml | 1 - .../plugins/transform_control/CMakeLists.txt | 2 - .../plugins/video_recorder/VideoRecorder.qml | 4 +- src/gui/plugins/view_angle/CMakeLists.txt | 2 - .../visualize_lidar/VisualizeLidar.qrc | 2 +- src/msgs/CMakeLists.txt | 1 - src/msgs/simulation_step.proto | 1 - src/network/NetworkConfig.cc | 1 - src/network/NetworkConfig_TEST.cc | 1 - src/network/NetworkManagerPrimary.hh | 1 - src/network/NetworkManagerPrivate.hh | 1 - src/network/NetworkManagerSecondary.cc | 1 - src/network/NetworkManagerSecondary.hh | 1 - src/network/NetworkRole.hh | 1 - src/network/PeerInfo.hh | 1 - src/network/PeerTracker.hh | 2 - src/systems/air_pressure/CMakeLists.txt | 1 - src/systems/altimeter/CMakeLists.txt | 1 - src/systems/elevator/vender/afsm/LICENSE | 2 +- .../elevator/vender/metapushkin/LICENSE | 2 +- src/systems/follow_actor/CMakeLists.txt | 1 - src/systems/force_torque/CMakeLists.txt | 2 +- src/systems/imu/CMakeLists.txt | 1 - .../joint_controller/JointController.hh | 1 - src/systems/lift_drag/CMakeLists.txt | 1 - src/systems/lift_drag/LiftDrag.hh | 1 - src/systems/logical_camera/CMakeLists.txt | 1 - src/systems/navsat/CMakeLists.txt | 1 - .../optical_tactile_plugin/CMakeLists.txt | 2 +- .../particle_emitter/ParticleEmitter.hh | 1 - .../particle_emitter2/ParticleEmitter2.hh | 1 - .../scene_broadcaster/SceneBroadcaster.hh | 1 - src/systems/sensors/CMakeLists.txt | 1 - src/systems/user_commands/CMakeLists.txt | 1 - .../velocity_control/VelocityControl.hh | 1 - src/systems/wind_effects/CMakeLists.txt | 1 - test/CMakeLists.txt | 2 +- test/benchmark/README.md | 1 - test/find_dri.cmake | 2 - test/gtest_vendor/CMakeLists.txt | 2 +- test/gtest_vendor/gtest_vendor_version | 2 +- test/helpers/UniqueTestDirectoryEnv.hh | 1 - test/integration/apply_joint_force_system.cc | 1 - test/integration/apply_link_wrench_system.cc | 1 - test/integration/buoyancy_engine.cc | 1 - test/integration/events.cc | 1 - test/integration/model.cc | 1 - test/integration/world.cc | 1 - test/performance/CMakeLists.txt | 1 - test/performance/README.md | 1 - test/plugins/EventTriggerSystem.cc | 1 - test/plugins/MockSystem.cc | 1 - test/plugins/TestModelSystem.cc | 1 - test/plugins/TestSensorSystem.cc | 1 - test/plugins/TestSystem.hh | 1 - test/plugins/TestWorldSystem.cc | 1 - test/worlds/buoyancy.sdf.in | 1 - .../buoyancy_graded_restoring_moments.sdf | 2 +- .../buoyancy_uniform_restoring_moments.sdf | 2 +- test/worlds/camera_distortion.sdf | 2 +- test/worlds/center_of_volume.sdf | 1 - test/worlds/center_of_volume_graded.sdf | 2 +- test/worlds/diff_drive_custom_tf_topic.sdf | 1 - test/worlds/log_playback.sdf | 1 - .../worlds/models/lift_drag_wing/model.config | 1 - .../models/mesh_with_submeshes/model.config | 1 - .../models/relative_resource_uri/model.config | 1 - .../models/relative_resource_uri/model.sdf | 1 - .../models/relative_resource_uri/model2.sdf | 1 - .../models/scheme_resource_uri/model.config | 1 - .../models/scheme_resource_uri/model.sdf | 1 - test/worlds/models/sphere/model.sdf | 1 - test/worlds/odometry_noise.sdf | 1 - test/worlds/odometry_offset.sdf | 1 - test/worlds/odometry_publisher.sdf | 1 - test/worlds/odometry_publisher_custom.sdf | 1 - test/worlds/particle_emitter.sdf | 2 - test/worlds/plugins_empty.sdf | 1 - test/worlds/server_invalid.config | 3 +- test/worlds/server_valid.config | 2 +- test/worlds/server_valid2.config | 2 +- test/worlds/static_diff_drive_vehicle.sdf | 2 +- test/worlds/triggered_publisher.sdf | 1 - tutorials/blender_distort_meshes.md | 1 - tutorials/erb_template.md | 8 +-- tutorials/files/spherical_coordinates/ENU.svg | 2 +- tutorials/gui_config.md | 3 - tutorials/headless_rendering.md | 6 +- tutorials/migration_plugins.md | 1 - tutorials/rendering_plugins.md | 1 - tutorials/terminology.md | 1 - 163 files changed, 155 insertions(+), 256 deletions(-) mode change 100644 => 100755 .github/ci-focal/before_cmake.sh mode change 100644 => 100755 .github/ci/after_make.sh create mode 100644 .pre-commit-config.yaml mode change 100644 => 100755 examples/scripts/blender/distort_mesh.py mode change 100644 => 100755 examples/scripts/log_video_recorder/record_one_run.bash mode change 100644 => 100755 examples/scripts/python_api/testFixture.py mode change 100644 => 100755 src/cmd/cmdmodel.rb.in mode change 100644 => 100755 src/cmd/model.bash_completion.sh mode change 100644 => 100755 src/cmd/sim.bash_completion.sh diff --git a/.github/ci-focal/before_cmake.sh b/.github/ci-focal/before_cmake.sh old mode 100644 new mode 100755 diff --git a/.github/ci/after_make.sh b/.github/ci/after_make.sh old mode 100644 new mode 100755 diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 98b07b2ee0..0206d99944 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -9,6 +9,10 @@ jobs: steps: - name: Checkout uses: actions/checkout@v2 + - uses: actions/setup-python@v3 + - uses: pre-commit/action@v3.0.0 + with: + extra_args: --all-files - name: Compile and test id: ci uses: gazebo-tooling/action-gz-ci@focal @@ -22,6 +26,10 @@ jobs: steps: - name: Checkout uses: actions/checkout@v2 + - uses: actions/setup-python@v3 + - uses: pre-commit/action@v3.0.0 + with: + extra_args: --all-files - name: Compile and test id: ci uses: gazebo-tooling/action-gz-ci@jammy diff --git a/.github/workflows/triage.yml b/.github/workflows/triage.yml index 736670e0e4..6f93ccd58f 100644 --- a/.github/workflows/triage.yml +++ b/.github/workflows/triage.yml @@ -16,4 +16,3 @@ jobs: COLUMN: Inbox GITHUB_TOKEN: ${{ secrets.TRIAGE_TOKEN }} CHECK_ORG_PROJECT: true - diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 0000000000..d5472e5c9f --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,18 @@ +repos: +- repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.3.0 + hooks: + - id: check-added-large-files + args: ['--maxkb=500'] + - id: check-executables-have-shebangs + - id: check-json + - id: check-merge-conflict + - id: check-shebang-scripts-are-executable + - id: check-symlinks + - id: check-toml + - id: check-xml + - id: check-yaml + - id: destroyed-symlinks + - id: end-of-file-fixer + - id: mixed-line-ending + - id: trailing-whitespace diff --git a/COPYING b/COPYING index 4909afd04f..d9a10c0d8e 100644 --- a/COPYING +++ b/COPYING @@ -174,5 +174,3 @@ of your accepting any such warranty or additional liability. END OF TERMS AND CONDITIONS - - diff --git a/api.md.in b/api.md.in index 243e219071..ea548c89a7 100644 --- a/api.md.in +++ b/api.md.in @@ -1,7 +1,7 @@ ## Gazebo @GZ_DESIGNATION_CAP@ Gazebo @GZ_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries -designed to rapidly develop robot and simulation applications. +designed to rapidly develop robot and simulation applications. **Useful links** diff --git a/docker/Dockerfile.base b/docker/Dockerfile.base index bca8aa96d5..37e7b94eff 100644 --- a/docker/Dockerfile.base +++ b/docker/Dockerfile.base @@ -13,4 +13,3 @@ RUN scripts/install_common_deps.sh COPY docker/scripts/enable_gcc8.sh scripts/enable_gcc8.sh RUN scripts/enable_gcc8.sh - diff --git a/examples/plugin/custom_component/CustomComponentPlugin.cc b/examples/plugin/custom_component/CustomComponentPlugin.cc index 74b3aaf3e6..39079b33a8 100644 --- a/examples/plugin/custom_component/CustomComponentPlugin.cc +++ b/examples/plugin/custom_component/CustomComponentPlugin.cc @@ -21,4 +21,3 @@ GZ_ADD_PLUGIN(examples::CustomComponentPlugin, gz::sim::System, examples::CustomComponentPlugin::ISystemConfigure) - diff --git a/examples/plugin/hello_world/HelloWorld.cc b/examples/plugin/hello_world/HelloWorld.cc index f75e956baa..d301dfbf9a 100644 --- a/examples/plugin/hello_world/HelloWorld.cc +++ b/examples/plugin/hello_world/HelloWorld.cc @@ -51,6 +51,3 @@ void HelloWorld::PostUpdate(const gz::sim::UpdateInfo &_info, // higher (i.e. gz sim -v 3) gzmsg << msg << std::endl; } - - - diff --git a/examples/plugin/reset_plugin/CMakeLists.txt b/examples/plugin/reset_plugin/CMakeLists.txt index f2ec766259..12a2c7e3d8 100644 --- a/examples/plugin/reset_plugin/CMakeLists.txt +++ b/examples/plugin/reset_plugin/CMakeLists.txt @@ -9,6 +9,6 @@ find_package(gz-sim7 REQUIRED) set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR}) add_library(JointPositionRandomizer SHARED JointPositionRandomizer.cc) -target_link_libraries(JointPositionRandomizer +target_link_libraries(JointPositionRandomizer PRIVATE gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER} PRIVATE gz-sim${GZ_SIM_VER}::core) diff --git a/examples/plugin/reset_plugin/README.md b/examples/plugin/reset_plugin/README.md index c0d60b4a69..eb39312cf8 100644 --- a/examples/plugin/reset_plugin/README.md +++ b/examples/plugin/reset_plugin/README.md @@ -1,6 +1,6 @@ # System Reset API -This example uses the JointPositionRandomizer system to randomize the joint +This example uses the JointPositionRandomizer system to randomize the joint positions of a robot arm at every reset. diff --git a/examples/scripts/blender/distort_mesh.py b/examples/scripts/blender/distort_mesh.py old mode 100644 new mode 100755 diff --git a/examples/scripts/distributed/README.md b/examples/scripts/distributed/README.md index 7b7c6697df..0571f31d2b 100644 --- a/examples/scripts/distributed/README.md +++ b/examples/scripts/distributed/README.md @@ -31,4 +31,3 @@ the GUI. You can run the same world in a standalone process as follows: ./standalone.sh - diff --git a/examples/scripts/distributed/primary.sh b/examples/scripts/distributed/primary.sh index 277f374237..9624329456 100755 --- a/examples/scripts/distributed/primary.sh +++ b/examples/scripts/distributed/primary.sh @@ -3,4 +3,3 @@ DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" gz sim -v 4 -z 100000000 --network-role primary --network-secondaries 3 $DIR/primary.sdf - diff --git a/examples/scripts/distributed/secondary.sh b/examples/scripts/distributed/secondary.sh index f605b82b9c..91a7b8a4ba 100755 --- a/examples/scripts/distributed/secondary.sh +++ b/examples/scripts/distributed/secondary.sh @@ -3,4 +3,3 @@ DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" gz sim -s -v 4 -z 100000000 --network-role secondary $DIR/secondary.sdf - diff --git a/examples/scripts/distributed_levels/primary.sh b/examples/scripts/distributed_levels/primary.sh index 8f07ffec2d..b58d4a8508 100755 --- a/examples/scripts/distributed_levels/primary.sh +++ b/examples/scripts/distributed_levels/primary.sh @@ -4,4 +4,3 @@ DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" # --levels is implied by --network-role gz sim -v 4 -z 100000000 --network-role primary --network-secondaries 2 $DIR/primary.sdf - diff --git a/examples/scripts/distributed_levels/secondary.sdf b/examples/scripts/distributed_levels/secondary.sdf index e0510356a8..acb7e4d6f1 100644 --- a/examples/scripts/distributed_levels/secondary.sdf +++ b/examples/scripts/distributed_levels/secondary.sdf @@ -10,14 +10,14 @@ - + - - + + 0.8 0.8 0.8 1.0 @@ -40,7 +40,7 @@ -0.5 0.1 -0.9 - + 0 -1.5 2.5 0 0 0 @@ -74,7 +74,7 @@ - + 0 1.5 2.5 0 0 0 @@ -108,9 +108,9 @@ - - + + true 0.0 -1.5 -0.0 0 0.5235987755982988 0 @@ -171,7 +171,7 @@ - + true 0.0 1.5 -0.0 0 0.5235987755982988 0 @@ -232,7 +232,7 @@ - + true 2.598076211353316 -1.5 -1.4999999999999998 0 0.5235987755982988 0 @@ -293,7 +293,7 @@ - + true 2.598076211353316 1.5 -1.4999999999999998 0 0.5235987755982988 0 @@ -354,7 +354,7 @@ - + true 5.196152422706632 -1.5 -2.9999999999999996 0 0.5235987755982988 0 @@ -415,7 +415,7 @@ - + true 5.196152422706632 1.5 -2.9999999999999996 0 0.5235987755982988 0 @@ -476,7 +476,7 @@ - + true 7.794228634059948 0 -4.499999999999999 0 0.5235987755982988 0 @@ -537,7 +537,7 @@ - + true 10.392304845413264 -1.5 -5.999999999999999 0 0.5235987755982988 0 @@ -598,7 +598,7 @@ - + true 10.392304845413264 1.5 -5.999999999999999 0 0.5235987755982988 0 @@ -659,7 +659,7 @@ - + true 12.99038105676658 -1.5 -7.499999999999999 0 0.5235987755982988 0 @@ -720,7 +720,7 @@ - + true 12.99038105676658 1.5 -7.499999999999999 0 0.5235987755982988 0 @@ -781,7 +781,7 @@ - + true @@ -851,7 +851,7 @@ - + green_sphere @@ -860,7 +860,7 @@ - + yellow_box @@ -869,9 +869,9 @@ - - + + 0.0 -1.5 -0.0 0 0 0 @@ -882,7 +882,7 @@ 1.0 block_0_A - + 0.0 1.5 -0.0 0 0 0 @@ -893,7 +893,7 @@ 1.0 block_0_B - + 2.598076211353316 -1.5 -1.4999999999999998 0 0 0 @@ -904,7 +904,7 @@ 1.0 block_1_A - + 2.598076211353316 1.5 -1.4999999999999998 0 0 0 @@ -915,7 +915,7 @@ 1.0 block_1_B - + 5.196152422706632 -1.5 -2.9999999999999996 0 0 0 @@ -926,7 +926,7 @@ 1.0 block_2_A - + 5.196152422706632 1.5 -2.9999999999999996 0 0 0 @@ -937,7 +937,7 @@ 1.0 block_2_B - + 7.794228634059948 0 -4.499999999999999 0 0 0 @@ -948,7 +948,7 @@ 1.0 block_3_C - + 10.392304845413264 -1.5 -5.999999999999999 0 0 0 @@ -959,7 +959,7 @@ 1.0 block_4_A - + 10.392304845413264 1.5 -5.999999999999999 0 0 0 @@ -970,7 +970,7 @@ 1.0 block_4_B - + 12.99038105676658 -1.5 -7.499999999999999 0 0 0 @@ -981,7 +981,7 @@ 1.0 block_5_A - + 12.99038105676658 1.5 -7.499999999999999 0 0 0 @@ -992,7 +992,7 @@ 1.0 block_5_B - + diff --git a/examples/scripts/distributed_levels/secondary.sh b/examples/scripts/distributed_levels/secondary.sh index 7eb3d7efc2..aa768a315a 100755 --- a/examples/scripts/distributed_levels/secondary.sh +++ b/examples/scripts/distributed_levels/secondary.sh @@ -4,4 +4,3 @@ DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" # --levels is implied by --network-role gz sim -s -v 4 -z 100000000 --network-role secondary $DIR/secondary.sdf - diff --git a/examples/scripts/log_video_recorder/log_video_recorder.sdf b/examples/scripts/log_video_recorder/log_video_recorder.sdf index e464fc4fe1..cde3d0cc51 100644 --- a/examples/scripts/log_video_recorder/log_video_recorder.sdf +++ b/examples/scripts/log_video_recorder/log_video_recorder.sdf @@ -132,4 +132,3 @@ - diff --git a/examples/scripts/log_video_recorder/record_one_run.bash b/examples/scripts/log_video_recorder/record_one_run.bash old mode 100644 new mode 100755 index c0d447414b..8c078053cd --- a/examples/scripts/log_video_recorder/record_one_run.bash +++ b/examples/scripts/log_video_recorder/record_one_run.bash @@ -48,4 +48,3 @@ if [ -d "$tmpDir" ]; then rm -fr $tmpDir fi echo "Done" - diff --git a/examples/scripts/python_api/testFixture.py b/examples/scripts/python_api/testFixture.py old mode 100644 new mode 100755 diff --git a/examples/standalone/each_performance/CMakeLists.txt b/examples/standalone/each_performance/CMakeLists.txt index 4d5dff79d9..dcfcbc6b58 100644 --- a/examples/standalone/each_performance/CMakeLists.txt +++ b/examples/standalone/each_performance/CMakeLists.txt @@ -7,4 +7,3 @@ find_package(gz-sim7 QUIET REQUIRED) add_executable(each each.cc) target_link_libraries(each gz-sim7::core) - diff --git a/examples/standalone/each_performance/README.md b/examples/standalone/each_performance/README.md index a27e878ea9..16806043d0 100644 --- a/examples/standalone/each_performance/README.md +++ b/examples/standalone/each_performance/README.md @@ -16,4 +16,3 @@ Example program to generate performance data gnuplot -e "filename='each.data'" ../each.gp eog *.png - diff --git a/examples/standalone/gtest_setup/README.md b/examples/standalone/gtest_setup/README.md index ecc6edfd5a..8d95b90bf7 100644 --- a/examples/standalone/gtest_setup/README.md +++ b/examples/standalone/gtest_setup/README.md @@ -24,4 +24,3 @@ From the root of the repository: cd examples/standalone/gtest_setup/build ./gravity_TEST ./command_TEST - diff --git a/examples/standalone/joy_to_twist/CMakeLists.txt b/examples/standalone/joy_to_twist/CMakeLists.txt index b113a1128d..93ecf44aa9 100644 --- a/examples/standalone/joy_to_twist/CMakeLists.txt +++ b/examples/standalone/joy_to_twist/CMakeLists.txt @@ -13,4 +13,3 @@ target_link_libraries(joy_to_twist gz-transport${GZ_TRANSPORT_VER}::core sdformat${SDF_VER}::sdformat${SDF_VER} ) - diff --git a/examples/standalone/joy_to_twist/joy_to_twist.cc b/examples/standalone/joy_to_twist/joy_to_twist.cc index 4372910673..673d20a36a 100644 --- a/examples/standalone/joy_to_twist/joy_to_twist.cc +++ b/examples/standalone/joy_to_twist/joy_to_twist.cc @@ -150,4 +150,3 @@ int main(int argc, char **argv) { } } - diff --git a/examples/standalone/joy_to_twist/joy_to_twist.sdf b/examples/standalone/joy_to_twist/joy_to_twist.sdf index 0cff350937..aca59e63fa 100644 --- a/examples/standalone/joy_to_twist/joy_to_twist.sdf +++ b/examples/standalone/joy_to_twist/joy_to_twist.sdf @@ -39,4 +39,3 @@ - diff --git a/examples/standalone/joystick/joystick.cc b/examples/standalone/joystick/joystick.cc index ec81e59cd4..f1addd2dde 100644 --- a/examples/standalone/joystick/joystick.cc +++ b/examples/standalone/joystick/joystick.cc @@ -284,4 +284,3 @@ int main(int argc, char **argv) // Close the joystick close(joyFd); } - diff --git a/examples/standalone/joystick/joystick.sdf b/examples/standalone/joystick/joystick.sdf index 9360e9d225..55bf10250a 100644 --- a/examples/standalone/joystick/joystick.sdf +++ b/examples/standalone/joystick/joystick.sdf @@ -9,4 +9,3 @@ - diff --git a/examples/standalone/keyboard/keyboard.cc b/examples/standalone/keyboard/keyboard.cc index eb2494fe21..3ac52d834f 100644 --- a/examples/standalone/keyboard/keyboard.cc +++ b/examples/standalone/keyboard/keyboard.cc @@ -34,7 +34,7 @@ #include // read() -#define KEYCODE_ARR_R 0x43 +#define KEYCODE_ARR_R 0x43 #define KEYCODE_ARR_L 0x44 #define KEYCODE_ARR_U 0x41 #define KEYCODE_ARR_D 0x42 @@ -101,11 +101,11 @@ void KeyboardTeleop::KeyLoop() bool dirty = false, dirty2 = false; - // get the console in raw mode + // get the console in raw mode tcgetattr(kfd, &cooked); memcpy(&raw, &cooked, sizeof(struct termios)); raw.c_lflag &=~ (ICANON | ECHO); - // Setting a new line, then end of file + // Setting a new line, then end of file raw.c_cc[VEOL] = 1; raw.c_cc[VEOF] = 2; tcsetattr(kfd, TCSANOW, &raw); @@ -117,7 +117,7 @@ void KeyboardTeleop::KeyLoop() for (;;) { - // get the next event from the keyboard + // get the next event from the keyboard if (read(kfd, &c, 1) < 0) { perror("read():"); @@ -127,7 +127,7 @@ void KeyboardTeleop::KeyLoop() double linear = 0, linear2 = 0; double angular = 0, angular2 = 0; fprintf (stderr, "value: 0x%02X\n", c); - + switch (c) { // robot 1 @@ -173,7 +173,7 @@ void KeyboardTeleop::KeyLoop() dirty2 = true; break; } - + gz::msgs::Twist cmdVelMsg; cmdVelMsg.mutable_linear()->set_x(lScale * linear); cmdVelMsg.mutable_angular()->set_z(aScale * angular); @@ -240,6 +240,6 @@ int main(int argc, char** argv) scaleAngular.Z()); signal(SIGINT, Quit); teleop_turtle.KeyLoop(); - + return(0); } diff --git a/examples/standalone/keyboard/keyboard.sdf b/examples/standalone/keyboard/keyboard.sdf index 414521cd90..a46ee059e7 100644 --- a/examples/standalone/keyboard/keyboard.sdf +++ b/examples/standalone/keyboard/keyboard.sdf @@ -15,4 +15,3 @@ - diff --git a/examples/standalone/scene_requester/CMakeLists.txt b/examples/standalone/scene_requester/CMakeLists.txt index 58058b12f6..71eb8f0ddd 100644 --- a/examples/standalone/scene_requester/CMakeLists.txt +++ b/examples/standalone/scene_requester/CMakeLists.txt @@ -8,4 +8,3 @@ set(GZ_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR}) add_executable(scene_requester scene_requester.cc) target_link_libraries(scene_requester gz-transport${GZ_TRANSPORT_VER}::core) - diff --git a/examples/worlds/boundingbox_camera.sdf b/examples/worlds/boundingbox_camera.sdf index 25ecdb5acf..4aa95a96ae 100644 --- a/examples/worlds/boundingbox_camera.sdf +++ b/examples/worlds/boundingbox_camera.sdf @@ -412,4 +412,3 @@ - diff --git a/examples/worlds/collada_world_exporter.sdf b/examples/worlds/collada_world_exporter.sdf index 3d4c9e859d..0d1abdbdf3 100644 --- a/examples/worlds/collada_world_exporter.sdf +++ b/examples/worlds/collada_world_exporter.sdf @@ -4,7 +4,7 @@ This world will load the ColladaWorldExporter plugin, which is designed to convert a world to a single Collada file. When this world is run, a subdirectory named after the world is created. Within this subdirectory is the mesh and -materials for the world. +materials for the world. This example just exports simple shapes into a Collada file. To run use: diff --git a/examples/worlds/kinetic_energy_monitor.sdf b/examples/worlds/kinetic_energy_monitor.sdf index e42b266af4..df64964db5 100644 --- a/examples/worlds/kinetic_energy_monitor.sdf +++ b/examples/worlds/kinetic_energy_monitor.sdf @@ -113,4 +113,3 @@ - diff --git a/examples/worlds/linear_battery_demo.sdf b/examples/worlds/linear_battery_demo.sdf index 9e989ef06c..99128bf928 100644 --- a/examples/worlds/linear_battery_demo.sdf +++ b/examples/worlds/linear_battery_demo.sdf @@ -282,7 +282,7 @@ 0.07 2.0 true - 3.0 0.51 @@ -484,7 +484,7 @@ 6.6 true true - 3.0 diff --git a/include/gz/sim/Primitives.hh b/include/gz/sim/Primitives.hh index 407cde0510..84bc8344f5 100644 --- a/include/gz/sim/Primitives.hh +++ b/include/gz/sim/Primitives.hh @@ -79,5 +79,3 @@ namespace gz #endif // GZ_SIM_PRIMITIVES_HH_ - - diff --git a/include/gz/sim/SystemLoader.hh b/include/gz/sim/SystemLoader.hh index 05b280f904..cf78fe3c5e 100644 --- a/include/gz/sim/SystemLoader.hh +++ b/include/gz/sim/SystemLoader.hh @@ -92,4 +92,3 @@ namespace gz } } #endif // GZ_SIM_SYSTEMLOADER_HH_ - diff --git a/include/gz/sim/components/DetachableJoint.hh b/include/gz/sim/components/DetachableJoint.hh index 7bcf6e4602..a2286e4dad 100644 --- a/include/gz/sim/components/DetachableJoint.hh +++ b/include/gz/sim/components/DetachableJoint.hh @@ -102,4 +102,3 @@ namespace components } #endif - diff --git a/include/gz/sim/components/ExternalWorldWrenchCmd.hh b/include/gz/sim/components/ExternalWorldWrenchCmd.hh index d707c4a65a..2a6ba99a39 100644 --- a/include/gz/sim/components/ExternalWorldWrenchCmd.hh +++ b/include/gz/sim/components/ExternalWorldWrenchCmd.hh @@ -49,4 +49,3 @@ namespace components } #endif - diff --git a/include/gz/sim/components/LevelBuffer.hh b/include/gz/sim/components/LevelBuffer.hh index a82c77f7ba..e745114f4e 100644 --- a/include/gz/sim/components/LevelBuffer.hh +++ b/include/gz/sim/components/LevelBuffer.hh @@ -40,4 +40,3 @@ namespace components } } #endif - diff --git a/include/gz/sim/components/LevelEntityNames.hh b/include/gz/sim/components/LevelEntityNames.hh index e9fc50f58a..5027f48e19 100644 --- a/include/gz/sim/components/LevelEntityNames.hh +++ b/include/gz/sim/components/LevelEntityNames.hh @@ -88,4 +88,3 @@ namespace components } } #endif - diff --git a/include/gz/sim/components/PerformerAffinity.hh b/include/gz/sim/components/PerformerAffinity.hh index 2551dc1288..ce58992a73 100644 --- a/include/gz/sim/components/PerformerAffinity.hh +++ b/include/gz/sim/components/PerformerAffinity.hh @@ -46,4 +46,3 @@ namespace components } #endif - diff --git a/include/gz/sim/components/PerformerLevels.hh b/include/gz/sim/components/PerformerLevels.hh index d6715568eb..d1208b36b6 100644 --- a/include/gz/sim/components/PerformerLevels.hh +++ b/include/gz/sim/components/PerformerLevels.hh @@ -82,4 +82,3 @@ namespace components } } #endif - diff --git a/include/gz/sim/components/components.hh.in b/include/gz/sim/components/components.hh.in index 05effcee01..f93046a8e6 100644 --- a/include/gz/sim/components/components.hh.in +++ b/include/gz/sim/components/components.hh.in @@ -21,4 +21,3 @@ ${component_includes} #endif - diff --git a/python/test/testFixture_TEST.py b/python/test/testFixture_TEST.py index 9978ad4fb9..964a3b7da0 100755 --- a/python/test/testFixture_TEST.py +++ b/python/test/testFixture_TEST.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 # Copyright (C) 2021 Open Source Robotics Foundation # Licensed under the Apache License, Version 2.0 (the "License"); diff --git a/src/Barrier.cc b/src/Barrier.cc index eeb2380944..ca6b4347bd 100644 --- a/src/Barrier.cc +++ b/src/Barrier.cc @@ -97,4 +97,3 @@ void Barrier::Cancel() this->dataPtr->cancelled = true; this->dataPtr->cv.notify_all(); } - diff --git a/src/EventManager_TEST.cc b/src/EventManager_TEST.cc index 78ef5cda90..ab7e86c9f2 100644 --- a/src/EventManager_TEST.cc +++ b/src/EventManager_TEST.cc @@ -118,4 +118,3 @@ TEST(EventManager, Disambiguate) eventManager.Emit(); EXPECT_EQ(1, calls); } - diff --git a/src/LevelManager.hh b/src/LevelManager.hh index 80160c4442..63e0466533 100644 --- a/src/LevelManager.hh +++ b/src/LevelManager.hh @@ -184,4 +184,3 @@ namespace gz } // GZ_SIM_LEVELMANAGER_HH #endif - diff --git a/src/SystemManager_TEST.cc b/src/SystemManager_TEST.cc index 5aaafd376f..e9e636815a 100644 --- a/src/SystemManager_TEST.cc +++ b/src/SystemManager_TEST.cc @@ -259,4 +259,3 @@ TEST(SystemManager, AddSystemWithInfo) }); EXPECT_EQ(1, entityCount); } - diff --git a/src/TestFixture.cc b/src/TestFixture.cc index 8110deca1b..b5541af33b 100644 --- a/src/TestFixture.cc +++ b/src/TestFixture.cc @@ -212,4 +212,3 @@ std::shared_ptr TestFixture::Server() const { return this->dataPtr->server; } - diff --git a/src/World.cc b/src/World.cc index 80d9069498..acad788d2c 100644 --- a/src/World.cc +++ b/src/World.cc @@ -240,4 +240,3 @@ uint64_t World::ModelCount(const EntityComponentManager &_ecm) const { return this->Models(_ecm).size(); } - diff --git a/src/cmd/ModelCommandAPI.hh b/src/cmd/ModelCommandAPI.hh index fca2059a8d..c749be820e 100644 --- a/src/cmd/ModelCommandAPI.hh +++ b/src/cmd/ModelCommandAPI.hh @@ -30,4 +30,3 @@ extern "C" GZ_SIM_VISIBLE void cmdModelInfo( const char *_modelName, int _pose, const char *_linkName, const char *_jointName, const char *_sensorName); - diff --git a/src/cmd/cmdmodel.rb.in b/src/cmd/cmdmodel.rb.in old mode 100644 new mode 100755 diff --git a/src/cmd/cmdsim.rb.in b/src/cmd/cmdsim.rb.in index 1ee6829614..8d118d21cf 100755 --- a/src/cmd/cmdsim.rb.in +++ b/src/cmd/cmdsim.rb.in @@ -482,7 +482,7 @@ Please use [GZ_SIM_RESOURCE_PATH] instead." if plugin.end_with? ".dylib" puts "On macOS `gz sim` currently only works with either the -s argument -or the -g argument, you cannot run both server and gui in one terminal. +or the -g argument, you cannot run both server and gui in one terminal. See https://github.com/gazebosim/gz-sim/issues/44 for more info." exit(-1) end diff --git a/src/cmd/model.bash_completion.sh b/src/cmd/model.bash_completion.sh old mode 100644 new mode 100755 diff --git a/src/cmd/sim.bash_completion.sh b/src/cmd/sim.bash_completion.sh old mode 100644 new mode 100755 diff --git a/src/gui/GuiFileHandler.cc b/src/gui/GuiFileHandler.cc index 8eee4490de..6006cd4c2d 100644 --- a/src/gui/GuiFileHandler.cc +++ b/src/gui/GuiFileHandler.cc @@ -114,4 +114,3 @@ void GuiFileHandler::SaveWorldAs(const QString &_fileUrl, } emit newSaveWorldStatus(status, QString::fromStdString(statusMsg.str())); } - diff --git a/src/gui/PathManager.cc b/src/gui/PathManager.cc index 3b88b118d6..a10e806445 100644 --- a/src/gui/PathManager.cc +++ b/src/gui/PathManager.cc @@ -71,4 +71,3 @@ PathManager::PathManager() // Get path updates through this topic this->node.Subscribe("/gazebo/resource_paths", onAddResourcePaths); } - diff --git a/src/gui/plugins/align_tool/AlignTool.qml b/src/gui/plugins/align_tool/AlignTool.qml index a002c0f447..f8f1d624ff 100644 --- a/src/gui/plugins/align_tool/AlignTool.qml +++ b/src/gui/plugins/align_tool/AlignTool.qml @@ -373,7 +373,7 @@ ToolBar { id: relativeAlignList ListElement { text: "First" } ListElement { text: "Last" } - } + } onCurrentIndexChanged: AlignTool.OnAlignTarget(relativeAlignList.get(currentIndex).text) } } diff --git a/src/gui/plugins/component_inspector/SystemPluginInfo.cc b/src/gui/plugins/component_inspector/SystemPluginInfo.cc index 7d64c35328..debaa1eecb 100644 --- a/src/gui/plugins/component_inspector/SystemPluginInfo.cc +++ b/src/gui/plugins/component_inspector/SystemPluginInfo.cc @@ -68,4 +68,3 @@ void SystemPluginInfo::UpdateView(const EntityComponentManager &_ecm, _item->setData(pluginList, ComponentsModel::RoleNames().key("data")); } - diff --git a/src/gui/plugins/component_inspector/Types.hh b/src/gui/plugins/component_inspector/Types.hh index 3625eb189a..1c68ca9c7d 100644 --- a/src/gui/plugins/component_inspector/Types.hh +++ b/src/gui/plugins/component_inspector/Types.hh @@ -39,4 +39,3 @@ namespace inspector } } #endif - diff --git a/src/gui/plugins/component_inspector_editor/Altimeter.qml b/src/gui/plugins/component_inspector_editor/Altimeter.qml index f895aa56d2..55b6d01517 100644 --- a/src/gui/plugins/component_inspector_editor/Altimeter.qml +++ b/src/gui/plugins/component_inspector_editor/Altimeter.qml @@ -41,7 +41,7 @@ Rectangle { // Set the 'expandingHeaderText' value to override the default header // values, which is based on the model. expandingHeaderText: "Altimeter" - expandingHeaderToolTip: "Altimeter sensor properties" + expandingHeaderToolTip: "Altimeter sensor properties" } // This is the content that will be expanded/contracted using the diff --git a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml index 2bec7b8ba2..f1e47ccd81 100644 --- a/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml +++ b/src/gui/plugins/component_inspector_editor/ComponentInspectorEditor.qml @@ -107,7 +107,7 @@ Rectangle { // \param[in] _value The value that should be used to set the _widgetId's // value attribute. function getDecimalsAdjustValue(_widgetId, _value) { - // Make sure to update the value, otherwise zeros are used intead of + // Make sure to update the value, otherwise zeros are used intead of // the actual values. _widgetId.value = _widgetId.activeFocus ? _widgetId.value : _value return getDecimals(_widgetId.width) @@ -614,7 +614,7 @@ Rectangle { ComponentInspectorEditor.OnAddEntity(airPressure.text, "sensor"); } } - + MenuItem { id: altimeter text: "Altimeter" @@ -622,7 +622,7 @@ Rectangle { ComponentInspectorEditor.OnAddEntity(altimeter.text, "sensor"); } } - + MenuItem { id: cameraSensorMenu text: "Camera >" @@ -634,7 +634,7 @@ Rectangle { onEntered: cameraSubmenu.open() } } - + MenuItem { id: contact text: "Contact" @@ -642,7 +642,7 @@ Rectangle { ComponentInspectorEditor.OnAddEntity(contact.text, "sensor"); } } - + MenuItem { id: forceTorque text: "Force torque" @@ -674,7 +674,7 @@ Rectangle { ComponentInspectorEditor.OnAddEntity(imu.text, "sensor"); } } - + MenuItem { id: magnetometer text: "Magnetometer" @@ -683,7 +683,7 @@ Rectangle { } } } - + Menu { id: cameraSubmenu x: addSensorMenu.x - addSensorMenu.width diff --git a/src/gui/plugins/component_inspector_editor/Lidar.cc b/src/gui/plugins/component_inspector_editor/Lidar.cc index 192ae3d6d9..5d027f178a 100644 --- a/src/gui/plugins/component_inspector_editor/Lidar.cc +++ b/src/gui/plugins/component_inspector_editor/Lidar.cc @@ -150,4 +150,3 @@ Q_INVOKABLE void Lidar::OnLidarChange( }; this->inspector->AddUpdateCallback(cb); } - diff --git a/src/gui/plugins/component_inspector_editor/Lidar.qml b/src/gui/plugins/component_inspector_editor/Lidar.qml index 1cfdbe8f34..e335e09b2e 100644 --- a/src/gui/plugins/component_inspector_editor/Lidar.qml +++ b/src/gui/plugins/component_inspector_editor/Lidar.qml @@ -48,28 +48,28 @@ Rectangle { // Noise dynamic bias correlation time property double noiseDynamicBiasCorrelationTime: model.data[5] - // Horizontal scan samples + // Horizontal scan samples property double horizontalScanSamples: model.data[6] - // Horizontal scan resolution + // Horizontal scan resolution property double horizontalScanResolution: model.data[7] - // Horizontal scan min angle + // Horizontal scan min angle property double horizontalScanMinAngle: model.data[8] - // Horizontal scan max angle + // Horizontal scan max angle property double horizontalScanMaxAngle: model.data[9] - // Vertical scan samples + // Vertical scan samples property double verticalScanSamples: model.data[10] - // Vertical scan resolution + // Vertical scan resolution property double verticalScanResolution: model.data[11] - // Vertical scan min angle + // Vertical scan min angle property double verticalScanMinAngle: model.data[12] - // Vertical scan max angle + // Vertical scan max angle property double verticalScanMaxAngle: model.data[13] // Range min @@ -194,24 +194,24 @@ Rectangle { height: rangeGrid.height color: "transparent" Layout.leftMargin: 20 - + GridLayout { id: rangeGrid width: parent.width columns: 4 - - // Padding + + // Padding Rectangle { Layout.columnSpan: 4 height: 4 } - + // Range min Rectangle { color: "transparent" height: 40 Layout.preferredWidth: rangeMinText.width - + Text { id : rangeMinText text: 'Min (m)' @@ -248,13 +248,13 @@ Rectangle { } } // End of min range - + // Max range Rectangle { color: "transparent" height: 40 Layout.preferredWidth: rangeMaxText.width - + Text { id : rangeMaxText text: 'Max (m)' @@ -290,14 +290,14 @@ Rectangle { rangeMaxSpin.onChange.connect(onRangeMax) } } - // End of range max - + // End of range max + // Range resolution Rectangle { color: "transparent" height: 40 Layout.preferredWidth: rangeResolutionText.width - + Text { id : rangeResolutionText text: 'Resolution' @@ -325,7 +325,7 @@ Rectangle { Layout.fillWidth: true height: 40 numberValue: rangeResolution - minValue: 0 + minValue: 0 maxValue: Number.MAX_VALUE stepValue: 0.1 // Connect to the onLidarUpdate signal in Noise.qml @@ -354,7 +354,7 @@ Rectangle { } Rectangle { Layout.fillWidth: true - height: horizontalScan.height + height: horizontalScan.height Layout.leftMargin: 20 color: "transparent" LidarScan { @@ -390,7 +390,7 @@ Rectangle { } Rectangle { Layout.fillWidth: true - height: verticalScan.height + height: verticalScan.height Layout.leftMargin: 20 color: "transparent" diff --git a/src/gui/plugins/component_inspector_editor/LidarScan.qml b/src/gui/plugins/component_inspector_editor/LidarScan.qml index 9283c31fbf..28a049a2ef 100644 --- a/src/gui/plugins/component_inspector_editor/LidarScan.qml +++ b/src/gui/plugins/component_inspector_editor/LidarScan.qml @@ -64,7 +64,7 @@ Rectangle { width: parent.width columns: 4 - // Padding + // Padding Rectangle { Layout.columnSpan: 4 height: 4 @@ -112,7 +112,7 @@ Rectangle { } } // End of samples - + // Resolution Rectangle { color: "transparent" @@ -154,7 +154,7 @@ Rectangle { resolutionSpin.onChange.connect(onResolution) } } - // End of resolution + // End of resolution // Min angle Rectangle { @@ -189,8 +189,8 @@ Rectangle { Layout.fillWidth: true height: 40 numberValue: minAngleValue - minValue: -3.1415 - maxValue: 3.1415 + minValue: -3.1415 + maxValue: 3.1415 stepValue: 0.1 // Send the change signal Component.onCompleted: { @@ -232,8 +232,8 @@ Rectangle { Layout.fillWidth: true height: 40 numberValue: maxAngleValue - minValue: -3.1415 - maxValue: 3.1415 + minValue: -3.1415 + maxValue: 3.1415 stepValue: 0.1 // Connect to the onLidarUpdate signal in Noise.qml Component.onCompleted: { diff --git a/src/gui/plugins/component_inspector_editor/Magnetometer.qml b/src/gui/plugins/component_inspector_editor/Magnetometer.qml index dc182cd667..4dc0027e45 100644 --- a/src/gui/plugins/component_inspector_editor/Magnetometer.qml +++ b/src/gui/plugins/component_inspector_editor/Magnetometer.qml @@ -41,7 +41,7 @@ Rectangle { // Set the 'expandingHeaderText' value to override the default header // values, which is based on the model. expandingHeaderText: "Magnetometer noise" - expandingHeaderToolTip: "Magnetometer noise properties" + expandingHeaderToolTip: "Magnetometer noise properties" } // This is the content that will be expanded/contracted using the diff --git a/src/gui/plugins/component_inspector_editor/Noise.qml b/src/gui/plugins/component_inspector_editor/Noise.qml index 0c782d048d..2f07d6ad50 100644 --- a/src/gui/plugins/component_inspector_editor/Noise.qml +++ b/src/gui/plugins/component_inspector_editor/Noise.qml @@ -49,7 +49,7 @@ Rectangle { property double dynamicBiasCorrelationTime: 0.0 // Signal that a user of this component can connect to in order to receive - // noise updates + // noise updates signal onNoiseUpdate(double _mean, double _meanBias, double _stdDev, double _stdDevBias, double _dynamicBiasStdDev, double _dynamicBiasCorrelationTime) @@ -114,7 +114,7 @@ Rectangle { width: parent.width columns: 4 - // Padding + // Padding Rectangle { Layout.columnSpan: 4 height: 4 @@ -171,7 +171,7 @@ Rectangle { } } // End of mean - + // Mean Bias Rectangle { color: "transparent" @@ -214,8 +214,8 @@ Rectangle { } } // End of mean bias - - // Padding + + // Padding Rectangle { Layout.columnSpan: 4 height: 4 @@ -316,7 +316,7 @@ Rectangle { } // End of stddev bias - // Padding + // Padding Rectangle { Layout.columnSpan: 4 height: 4 diff --git a/src/gui/plugins/component_inspector_editor/StateAwareSpin.qml b/src/gui/plugins/component_inspector_editor/StateAwareSpin.qml index 8396c19194..0650acf2d1 100644 --- a/src/gui/plugins/component_inspector_editor/StateAwareSpin.qml +++ b/src/gui/plugins/component_inspector_editor/StateAwareSpin.qml @@ -36,10 +36,10 @@ Rectangle { property double minValue: 0 // max value - property double maxValue: 1 + property double maxValue: 1 - // value of the spin number value - property double numberValue: 0.0 + // value of the spin number value + property double numberValue: 0.0 signal onChange(double _value) diff --git a/src/gui/plugins/entity_tree/EntityTree.qml b/src/gui/plugins/entity_tree/EntityTree.qml index 1906345505..8b6db13123 100644 --- a/src/gui/plugins/entity_tree/EntityTree.qml +++ b/src/gui/plugins/entity_tree/EntityTree.qml @@ -116,7 +116,7 @@ Rectangle { height: childrenRect.height Text { - text: sectionText + text: sectionText font.pointSize: 10 padding: 5 } @@ -125,7 +125,7 @@ Rectangle { Rectangle { id: header - visible: true + visible: true height: addEntity.height anchors.top: parent.top anchors.left: parent.left @@ -178,7 +178,7 @@ Rectangle { Item { Layout.fillWidth: true height: childrenRect.height - Loader { + Loader { property string sectionText: "Model" sourceComponent: menuSectionHeading } @@ -222,7 +222,7 @@ Rectangle { MenuItem { - id: sphere + id: sphere text: "Sphere" onClicked: { EntityTree.OnInsertEntity("sphere") @@ -231,7 +231,7 @@ Rectangle { MenuItem { - id: mesh + id: mesh text: "Mesh" onClicked: { loadFileDialog.open() @@ -252,7 +252,7 @@ Rectangle { Item { Layout.fillWidth: true height: childrenRect.height - Loader { + Loader { property string sectionText: "Light" sourceComponent: menuSectionHeading } @@ -260,7 +260,7 @@ Rectangle { MenuItem { - id: directionalLight + id: directionalLight text: "Directional" onClicked: { EntityTree.OnInsertEntity("directional") @@ -278,7 +278,7 @@ Rectangle { MenuItem { - id: spotLight + id: spotLight text: "Spot" onClicked: { EntityTree.OnInsertEntity("spot") diff --git a/src/gui/plugins/modules/TypeIcon.qml b/src/gui/plugins/modules/TypeIcon.qml index 36090d8ef5..ece067c38b 100644 --- a/src/gui/plugins/modules/TypeIcon.qml +++ b/src/gui/plugins/modules/TypeIcon.qml @@ -70,4 +70,3 @@ Image { hoverEnabled: true } } - diff --git a/src/gui/plugins/transform_control/CMakeLists.txt b/src/gui/plugins/transform_control/CMakeLists.txt index 58aded7826..69a578fb60 100644 --- a/src/gui/plugins/transform_control/CMakeLists.txt +++ b/src/gui/plugins/transform_control/CMakeLists.txt @@ -5,5 +5,3 @@ gz_add_gui_plugin(TransformControl gz-rendering${GZ_RENDERING_VER}::gz-rendering${GZ_RENDERING_VER} gz-utils${GZ_UTILS_VER}::gz-utils${GZ_UTILS_VER} ) - - diff --git a/src/gui/plugins/video_recorder/VideoRecorder.qml b/src/gui/plugins/video_recorder/VideoRecorder.qml index c56d44fe89..f064c6e7b8 100644 --- a/src/gui/plugins/video_recorder/VideoRecorder.qml +++ b/src/gui/plugins/video_recorder/VideoRecorder.qml @@ -43,7 +43,7 @@ ToolBar { function getFormat(url) { return (url.slice(url.lastIndexOf(".") + 1)) } - + onAccepted: { fileFormat = getFormat(fileUrl.toString()) if (fileFormat == fileUrl.toString()) { @@ -67,7 +67,7 @@ ToolBar { } Dialog { - id: mismatchDialog + id: mismatchDialog title: "Enconding and filename mismatch" modal: true focus: false diff --git a/src/gui/plugins/view_angle/CMakeLists.txt b/src/gui/plugins/view_angle/CMakeLists.txt index 2e13f9ea06..22fa0770c8 100644 --- a/src/gui/plugins/view_angle/CMakeLists.txt +++ b/src/gui/plugins/view_angle/CMakeLists.txt @@ -4,5 +4,3 @@ gz_add_gui_plugin(ViewAngle PRIVATE_LINK_LIBS ${PROJECT_LIBRARY_TARGET_NAME}-rendering ) - - diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.qrc b/src/gui/plugins/visualize_lidar/VisualizeLidar.qrc index a351b7c712..ae58a0abb5 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.qrc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.qrc @@ -2,4 +2,4 @@ VisualizeLidar.qml - \ No newline at end of file + diff --git a/src/msgs/CMakeLists.txt b/src/msgs/CMakeLists.txt index 7941ad8f48..a1e6edad36 100644 --- a/src/msgs/CMakeLists.txt +++ b/src/msgs/CMakeLists.txt @@ -11,4 +11,3 @@ set(PROTO_PRIVATE_HEADERS ${PROTO_PRIVATE_HEADERS} PARENT_SCOPE) add_custom_target(gz-sim_private_msgs DEPENDS ${PROTO_PRIVATE_SRC} ) - diff --git a/src/msgs/simulation_step.proto b/src/msgs/simulation_step.proto index 284380b305..94b13ff1a8 100644 --- a/src/msgs/simulation_step.proto +++ b/src/msgs/simulation_step.proto @@ -35,4 +35,3 @@ message SimulationStep /// affinity changes. repeated PerformerAffinity affinity = 2; } - diff --git a/src/network/NetworkConfig.cc b/src/network/NetworkConfig.cc index e1e0f70e20..7d2fc4b8ad 100644 --- a/src/network/NetworkConfig.cc +++ b/src/network/NetworkConfig.cc @@ -76,4 +76,3 @@ NetworkConfig NetworkConfig::FromValues(const std::string &_role, return config; } - diff --git a/src/network/NetworkConfig_TEST.cc b/src/network/NetworkConfig_TEST.cc index b60ea77f48..d68be8ab33 100644 --- a/src/network/NetworkConfig_TEST.cc +++ b/src/network/NetworkConfig_TEST.cc @@ -60,4 +60,3 @@ TEST(NetworkManager, ValueConstructor) assert(config.role == NetworkRole::None); } } - diff --git a/src/network/NetworkManagerPrimary.hh b/src/network/NetworkManagerPrimary.hh index ddacff70c3..7620d22aea 100644 --- a/src/network/NetworkManagerPrimary.hh +++ b/src/network/NetworkManagerPrimary.hh @@ -128,4 +128,3 @@ namespace gz } // namespace gz #endif // GZ_SIM_NETWORKMANAGERPRIMARY_HH_ - diff --git a/src/network/NetworkManagerPrivate.hh b/src/network/NetworkManagerPrivate.hh index 331765997f..fbae8ff3f3 100644 --- a/src/network/NetworkManagerPrivate.hh +++ b/src/network/NetworkManagerPrivate.hh @@ -73,4 +73,3 @@ namespace gz } // namespace gz #endif // GZ_SIM_NETWORKMANAGER_HH_ - diff --git a/src/network/NetworkManagerSecondary.cc b/src/network/NetworkManagerSecondary.cc index 5ad4806fec..550392958c 100644 --- a/src/network/NetworkManagerSecondary.cc +++ b/src/network/NetworkManagerSecondary.cc @@ -174,4 +174,3 @@ void NetworkManagerSecondary::OnStep( this->dataPtr->ecm->SetAllComponentsUnchanged(); } - diff --git a/src/network/NetworkManagerSecondary.hh b/src/network/NetworkManagerSecondary.hh index 375178bacb..eee72502ae 100644 --- a/src/network/NetworkManagerSecondary.hh +++ b/src/network/NetworkManagerSecondary.hh @@ -87,4 +87,3 @@ namespace gz } // namespace gz #endif // GZ_SIM_NETWORKMANAGERSECONDARY_HH_ - diff --git a/src/network/NetworkRole.hh b/src/network/NetworkRole.hh index 17f1bcfefc..fbd4535b7f 100644 --- a/src/network/NetworkRole.hh +++ b/src/network/NetworkRole.hh @@ -51,4 +51,3 @@ namespace gz } // namespace gz #endif // GZ_SIM_NETWORKROLE_HH_ - diff --git a/src/network/PeerInfo.hh b/src/network/PeerInfo.hh index 75238ae2c2..5064d7c068 100644 --- a/src/network/PeerInfo.hh +++ b/src/network/PeerInfo.hh @@ -65,4 +65,3 @@ namespace gz } // namespace gz #endif // GZ_SIM_NETWORK_PEERINFO_HH_ - diff --git a/src/network/PeerTracker.hh b/src/network/PeerTracker.hh index bb428daeaf..82b8d0c015 100644 --- a/src/network/PeerTracker.hh +++ b/src/network/PeerTracker.hh @@ -222,5 +222,3 @@ namespace gz } // namespace gz #endif // GZ_SIM_NETWORKCONFIG_HH_ - - diff --git a/src/systems/air_pressure/CMakeLists.txt b/src/systems/air_pressure/CMakeLists.txt index 1632110def..cf410eba6a 100644 --- a/src/systems/air_pressure/CMakeLists.txt +++ b/src/systems/air_pressure/CMakeLists.txt @@ -6,4 +6,3 @@ gz_add_system(air-pressure PRIVATE_LINK_LIBS gz-sensors${GZ_SENSORS_VER}::air_pressure ) - diff --git a/src/systems/altimeter/CMakeLists.txt b/src/systems/altimeter/CMakeLists.txt index a6b082275b..f1112eb873 100644 --- a/src/systems/altimeter/CMakeLists.txt +++ b/src/systems/altimeter/CMakeLists.txt @@ -6,4 +6,3 @@ gz_add_system(altimeter PRIVATE_LINK_LIBS gz-sensors${GZ_SENSORS_VER}::altimeter ) - diff --git a/src/systems/elevator/vender/afsm/LICENSE b/src/systems/elevator/vender/afsm/LICENSE index 6a3a57fb25..9d00de5228 100644 --- a/src/systems/elevator/vender/afsm/LICENSE +++ b/src/systems/elevator/vender/afsm/LICENSE @@ -108,7 +108,7 @@ you do at least ONE of the following: (c) allow anyone who receives a copy of the Modified Version to make the Source form of the Modified Version available to others under - + (i) the Original License or (ii) a license that permits the licensee to freely copy, diff --git a/src/systems/elevator/vender/metapushkin/LICENSE b/src/systems/elevator/vender/metapushkin/LICENSE index 6a3a57fb25..9d00de5228 100644 --- a/src/systems/elevator/vender/metapushkin/LICENSE +++ b/src/systems/elevator/vender/metapushkin/LICENSE @@ -108,7 +108,7 @@ you do at least ONE of the following: (c) allow anyone who receives a copy of the Modified Version to make the Source form of the Modified Version available to others under - + (i) the Original License or (ii) a license that permits the licensee to freely copy, diff --git a/src/systems/follow_actor/CMakeLists.txt b/src/systems/follow_actor/CMakeLists.txt index 864371e1d6..929a6cfd37 100644 --- a/src/systems/follow_actor/CMakeLists.txt +++ b/src/systems/follow_actor/CMakeLists.txt @@ -2,4 +2,3 @@ gz_add_system(follow-actor SOURCES FollowActor.cc ) - diff --git a/src/systems/force_torque/CMakeLists.txt b/src/systems/force_torque/CMakeLists.txt index 5cfb64756d..1e41bf0ffe 100644 --- a/src/systems/force_torque/CMakeLists.txt +++ b/src/systems/force_torque/CMakeLists.txt @@ -5,4 +5,4 @@ gz_add_system(forcetorque gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} PRIVATE_LINK_LIBS gz-sensors${GZ_SENSORS_VER}::force_torque -) \ No newline at end of file +) diff --git a/src/systems/imu/CMakeLists.txt b/src/systems/imu/CMakeLists.txt index 66e0b00681..87bf121196 100644 --- a/src/systems/imu/CMakeLists.txt +++ b/src/systems/imu/CMakeLists.txt @@ -6,4 +6,3 @@ gz_add_system(imu PRIVATE_LINK_LIBS gz-sensors${GZ_SENSORS_VER}::imu ) - diff --git a/src/systems/joint_controller/JointController.hh b/src/systems/joint_controller/JointController.hh index 23f10a81a3..9bb10ece91 100644 --- a/src/systems/joint_controller/JointController.hh +++ b/src/systems/joint_controller/JointController.hh @@ -105,4 +105,3 @@ namespace systems } #endif - diff --git a/src/systems/lift_drag/CMakeLists.txt b/src/systems/lift_drag/CMakeLists.txt index c97cb83c33..db63d107a0 100644 --- a/src/systems/lift_drag/CMakeLists.txt +++ b/src/systems/lift_drag/CMakeLists.txt @@ -2,4 +2,3 @@ gz_add_system(lift-drag SOURCES LiftDrag.cc ) - diff --git a/src/systems/lift_drag/LiftDrag.hh b/src/systems/lift_drag/LiftDrag.hh index efbed40502..8c7cba996d 100644 --- a/src/systems/lift_drag/LiftDrag.hh +++ b/src/systems/lift_drag/LiftDrag.hh @@ -93,4 +93,3 @@ namespace systems } #endif - diff --git a/src/systems/logical_camera/CMakeLists.txt b/src/systems/logical_camera/CMakeLists.txt index c946d91b91..a009f6c57e 100644 --- a/src/systems/logical_camera/CMakeLists.txt +++ b/src/systems/logical_camera/CMakeLists.txt @@ -6,4 +6,3 @@ gz_add_system(logical-camera gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER} gz-sensors${GZ_SENSORS_VER}::logical_camera ) - diff --git a/src/systems/navsat/CMakeLists.txt b/src/systems/navsat/CMakeLists.txt index d81b035b16..4ba044faa9 100644 --- a/src/systems/navsat/CMakeLists.txt +++ b/src/systems/navsat/CMakeLists.txt @@ -6,4 +6,3 @@ gz_add_system(navsat PRIVATE_LINK_LIBS gz-sensors${GZ_SENSORS_VER}::navsat ) - diff --git a/src/systems/optical_tactile_plugin/CMakeLists.txt b/src/systems/optical_tactile_plugin/CMakeLists.txt index d4e4661831..1d74f0a721 100644 --- a/src/systems/optical_tactile_plugin/CMakeLists.txt +++ b/src/systems/optical_tactile_plugin/CMakeLists.txt @@ -4,4 +4,4 @@ gz_add_system(opticaltactileplugin Visualization.cc PUBLIC_LINK_LIBS gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} -) \ No newline at end of file +) diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh index b2878f9381..848fa21a61 100644 --- a/src/systems/particle_emitter/ParticleEmitter.hh +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -66,4 +66,3 @@ namespace systems } #endif - diff --git a/src/systems/particle_emitter2/ParticleEmitter2.hh b/src/systems/particle_emitter2/ParticleEmitter2.hh index df35b8e40a..00bd97b129 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.hh +++ b/src/systems/particle_emitter2/ParticleEmitter2.hh @@ -74,4 +74,3 @@ namespace systems } #endif - diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.hh b/src/systems/scene_broadcaster/SceneBroadcaster.hh index ad456209dd..ac3ac33037 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.hh +++ b/src/systems/scene_broadcaster/SceneBroadcaster.hh @@ -71,4 +71,3 @@ namespace systems } } #endif - diff --git a/src/systems/sensors/CMakeLists.txt b/src/systems/sensors/CMakeLists.txt index 7d68172129..306ec4d037 100644 --- a/src/systems/sensors/CMakeLists.txt +++ b/src/systems/sensors/CMakeLists.txt @@ -16,4 +16,3 @@ gz_add_system(sensors gz-sensors${GZ_SENSORS_VER}::thermal_camera gz-sensors${GZ_SENSORS_VER}::wide_angle_camera ) - diff --git a/src/systems/user_commands/CMakeLists.txt b/src/systems/user_commands/CMakeLists.txt index e54987376d..4b4b5a27ab 100644 --- a/src/systems/user_commands/CMakeLists.txt +++ b/src/systems/user_commands/CMakeLists.txt @@ -4,4 +4,3 @@ gz_add_system(user-commands PUBLIC_LINK_LIBS gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} ) - diff --git a/src/systems/velocity_control/VelocityControl.hh b/src/systems/velocity_control/VelocityControl.hh index 431aec98a9..8995cbcdff 100644 --- a/src/systems/velocity_control/VelocityControl.hh +++ b/src/systems/velocity_control/VelocityControl.hh @@ -81,4 +81,3 @@ namespace systems } #endif - diff --git a/src/systems/wind_effects/CMakeLists.txt b/src/systems/wind_effects/CMakeLists.txt index f019bb7534..be2fa77339 100644 --- a/src/systems/wind_effects/CMakeLists.txt +++ b/src/systems/wind_effects/CMakeLists.txt @@ -6,4 +6,3 @@ gz_add_system(wind-effects # Include gz-sensors for noise models gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER} ) - diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 28012fb3d4..0436a5fc32 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,4 +1,4 @@ -configure_file (test_config.hh.in +configure_file (test_config.hh.in ${PROJECT_BINARY_DIR}/include/test_config.hh ) include_directories ( diff --git a/test/benchmark/README.md b/test/benchmark/README.md index a5f7f79b8a..d73688846d 100644 --- a/test/benchmark/README.md +++ b/test/benchmark/README.md @@ -34,4 +34,3 @@ The previous setting can be restored with: ``` sudo cpupower frequency-set --governor powersave ``` - diff --git a/test/find_dri.cmake b/test/find_dri.cmake index ce43b372db..8d03a609f0 100644 --- a/test/find_dri.cmake +++ b/test/find_dri.cmake @@ -100,5 +100,3 @@ set(VALID_DRI_DISPLAY ${VALID_DRI_DISPLAY} PARENT_SCOPE) endfunction() ############################## End FindDRI support ############################# - - diff --git a/test/gtest_vendor/CMakeLists.txt b/test/gtest_vendor/CMakeLists.txt index 5eeb6346b0..ec74d0d89e 100644 --- a/test/gtest_vendor/CMakeLists.txt +++ b/test/gtest_vendor/CMakeLists.txt @@ -1,7 +1,7 @@ add_library(gtest STATIC ${CMAKE_CURRENT_SOURCE_DIR}/src/gtest-all.cc) add_library(gtest_main STATIC ${CMAKE_CURRENT_SOURCE_DIR}/src/gtest_main.cc) -target_include_directories(gtest +target_include_directories(gtest SYSTEM PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include PRIVATE diff --git a/test/gtest_vendor/gtest_vendor_version b/test/gtest_vendor/gtest_vendor_version index 7beba17434..f89a500373 100644 --- a/test/gtest_vendor/gtest_vendor_version +++ b/test/gtest_vendor/gtest_vendor_version @@ -3,6 +3,6 @@ Author: Abseil Team Date: Mon Jun 27 13:15:39 2022 -0700 Mark internal-only function as having internal linkage. - + PiperOrigin-RevId: 457550818 Change-Id: I9046801b64ce4581d742d650451332fd56489632 diff --git a/test/helpers/UniqueTestDirectoryEnv.hh b/test/helpers/UniqueTestDirectoryEnv.hh index 19152eb52c..7fe7be5229 100644 --- a/test/helpers/UniqueTestDirectoryEnv.hh +++ b/test/helpers/UniqueTestDirectoryEnv.hh @@ -98,4 +98,3 @@ class UniqueTestDirectoryEnv : public ::testing::Environment } } #endif - diff --git a/test/integration/apply_joint_force_system.cc b/test/integration/apply_joint_force_system.cc index 1ef189d778..7539b9fc99 100644 --- a/test/integration/apply_joint_force_system.cc +++ b/test/integration/apply_joint_force_system.cc @@ -117,4 +117,3 @@ TEST_F(ApplyJointForceTestFixture, } EXPECT_DOUBLE_EQ(jointForceCmd.back(), testJointForce); } - diff --git a/test/integration/apply_link_wrench_system.cc b/test/integration/apply_link_wrench_system.cc index 714cdbf077..1578cac3d3 100644 --- a/test/integration/apply_link_wrench_system.cc +++ b/test/integration/apply_link_wrench_system.cc @@ -344,4 +344,3 @@ TEST_F(ApplyLinkWrenchTestFixture, EXPECT_EQ(targetIterations, iterations); EXPECT_EQ(1u, impulseIterations); } - diff --git a/test/integration/buoyancy_engine.cc b/test/integration/buoyancy_engine.cc index 6b9616a85a..fe2a132c92 100644 --- a/test/integration/buoyancy_engine.cc +++ b/test/integration/buoyancy_engine.cc @@ -201,4 +201,3 @@ TEST_F(BuoyancyEngineTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(TestUpwardSurface)) EXPECT_NEAR(poses.rbegin()->Pos().X(), poses.begin()->Pos().X(), 1e-3); EXPECT_NEAR(poses.rbegin()->Pos().Y(), poses.begin()->Pos().Y(), 1e-3); } - diff --git a/test/integration/events.cc b/test/integration/events.cc index 30b495b4ee..d549f09433 100644 --- a/test/integration/events.cc +++ b/test/integration/events.cc @@ -53,4 +53,3 @@ TEST_F(EventTrigger, GZ_UTILS_TEST_DISABLED_ON_WIN32(TriggerPause)) server.Run(true, 1, true); EXPECT_FALSE(*server.Paused()); } - diff --git a/test/integration/model.cc b/test/integration/model.cc index 6d403fb32a..f878088631 100644 --- a/test/integration/model.cc +++ b/test/integration/model.cc @@ -261,4 +261,3 @@ TEST_F(ModelIntegrationTest, CanonicalLink) EXPECT_EQ(canonicalLink, model.CanonicalLink(ecm)); EXPECT_EQ(2u, model.LinkCount(ecm)); } - diff --git a/test/integration/world.cc b/test/integration/world.cc index f7de7e9ccf..c0f1931960 100644 --- a/test/integration/world.cc +++ b/test/integration/world.cc @@ -237,4 +237,3 @@ TEST_F(WorldIntegrationTest, ActorByName) EXPECT_EQ(eActor, world.ActorByName(ecm, "actor_name")); EXPECT_EQ(1u, world.ActorCount(ecm)); } - diff --git a/test/performance/CMakeLists.txt b/test/performance/CMakeLists.txt index ba96ad55be..770ba7b937 100644 --- a/test/performance/CMakeLists.txt +++ b/test/performance/CMakeLists.txt @@ -39,4 +39,3 @@ target_link_libraries( gz-sim${PROJECT_VERSION_MAJOR} gz-sim${PROJECT_VERSION_MAJOR}-gui ) - diff --git a/test/performance/README.md b/test/performance/README.md index 5aa90a4670..f69acdbfa5 100644 --- a/test/performance/README.md +++ b/test/performance/README.md @@ -43,4 +43,3 @@ Max RTF: 1.01867 * `gz_perf.py data.csv --plot` Time series plot of RTF vs simualation time * `gz_perf.py data.csv --hist` Histogram of real time factors - diff --git a/test/plugins/EventTriggerSystem.cc b/test/plugins/EventTriggerSystem.cc index 824c85ebe4..b7e1f797f3 100644 --- a/test/plugins/EventTriggerSystem.cc +++ b/test/plugins/EventTriggerSystem.cc @@ -6,4 +6,3 @@ GZ_ADD_PLUGIN(gz::sim::EventTriggerSystem, gz::sim::System, gz::sim::EventTriggerSystem::ISystemConfigure, gz::sim::EventTriggerSystem::ISystemUpdate) - diff --git a/test/plugins/MockSystem.cc b/test/plugins/MockSystem.cc index 4b787d1bd6..0813f3475d 100644 --- a/test/plugins/MockSystem.cc +++ b/test/plugins/MockSystem.cc @@ -8,4 +8,3 @@ GZ_ADD_PLUGIN(gz::sim::MockSystem, gz::sim::System, gz::sim::MockSystem::ISystemPreUpdate, gz::sim::MockSystem::ISystemUpdate, gz::sim::MockSystem::ISystemPostUpdate) - diff --git a/test/plugins/TestModelSystem.cc b/test/plugins/TestModelSystem.cc index 3f966d9e5b..bc1acb75f9 100644 --- a/test/plugins/TestModelSystem.cc +++ b/test/plugins/TestModelSystem.cc @@ -21,4 +21,3 @@ GZ_ADD_PLUGIN(gz::sim::TestModelSystem, gz::sim::System, gz::sim::TestModelSystem::ISystemConfigure) - diff --git a/test/plugins/TestSensorSystem.cc b/test/plugins/TestSensorSystem.cc index 48e0591cc4..c74146b77b 100644 --- a/test/plugins/TestSensorSystem.cc +++ b/test/plugins/TestSensorSystem.cc @@ -21,4 +21,3 @@ GZ_ADD_PLUGIN(gz::sim::TestSensorSystem, gz::sim::System, gz::sim::TestSensorSystem::ISystemConfigure) - diff --git a/test/plugins/TestSystem.hh b/test/plugins/TestSystem.hh index d3269072b1..3e0a0993ff 100644 --- a/test/plugins/TestSystem.hh +++ b/test/plugins/TestSystem.hh @@ -37,4 +37,3 @@ namespace gz #endif - diff --git a/test/plugins/TestWorldSystem.cc b/test/plugins/TestWorldSystem.cc index d4182d8cdd..938524679e 100644 --- a/test/plugins/TestWorldSystem.cc +++ b/test/plugins/TestWorldSystem.cc @@ -22,4 +22,3 @@ GZ_ADD_PLUGIN(gz::sim::TestWorldSystem, gz::sim::System, gz::sim::TestWorldSystem::ISystemConfigure, gz::sim::TestWorldSystem::ISystemUpdate) - diff --git a/test/worlds/buoyancy.sdf.in b/test/worlds/buoyancy.sdf.in index b96adadffe..c384902ae4 100644 --- a/test/worlds/buoyancy.sdf.in +++ b/test/worlds/buoyancy.sdf.in @@ -518,4 +518,3 @@ - diff --git a/test/worlds/buoyancy_graded_restoring_moments.sdf b/test/worlds/buoyancy_graded_restoring_moments.sdf index 4f95e26fa1..b3e082e12e 100644 --- a/test/worlds/buoyancy_graded_restoring_moments.sdf +++ b/test/worlds/buoyancy_graded_restoring_moments.sdf @@ -68,4 +68,4 @@ - \ No newline at end of file + diff --git a/test/worlds/buoyancy_uniform_restoring_moments.sdf b/test/worlds/buoyancy_uniform_restoring_moments.sdf index 53ad22dc74..ef149ef27b 100644 --- a/test/worlds/buoyancy_uniform_restoring_moments.sdf +++ b/test/worlds/buoyancy_uniform_restoring_moments.sdf @@ -62,4 +62,4 @@ - \ No newline at end of file + diff --git a/test/worlds/camera_distortion.sdf b/test/worlds/camera_distortion.sdf index ac75008251..83bb41d4e5 100644 --- a/test/worlds/camera_distortion.sdf +++ b/test/worlds/camera_distortion.sdf @@ -164,5 +164,5 @@ - + diff --git a/test/worlds/center_of_volume.sdf b/test/worlds/center_of_volume.sdf index 0942e68488..4880abd20b 100644 --- a/test/worlds/center_of_volume.sdf +++ b/test/worlds/center_of_volume.sdf @@ -157,4 +157,3 @@ - diff --git a/test/worlds/center_of_volume_graded.sdf b/test/worlds/center_of_volume_graded.sdf index 7f9ef8500e..6c8c84addd 100644 --- a/test/worlds/center_of_volume_graded.sdf +++ b/test/worlds/center_of_volume_graded.sdf @@ -170,4 +170,4 @@ - \ No newline at end of file + diff --git a/test/worlds/diff_drive_custom_tf_topic.sdf b/test/worlds/diff_drive_custom_tf_topic.sdf index 684b001b7d..864b46292a 100644 --- a/test/worlds/diff_drive_custom_tf_topic.sdf +++ b/test/worlds/diff_drive_custom_tf_topic.sdf @@ -241,4 +241,3 @@ - diff --git a/test/worlds/log_playback.sdf b/test/worlds/log_playback.sdf index 568d0828b0..593d41fddb 100644 --- a/test/worlds/log_playback.sdf +++ b/test/worlds/log_playback.sdf @@ -14,4 +14,3 @@ - diff --git a/test/worlds/models/lift_drag_wing/model.config b/test/worlds/models/lift_drag_wing/model.config index 5cb5ee1ec5..ef4c9e89b6 100644 --- a/test/worlds/models/lift_drag_wing/model.config +++ b/test/worlds/models/lift_drag_wing/model.config @@ -4,4 +4,3 @@ 1.0 model.sdf - diff --git a/test/worlds/models/mesh_with_submeshes/model.config b/test/worlds/models/mesh_with_submeshes/model.config index 5f8cbc02f1..cc2ad49b4a 100644 --- a/test/worlds/models/mesh_with_submeshes/model.config +++ b/test/worlds/models/mesh_with_submeshes/model.config @@ -4,4 +4,3 @@ 1.0 model.sdf - diff --git a/test/worlds/models/relative_resource_uri/model.config b/test/worlds/models/relative_resource_uri/model.config index a275b5b10c..de9fb1f685 100644 --- a/test/worlds/models/relative_resource_uri/model.config +++ b/test/worlds/models/relative_resource_uri/model.config @@ -4,4 +4,3 @@ 1.0 model.sdf - diff --git a/test/worlds/models/relative_resource_uri/model.sdf b/test/worlds/models/relative_resource_uri/model.sdf index 93240d1b9a..e9a438ca0d 100644 --- a/test/worlds/models/relative_resource_uri/model.sdf +++ b/test/worlds/models/relative_resource_uri/model.sdf @@ -38,4 +38,3 @@ - diff --git a/test/worlds/models/relative_resource_uri/model2.sdf b/test/worlds/models/relative_resource_uri/model2.sdf index 03ac29cec4..eaa3845b14 100644 --- a/test/worlds/models/relative_resource_uri/model2.sdf +++ b/test/worlds/models/relative_resource_uri/model2.sdf @@ -24,4 +24,3 @@ - diff --git a/test/worlds/models/scheme_resource_uri/model.config b/test/worlds/models/scheme_resource_uri/model.config index fd4cb55a64..9144f1d8da 100644 --- a/test/worlds/models/scheme_resource_uri/model.config +++ b/test/worlds/models/scheme_resource_uri/model.config @@ -4,4 +4,3 @@ 1.0 model.sdf - diff --git a/test/worlds/models/scheme_resource_uri/model.sdf b/test/worlds/models/scheme_resource_uri/model.sdf index a1f122416e..f9f515513f 100644 --- a/test/worlds/models/scheme_resource_uri/model.sdf +++ b/test/worlds/models/scheme_resource_uri/model.sdf @@ -22,4 +22,3 @@ - diff --git a/test/worlds/models/sphere/model.sdf b/test/worlds/models/sphere/model.sdf index ab68145917..f5c56cab9e 100644 --- a/test/worlds/models/sphere/model.sdf +++ b/test/worlds/models/sphere/model.sdf @@ -20,4 +20,3 @@ - diff --git a/test/worlds/odometry_noise.sdf b/test/worlds/odometry_noise.sdf index 4994b1ecd0..2c018e9d5e 100644 --- a/test/worlds/odometry_noise.sdf +++ b/test/worlds/odometry_noise.sdf @@ -228,4 +228,3 @@ - diff --git a/test/worlds/odometry_offset.sdf b/test/worlds/odometry_offset.sdf index 59451f4df0..13cd18c7e6 100644 --- a/test/worlds/odometry_offset.sdf +++ b/test/worlds/odometry_offset.sdf @@ -229,4 +229,3 @@ - diff --git a/test/worlds/odometry_publisher.sdf b/test/worlds/odometry_publisher.sdf index 1d2a4d49af..3f56f86f01 100644 --- a/test/worlds/odometry_publisher.sdf +++ b/test/worlds/odometry_publisher.sdf @@ -227,4 +227,3 @@ - diff --git a/test/worlds/odometry_publisher_custom.sdf b/test/worlds/odometry_publisher_custom.sdf index 1671ad2566..5992f68c73 100644 --- a/test/worlds/odometry_publisher_custom.sdf +++ b/test/worlds/odometry_publisher_custom.sdf @@ -231,4 +231,3 @@ - diff --git a/test/worlds/particle_emitter.sdf b/test/worlds/particle_emitter.sdf index 73fb923177..f89e9d9e26 100644 --- a/test/worlds/particle_emitter.sdf +++ b/test/worlds/particle_emitter.sdf @@ -107,5 +107,3 @@ - - diff --git a/test/worlds/plugins_empty.sdf b/test/worlds/plugins_empty.sdf index 6061dfccde..106fc9d8f8 100644 --- a/test/worlds/plugins_empty.sdf +++ b/test/worlds/plugins_empty.sdf @@ -14,4 +14,3 @@ - diff --git a/test/worlds/server_invalid.config b/test/worlds/server_invalid.config index 48cc6ec97a..ff0d74c7b1 100644 --- a/test/worlds/server_invalid.config +++ b/test/worlds/server_invalid.config @@ -1,4 +1,4 @@ - @@ -10,4 +10,3 @@ Example server configuration that is NOT valid 0.123 - diff --git a/test/worlds/server_valid.config b/test/worlds/server_valid.config index 39217fd30f..4da1809bda 100644 --- a/test/worlds/server_valid.config +++ b/test/worlds/server_valid.config @@ -1,4 +1,4 @@ - diff --git a/test/worlds/server_valid2.config b/test/worlds/server_valid2.config index 598077a39a..26ab5553da 100644 --- a/test/worlds/server_valid2.config +++ b/test/worlds/server_valid2.config @@ -1,4 +1,4 @@ - diff --git a/test/worlds/static_diff_drive_vehicle.sdf b/test/worlds/static_diff_drive_vehicle.sdf index 618ba1b6a0..5613755e81 100644 --- a/test/worlds/static_diff_drive_vehicle.sdf +++ b/test/worlds/static_diff_drive_vehicle.sdf @@ -221,6 +221,6 @@ true - + diff --git a/test/worlds/triggered_publisher.sdf b/test/worlds/triggered_publisher.sdf index 6db3da4606..b51a693c3c 100644 --- a/test/worlds/triggered_publisher.sdf +++ b/test/worlds/triggered_publisher.sdf @@ -253,4 +253,3 @@ - diff --git a/tutorials/blender_distort_meshes.md b/tutorials/blender_distort_meshes.md index 7cf5a77d25..853337332b 100644 --- a/tutorials/blender_distort_meshes.md +++ b/tutorials/blender_distort_meshes.md @@ -233,4 +233,3 @@ There are example calls in the Python script. - Blender sometimes does not export the texture back to a COLLADA file correctly. Importing OBJ and exporting COLLADA works fine. - diff --git a/tutorials/erb_template.md b/tutorials/erb_template.md index e30da7cb9f..e38f5cd1d4 100644 --- a/tutorials/erb_template.md +++ b/tutorials/erb_template.md @@ -6,7 +6,7 @@ In this case, since most simulation world used in gazebo is defined with [SDForm ## Why ERB -There are many use cases and advantages of using ERB in your SDF file. +There are many use cases and advantages of using ERB in your SDF file. Some of them are listed below and demonstrated in this [example ERB file](https://github.com/osrf/srcsim/blob/master/worlds/unique.world.erb): 1. Embedding logic into the SDF, such as loops and conditionals @@ -18,7 +18,7 @@ Some of them are listed below and demonstrated in this [example ERB file](https: Firstly, Ruby needs to be installed. If you have gone through [Gazebo Sim's installation guide](https://gazebosim.org/docs/latest/install), it's most likely you already have Ruby installed. -To check if Ruby is installed, use +To check if Ruby is installed, use ```{.sh} ruby --version ``` @@ -104,7 +104,7 @@ Each box model also has a different name and pose to ensure they show up as indi [Here](https://github.com/gazebosim/gz-sim/blob/main/examples/worlds/shapes_population.sdf.erb) is a complete shapes simulation world example. -Instead of simple shapes, you can also use a nested loop to generate 100 actors spaced out evenly in a simulation world. +Instead of simple shapes, you can also use a nested loop to generate 100 actors spaced out evenly in a simulation world. ``` <% @@ -145,7 +145,7 @@ Instead of simple shapes, you can also use a nested loop to generate 100 actors end %> ``` - + ## Generate SDF from ERB template Now that an ERB template file is ready and saved as `my_first_erb.erb`, you can run the following terminal command to generate the corresponding SDF file. diff --git a/tutorials/files/spherical_coordinates/ENU.svg b/tutorials/files/spherical_coordinates/ENU.svg index c97ca18197..add223c170 100644 --- a/tutorials/files/spherical_coordinates/ENU.svg +++ b/tutorials/files/spherical_coordinates/ENU.svg @@ -345,4 +345,4 @@ y="-379.30618" id="tspan3727-8-4-5-7-1">λ - \ No newline at end of file + diff --git a/tutorials/gui_config.md b/tutorials/gui_config.md index e43960f3a0..b3c028a531 100644 --- a/tutorials/gui_config.md +++ b/tutorials/gui_config.md @@ -190,6 +190,3 @@ hand, we'll create it from the UI. save directly to `$HOME/.gz/sim/<#>/gui.config`. @image html files/gui_config/cmd_line.png - - - diff --git a/tutorials/headless_rendering.md b/tutorials/headless_rendering.md index 2e4f9a30fe..6c01ef756d 100644 --- a/tutorials/headless_rendering.md +++ b/tutorials/headless_rendering.md @@ -1,5 +1,5 @@ -\page headless_rendering Headless Rendering - +\page headless_rendering Headless Rendering + It is often desirable to run simulation on a remote computer, such as a computer managed by cloud provider, in order to paralellize work or access specific compute resources. Simulated sensors that require GPU access have @@ -35,7 +35,7 @@ here](https://www.ogre3d.org/2021/02/06/ogre-2-2-5-cerberus-released-and-egl-hea 3. Select `Ubuntu Server` version 20.04 or greater from the AMI list. 4. Choose a GPU enabled instance type, such as `g3.4xlarge`. 5. Enable `Auto-assign Public IP` on the `Configure Instance Details` step. - This is not the best practice, but it simplifies this tutorial. + This is not the best practice, but it simplifies this tutorial. 6. Add around 200GB storage to your instance on the `Add Storage` step. 7. Enable ssh source `Anywhere` on the `Configure Security Group` step. 8. Review and launch your instance. Make sure to setup a key pair in the diff --git a/tutorials/migration_plugins.md b/tutorials/migration_plugins.md index ebbe942433..25104ee695 100644 --- a/tutorials/migration_plugins.md +++ b/tutorials/migration_plugins.md @@ -254,4 +254,3 @@ In summary, the key differences between Gazebo Classic and Gazebo are: All these changes are meant to give plugin developers more flexibility to only use the features they need, and several layers of abstraction which can be chosen according to the developer's experience and specific use-case. - diff --git a/tutorials/rendering_plugins.md b/tutorials/rendering_plugins.md index d41d8137a8..0ba4e34003 100644 --- a/tutorials/rendering_plugins.md +++ b/tutorials/rendering_plugins.md @@ -135,4 +135,3 @@ the one on the GUI. Try pausing simulation and pressing the `RANDOM GUI COLOR` button to see which scene gets updated. @image html files/rendering_plugins.gif - diff --git a/tutorials/terminology.md b/tutorials/terminology.md index 44690bfa25..b4e8df5e6c 100644 --- a/tutorials/terminology.md +++ b/tutorials/terminology.md @@ -80,4 +80,3 @@ to developers touching the source code. * **Server**: Gazebo Sim's entry point. It's responsible for loading an SDF file and instantiating a simulation runner per world. - From 021ff49cb315ae238daaea5b85ad25f6be07856e Mon Sep 17 00:00:00 2001 From: Aditya Pande Date: Thu, 17 Nov 2022 14:17:02 -0800 Subject: [PATCH 3/6] Acoustic comms : Propagation model (#1793) * Added propagation model, test cases Signed-off-by: Aditya --- .../worlds/acoustic_comms_propagation.sdf | 264 ++++++++++++++++++ src/systems/acoustic_comms/AcousticComms.cc | 91 ++++++ src/systems/acoustic_comms/AcousticComms.hh | 30 +- test/integration/acoustic_comms.cc | 6 +- 4 files changed, 387 insertions(+), 4 deletions(-) create mode 100644 examples/worlds/acoustic_comms_propagation.sdf diff --git a/examples/worlds/acoustic_comms_propagation.sdf b/examples/worlds/acoustic_comms_propagation.sdf new file mode 100644 index 0000000000..7ccde3ad2d --- /dev/null +++ b/examples/worlds/acoustic_comms_propagation.sdf @@ -0,0 +1,264 @@ + + + + + + + 0.001 + 1.0 + + + + + + + + + 6 + 1400 + + + + + 0.001 + 150 + 7 + 0 + + + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 2 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + +
addr1
+ addr1/rx +
+
+ + + -2 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + +
addr2
+ addr2/rx + + /broker/bind + /broker/unbind + +
+ +
+ + + 5 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + +
addr3
+ addr3/rx +
+
+ + + -5 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + +
addr4
+ addr4/rx +
+
+ +
+
diff --git a/src/systems/acoustic_comms/AcousticComms.cc b/src/systems/acoustic_comms/AcousticComms.cc index 93699fdd70..f11f56821e 100644 --- a/src/systems/acoustic_comms/AcousticComms.cc +++ b/src/systems/acoustic_comms/AcousticComms.cc @@ -61,8 +61,78 @@ class AcousticComms::Implementation std::tuple, std::chrono::duration>> lastMsgReceivedInfo; + + /// \brief This method simulates the propagation model, + /// and returns false if the packet was dropped, otherwise true. + public: bool propagationModel(double _distToSource, + int _numBytes); + + /// \brief Source power in Watts. + /// \ref https://www.sciencedirect.com/topics/ + /// computer-science/underwater-acoustic-signal + public: double sourcePower = 2000; + + /// \brief Ratio of the noise intensity at the + /// receiver to the same reference intensity used for source level. + public: double noiseLevel = 1; + + /// \brief Information rate that can be transmitted over a given + /// bandwidth in a specific communication system, in (bits/sec)/Hz. + /// \ref: https://www.ncbi.nlm.nih.gov/pmc/articles/PMC5514747/ + public: double spectralEfficiency = 7.0; + + /// \brief Flag to store if the propagation model should be used. + public: bool usePropagationModel = false; + + /// \brief Seed value for random sampling. + public: unsigned int seed = 0; }; +////////////////////////////////////////////////// +bool AcousticComms::Implementation::propagationModel( + double _distToSource, + int _numBytes +) +{ + // From https://www.mathworks.com/help/phased/ug/sonar-equation.html + // SNR = SL - TL - (NL - DI) + // SNR : Signal to noise ratio. + // SL : Source level. Ratio of the transmitted intensity from + // the source to a reference intensity (1 m from source), + // converted to dB. + // TL : Transmission loss (dB) + // NL : Noise level. + + // The constant 170.8 comes from reference intensity measured + // 1m from the source. + double sl = 170.8 + 10 * std::log10(this->sourcePower); + double tl = 20 * std::log10(_distToSource); + + // Calculate SNR. + auto snr = sl - tl - this->noiseLevel; + + // References : https://www.montana.edu/aolson/ee447/EB%20and%20NO.pdf + // https://en.wikipedia.org/wiki/Eb/N0 + auto EbByN0 = snr / this->spectralEfficiency; + + // Bit error rate calculation using BPSK. + // Reference : https://www.gaussianwaves.com/2012/07/ + // intuitive-derivation-of-performance-of-an-optimum- + // bpsk-receiver-in-awgn-channel/ + // Reference : https://unetstack.net/handbook/unet-handbook_modems + // _and_channel_models.html + auto ber = 0.5 * std::erfc(EbByN0); + + // Calculate if the packet was dropped. + double packetDropProb = + 1.0 - std::exp(static_cast(_numBytes) * + std::log(1 - ber)); + + gz::math::Rand::Seed(this->seed); + double randDraw = gz::math::Rand::DblUniform(); + return randDraw > packetDropProb; +} + ////////////////////////////////////////////////// AcousticComms::AcousticComms() : dataPtr(gz::utils::MakeUniqueImpl()) @@ -90,6 +160,18 @@ void AcousticComms::Load( _sdf->Get("collision_time_per_byte"); } + if (_sdf->HasElement("propagation_model")) + { + this->dataPtr->usePropagationModel = true; + sdf::ElementPtr propElement = _sdf->Clone()-> + GetElement("propagation_model"); + this->dataPtr->sourcePower = propElement->Get("source_power"); + this->dataPtr->noiseLevel = propElement->Get("noise_level"); + this->dataPtr->spectralEfficiency = + propElement->Get("spectral_efficiency"); + this->dataPtr->seed = propElement->Get("seed"); + } + gzmsg << "AcousticComms configured with max range : " << this->dataPtr->maxRange << " m and speed of sound : " << this->dataPtr->speedOfSound << " m/s." << std::endl; @@ -222,6 +304,15 @@ void AcousticComms::Step( receivedSuccessfully = true; } + // Packet has survived collisions, check if the propagation model + // should be run on this packet. + if (this->dataPtr->usePropagationModel) + { + receivedSuccessfully = receivedSuccessfully && + this->dataPtr->propagationModel(distanceCoveredByMessage, + msg->data().length()); + } + // This message needs to be processed. // Push the msg to inbound of the destination if // receivedSuccessfully is true, else it is dropped. diff --git a/src/systems/acoustic_comms/AcousticComms.hh b/src/systems/acoustic_comms/AcousticComms.hh index f443e3970c..2845436cef 100644 --- a/src/systems/acoustic_comms/AcousticComms.hh +++ b/src/systems/acoustic_comms/AcousticComms.hh @@ -28,6 +28,7 @@ #include #include +#include #include "gz/sim/comms/ICommsModel.hh" #include #include @@ -55,19 +56,42 @@ namespace systems /// * : If a subscriber receives a message /// 'b' bytes long at time 't0', it won't receive /// and other message till time : - /// 't0 + b * collision_time_per_byte' + /// 't0 + b * collision_time_per_byte'. + /// Defaults to zero. /// * : If a packet is dropped at time /// `t0`, the next packet won't be received until - /// time `t0 + collision_time_packet_drop` + /// time `t0 + collision_time_packet_drop`. + /// Defaults to zero. + /// * : Enables the use of propagation model. + /// Disabled by default. + /// * : Source power at the transmitter in Watts. + /// Defaults to 2 kW. + /// * : Ratio of the noise intensity at the + /// receiver to the same reference intensity used + /// for source level. Defaults to 1. + /// * : Information rate that can be transmitted + /// over a given bandwidth in a specific + /// communication system, in (bits/sec)/Hz. + /// Defaults to 7 bits/sec/Hz. + /// * : Seed value to be used for random sampling. /// /// Here's an example: /// - /// 6 + /// + /// 500 /// 1400 + /// /// 0.001 /// 0.001 + /// + /// + /// 2000 + /// 1 + /// 7 + /// + /// /// class AcousticComms: diff --git a/test/integration/acoustic_comms.cc b/test/integration/acoustic_comms.cc index a0d0c4e930..cb4a447ee6 100644 --- a/test/integration/acoustic_comms.cc +++ b/test/integration/acoustic_comms.cc @@ -161,6 +161,10 @@ INSTANTIATE_TEST_SUITE_P( // Message packets will be dropped as they are sent too fast // compared to "collision_time_interval". AcousticCommsTestDefinition( - "acoustic_comms_packet_collision.sdf", "addr2", "addr1", 3, 1) + "acoustic_comms_packet_collision.sdf", "addr2", "addr1", 3, 1), + // Source power is decreased and noise bumped up to make the packets + // drop. + AcousticCommsTestDefinition( + "acoustic_comms_propagation.sdf", "addr2", "addr1", 3, 0) ) ); From 4fa1f26a738cbdb3ff0c4a37fdde9506f3cd9b4e Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Mon, 21 Nov 2022 14:27:45 +0800 Subject: [PATCH 4/6] Backport #1748: Adds a tool for environment data visualization and custom environmental sensors (#1798) This PR adds a tool to visualize Scalar Environmental Data. It also adds custom sensors. Signed-off-by: Arjo Chakravarty --- examples/worlds/environmental_data.csv | 17 + examples/worlds/environmental_sensor.sdf | 112 ++++++ include/gz/sim/Util.hh | 14 + include/gz/sim/components/Environment.hh | 16 +- src/Util.cc | 40 ++ src/components/Environment.cc | 5 +- src/gui/plugins/CMakeLists.txt | 1 + .../environment_loader/EnvironmentLoader.cc | 40 +- .../environment_loader/EnvironmentLoader.hh | 26 ++ .../environment_loader/EnvironmentLoader.qml | 29 +- .../environment_visualization/CMakeLists.txt | 8 + .../EnvironmentVisualization.cc | 313 +++++++++++++++ .../EnvironmentVisualization.hh | 80 ++++ .../EnvironmentVisualization.qml | 111 ++++++ .../EnvironmentVisualization.qrc | 5 + src/systems/CMakeLists.txt | 1 + .../environment_preload/EnvironmentPreload.cc | 23 +- .../CMakeLists.txt | 8 + .../EnvironmentalSensorSystem.cc | 359 ++++++++++++++++++ .../EnvironmentalSensorSystem.hh | 68 ++++ test/integration/CMakeLists.txt | 1 + .../integration/environment_preload_system.cc | 64 +++- .../environmental_sensor_system.cc | 84 ++++ test/worlds/CMakeLists.txt | 2 + test/worlds/environmental_data.sdf.in | 13 +- test/worlds/environmental_sensor.csv | 17 + test/worlds/environmental_sensor.sdf.in | 112 ++++++ 27 files changed, 1558 insertions(+), 11 deletions(-) create mode 100644 examples/worlds/environmental_data.csv create mode 100644 examples/worlds/environmental_sensor.sdf create mode 100644 src/gui/plugins/environment_visualization/CMakeLists.txt create mode 100644 src/gui/plugins/environment_visualization/EnvironmentVisualization.cc create mode 100644 src/gui/plugins/environment_visualization/EnvironmentVisualization.hh create mode 100644 src/gui/plugins/environment_visualization/EnvironmentVisualization.qml create mode 100644 src/gui/plugins/environment_visualization/EnvironmentVisualization.qrc create mode 100644 src/systems/environmental_sensor_system/CMakeLists.txt create mode 100644 src/systems/environmental_sensor_system/EnvironmentalSensorSystem.cc create mode 100644 src/systems/environmental_sensor_system/EnvironmentalSensorSystem.hh create mode 100644 test/integration/environmental_sensor_system.cc create mode 100644 test/worlds/environmental_sensor.csv create mode 100644 test/worlds/environmental_sensor.sdf.in diff --git a/examples/worlds/environmental_data.csv b/examples/worlds/environmental_data.csv new file mode 100644 index 0000000000..fbd1ee7d0a --- /dev/null +++ b/examples/worlds/environmental_data.csv @@ -0,0 +1,17 @@ +timestamp,humidity,x,y,z +0,80,-1,-1,-1 +0,80,-1,-1, 1 +0,80,-1, 1,-1 +0,80,-1, 1, 1 +0,90, 1,-1,-1 +0,90, 1,-1, 1 +0,90, 1, 1,-1 +0,90, 1, 1, 1 +1,90,-1,-1,-1 +1,90,-1,-1, 1 +1,90,-1, 1,-1 +1,90,-1, 1, 1 +1,90, 1,-1,-1 +1,90, 1,-1, 1 +1,90, 1, 1,-1 +1,90, 1, 1, 1 diff --git a/examples/worlds/environmental_sensor.sdf b/examples/worlds/environmental_sensor.sdf new file mode 100644 index 0000000000..e1947c8591 --- /dev/null +++ b/examples/worlds/environmental_sensor.sdf @@ -0,0 +1,112 @@ + + + + + + + + + + + + + + + + environmental_data.csv + + + + x + y + z + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0.05 0 0 0 + + + 0.1 + + 0.000166667 + 0.000166667 + 0.000166667 + + + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1 + 30 + + + + + + diff --git a/include/gz/sim/Util.hh b/include/gz/sim/Util.hh index 734a7e1436..631455bb83 100644 --- a/include/gz/sim/Util.hh +++ b/include/gz/sim/Util.hh @@ -19,17 +19,21 @@ #include +#include #include #include #include #include + +#include "gz/sim/components/Environment.hh" #include "gz/sim/config.hh" #include "gz/sim/Entity.hh" #include "gz/sim/EntityComponentManager.hh" #include "gz/sim/Export.hh" #include "gz/sim/Types.hh" + namespace gz { namespace sim @@ -288,6 +292,16 @@ namespace gz std::optional GZ_SIM_VISIBLE sphericalCoordinates( Entity _entity, const EntityComponentManager &_ecm); + /// \brief Get grid field coordinates based on a world position in cartesian + /// coordinate frames. + /// \param[in] _ecm Entity Component Manager + /// \param[in] _worldPosition world position + /// \param[in] _gridField Gridfield you are interested in. + std::optional GZ_SIM_VISIBLE getGridFieldCoordinates( + const EntityComponentManager &_ecm, + const math::Vector3d& _worldPosition, + const std::shared_ptr& _gridField); + /// \brief Environment variable holding resource paths. const std::string kResourcePathEnv{"GZ_SIM_RESOURCE_PATH"}; diff --git a/include/gz/sim/components/Environment.hh b/include/gz/sim/components/Environment.hh index a0e721e8cd..57c84a4cf0 100644 --- a/include/gz/sim/components/Environment.hh +++ b/include/gz/sim/components/Environment.hh @@ -46,6 +46,12 @@ namespace components using FrameT = common::DataFrame; using ReferenceT = math::SphericalCoordinates::CoordinateType; + /// \brief Reference units + enum class ReferenceUnits { + RADIANS = 0, + DEGREES + }; + /// \brief Instantiate environmental data. /// /// An std::make_shared equivalent that ensures @@ -53,13 +59,21 @@ namespace components /// instantiation that is guaranteed to outlive /// them. static std::shared_ptr - MakeShared(FrameT _frame, ReferenceT _reference); + MakeShared(FrameT _frame, ReferenceT _reference, + ReferenceUnits _units = ReferenceUnits::RADIANS, + bool _ignoreTimeStep = false); /// \brief Environmental data frame. FrameT frame; /// \brief Spatial reference for data coordinates. ReferenceT reference; + + /// \brief The units to be used (only for spherical coordinates) + ReferenceUnits units; + + /// \brief Use time axis or not. + bool staticTime; }; /// \brief A component type that contains a environment data. diff --git a/src/Util.cc b/src/Util.cc index 56f0fca50f..9b786d43df 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -30,6 +30,7 @@ #include "gz/sim/components/Actor.hh" #include "gz/sim/components/Collision.hh" +#include "gz/sim/components/Environment.hh" #include "gz/sim/components/Joint.hh" #include "gz/sim/components/Light.hh" #include "gz/sim/components/Link.hh" @@ -671,6 +672,45 @@ std::optional sphericalCoordinates(Entity _entity, return math::Vector3d(GZ_RTOD(rad.X()), GZ_RTOD(rad.Y()), rad.Z()); } +////////////////////////////////////////////////// +std::optional getGridFieldCoordinates( + const EntityComponentManager &_ecm, + const math::Vector3d& _worldPosition, + const std::shared_ptr& _gridField + ) +{ + + auto origin = + _ecm.Component(worldEntity(_ecm)); + if (!origin) + { + if (_gridField->reference == math::SphericalCoordinates::SPHERICAL) + { + // If the reference frame is spherical, we must have some world reference + // coordinates. + gzerr << "World has no spherical coordinates," + << " but data was loaded with spherical reference plane" + << std::endl; + return std::nullopt; + } + else + { + // No need to transform + return _worldPosition; + } + } + auto position = origin->Data().PositionTransform( + _worldPosition, math::SphericalCoordinates::LOCAL2, + _gridField->reference); + if (_gridField->reference == math::SphericalCoordinates::SPHERICAL && + _gridField->units == components::EnvironmentalData::ReferenceUnits::DEGREES) + { + position.X(GZ_RTOD(position.X())); + position.Y(GZ_RTOD(position.Y())); + } + return position; +} + ////////////////////////////////////////////////// // Getting the first .sdf file in the path std::string findFuelResourceSdf(const std::string &_path) diff --git a/src/components/Environment.cc b/src/components/Environment.cc index 65232966c4..ccd498688d 100644 --- a/src/components/Environment.cc +++ b/src/components/Environment.cc @@ -23,10 +23,13 @@ using namespace gz::sim::components; std::shared_ptr -EnvironmentalData::MakeShared(FrameT _frame, ReferenceT _reference) +EnvironmentalData::MakeShared(FrameT _frame, ReferenceT _reference, + ReferenceUnits _units, bool _ignoreTimeStep) { auto data = std::make_shared(); data->frame = std::move(_frame); data->reference = _reference; + data->units = _units; + data->staticTime = _ignoreTimeStep; return data; } diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt index 7d092c36dc..956158f39c 100644 --- a/src/gui/plugins/CMakeLists.txt +++ b/src/gui/plugins/CMakeLists.txt @@ -136,6 +136,7 @@ add_subdirectory(copy_paste) add_subdirectory(entity_context_menu) add_subdirectory(entity_tree) add_subdirectory(environment_loader) +add_subdirectory(environment_visualization) add_subdirectory(joint_position_controller) add_subdirectory(lights) add_subdirectory(playback_scrubber) diff --git a/src/gui/plugins/environment_loader/EnvironmentLoader.cc b/src/gui/plugins/environment_loader/EnvironmentLoader.cc index c7ec575e0f..6ac8b464cf 100644 --- a/src/gui/plugins/environment_loader/EnvironmentLoader.cc +++ b/src/gui/plugins/environment_loader/EnvironmentLoader.cc @@ -64,6 +64,9 @@ class EnvironmentLoaderPrivate /// \brief Index of data dimension to be used as z coordinate. public: int zIndex{-1}; + /// \brief Index of data dimension to be used as units. + public: QString unit; + public: using ReferenceT = math::SphericalCoordinates::CoordinateType; /// \brief Map of supported spatial references. @@ -72,6 +75,15 @@ class EnvironmentLoaderPrivate {QString("spherical"), math::SphericalCoordinates::SPHERICAL}, {QString("ecef"), math::SphericalCoordinates::ECEF}}; + /// \brief Map of supported spatial units. + public: const QMap + unitMap{ + {QString("degree"), + components::EnvironmentalData::ReferenceUnits::DEGREES}, + {QString("radians"), + components::EnvironmentalData::ReferenceUnits::RADIANS} + }; + /// \brief Spatial reference. public: QString reference; @@ -116,6 +128,8 @@ void EnvironmentLoader::Update(const UpdateInfo &, std::lock_guard lock(this->dataPtr->mutex); this->dataPtr->needsLoad = false; + /// TODO(arjo): Handle the case where we are loading a file in windows. + /// Should SDFormat files support going from windows <=> unix paths? std::ifstream dataFile(this->dataPtr->dataPath.toStdString()); gzmsg << "Loading environmental data from " << this->dataPtr->dataPath.toStdString() @@ -131,7 +145,8 @@ void EnvironmentLoader::Update(const UpdateInfo &, static_cast(this->dataPtr->xIndex), static_cast(this->dataPtr->yIndex), static_cast(this->dataPtr->zIndex)}), - this->dataPtr->referenceMap[this->dataPtr->reference]); + this->dataPtr->referenceMap[this->dataPtr->reference], + this->dataPtr->unitMap[this->dataPtr->unit]); using ComponentT = components::Environment; _ecm.CreateComponent(worldEntity(_ecm), ComponentT{std::move(data)}); @@ -210,6 +225,29 @@ QStringList EnvironmentLoader::DimensionList() const return this->dataPtr->dimensionList; } +///////////////////////////////////////////////// +QStringList EnvironmentLoader::UnitList() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->unitMap.keys(); +} + +///////////////////////////////////////////////// +QString EnvironmentLoader::Unit() const +{ + std::lock_guard lock(this->dataPtr->mutex); + return this->dataPtr->unit; +} + +///////////////////////////////////////////////// +void EnvironmentLoader::SetUnit(QString _unit) +{ + { + std::lock_guard lock(this->dataPtr->mutex); + this->dataPtr->unit = _unit; + } + this->IsConfiguredChanged(); +} ///////////////////////////////////////////////// int EnvironmentLoader::TimeIndex() const { diff --git a/src/gui/plugins/environment_loader/EnvironmentLoader.hh b/src/gui/plugins/environment_loader/EnvironmentLoader.hh index 08ab2b773c..6a77d1e00c 100644 --- a/src/gui/plugins/environment_loader/EnvironmentLoader.hh +++ b/src/gui/plugins/environment_loader/EnvironmentLoader.hh @@ -55,6 +55,20 @@ inline namespace GZ_SIM_VERSION_NAMESPACE NOTIFY DimensionListChanged ) + /// \brief Unit list + Q_PROPERTY( + QStringList unitList + READ UnitList + ) + + /// \brief Unit list + Q_PROPERTY( + QString unit + READ Unit + WRITE SetUnit + NOTIFY UnitChanged + ) + /// \brief Time index Q_PROPERTY( int timeIndex @@ -136,6 +150,9 @@ inline namespace GZ_SIM_VERSION_NAMESPACE /// \brief Get dimensions available in the data file public: Q_INVOKABLE QStringList DimensionList() const; + /// \brief Get available units + public: Q_INVOKABLE QStringList UnitList() const; + /// \brief Notify that the list of dimensions has changed signals: void DimensionListChanged(); @@ -187,6 +204,15 @@ inline namespace GZ_SIM_VERSION_NAMESPACE /// \brief Notify the spatial reference has changed signals: void ReferenceChanged() const; + /// \brief Get index of the unit in the list + public: Q_INVOKABLE QString Unit() const; + + /// \brief Set index of the unit in the list + public: Q_INVOKABLE void SetUnit(QString _unit); + + /// \brief Notify the unit index has changed + signals: void UnitChanged() const; + /// \brief Get configuration status public: Q_INVOKABLE bool IsConfigured() const; diff --git a/src/gui/plugins/environment_loader/EnvironmentLoader.qml b/src/gui/plugins/environment_loader/EnvironmentLoader.qml index cd8b1001f6..f56ec83db0 100644 --- a/src/gui/plugins/environment_loader/EnvironmentLoader.qml +++ b/src/gui/plugins/environment_loader/EnvironmentLoader.qml @@ -26,7 +26,7 @@ GridLayout { columns: 8 columnSpacing: 10 Layout.minimumWidth: 350 - Layout.minimumHeight: 400 + Layout.minimumHeight: 500 anchors.fill: parent anchors.leftMargin: 10 anchors.rightMargin: 10 @@ -203,9 +203,34 @@ GridLayout { ToolTip.text: qsTr("Reference for spatial dimensions") } + Label { + Layout.row: 6 + Layout.columnSpan: 1 + horizontalAlignment: Text.AlignRight + id: unitText + color: "dimgrey" + text: qsTr("Units") + } + + ComboBox { + Layout.row: 6 + Layout.column: 2 + Layout.columnSpan: 6 + id: unitsConversion + Layout.fillWidth: true + enabled: referenceCombo.currentIndex == 2 + model: EnvironmentLoader.unitList + onCurrentTextChanged: { + EnvironmentLoader.unit = currentText + } + ToolTip.visible: hovered + ToolTip.text: qsTr("Units") + } + + Button { text: qsTr("Load") - Layout.row: 6 + Layout.row: 7 Layout.columnSpan: 8 Layout.fillWidth: true enabled: EnvironmentLoader.configured diff --git a/src/gui/plugins/environment_visualization/CMakeLists.txt b/src/gui/plugins/environment_visualization/CMakeLists.txt new file mode 100644 index 0000000000..893365700d --- /dev/null +++ b/src/gui/plugins/environment_visualization/CMakeLists.txt @@ -0,0 +1,8 @@ +gz_add_gui_plugin(EnvironmentVisualization + SOURCES EnvironmentVisualization.cc + QT_HEADERS EnvironmentVisualization.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} +) diff --git a/src/gui/plugins/environment_visualization/EnvironmentVisualization.cc b/src/gui/plugins/environment_visualization/EnvironmentVisualization.cc new file mode 100644 index 0000000000..3ed5f6f9ce --- /dev/null +++ b/src/gui/plugins/environment_visualization/EnvironmentVisualization.cc @@ -0,0 +1,313 @@ +/* + * 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 "EnvironmentVisualization.hh" + +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include +#include +#include +#include + +using namespace gz; +using namespace sim; + +namespace gz +{ +namespace sim +{ +inline namespace GZ_SIM_VERSION_NAMESPACE +{ +/// \brief Private data class for EnvironmentVisualization +class EnvironmentVisualizationPrivate +{ + public: EnvironmentVisualizationPrivate() + { + this->pcPub = + this->node.Advertise("/point_cloud"); + } + /// \brief To synchronize member access. + public: std::mutex mutex; + + /// \brief first load we need to scan for existing data sensor + public: bool first {true}; + + public: std::atomic resample{true}; + + ///////////////////////////////////////////////// + public: void CreatePointCloudTopics( + std::shared_ptr data) { + this->pubs.clear(); + this->sessions.clear(); + for (auto key : data->frame.Keys()) + { + this->pubs.emplace(key, node.Advertise(key)); + gz::msgs::Float_V msg; + this->floatFields.emplace(key, msg); + this->sessions.emplace(key, data->frame[key].CreateSession()); + } + } + + ///////////////////////////////////////////////// + public: void Step( + const UpdateInfo &_info, + std::shared_ptr &data, + const EntityComponentManager& _ecm, + double xSamples, double ySamples, double zSamples) + { + auto now = std::chrono::steady_clock::now(); + std::chrono::duration dt(now - this->lastTick); + + if (this->resample) + { + this->CreatePointCloudTopics(data); + this->ResizeCloud(data, _ecm, xSamples, ySamples, zSamples); + this->resample = false; + this->lastTick = now; + } + + for (auto &it : this->sessions) + { + auto res = + data->frame[it.first].StepTo(it.second, + std::chrono::duration(_info.simTime).count()); + if (res.has_value()) + { + it.second = res.value(); + } + } + + // Publish at 2 hz for now. In future make reconfigureable. + if (dt.count() > 0.5) + { + this->Visualize(data, xSamples, ySamples, zSamples); + this->Publish(); + lastTick = now; + } + } + + ///////////////////////////////////////////////// + public: void Visualize( + std::shared_ptr data, + double xSamples, double ySamples, double zSamples) { + + for (auto key : data->frame.Keys()) + { + const auto session = this->sessions[key]; + auto frame = data->frame[key]; + auto [lower_bound, upper_bound] = frame.Bounds(session); + auto step = upper_bound - lower_bound; + auto dx = step.X() / xSamples; + auto dy = step.Y() / ySamples; + auto dz = step.Z() / zSamples; + std::size_t idx = 0; + for (std::size_t x_steps = 0; x_steps < ceil(xSamples); x_steps++) + { + auto x = lower_bound.X() + x_steps * dx; + for (std::size_t y_steps = 0; y_steps < ceil(ySamples); y_steps++) + { + auto y = lower_bound.Y() + y_steps * dy; + for (std::size_t z_steps = 0; z_steps < ceil(zSamples); z_steps++) + { + auto z = lower_bound.Z() + z_steps * dz; + auto res = frame.LookUp(session, math::Vector3d(x, y, z)); + + if (res.has_value()) + { + this->floatFields[key].mutable_data()->Set(idx, + static_cast(res.value())); + } + else + { + this->floatFields[key].mutable_data()->Set(idx, std::nanf("")); + } + idx++; + } + } + } + } + } + + ///////////////////////////////////////////////// + public: void Publish() + { + pcPub.Publish(this->pcMsg); + for(auto &[key, pub] : this->pubs) + { + pub.Publish(this->floatFields[key]); + } + } + + ///////////////////////////////////////////////// + public: void ResizeCloud( + std::shared_ptr data, + const EntityComponentManager& _ecm, + unsigned int xSamples, unsigned int ySamples, unsigned int zSamples) + { + assert (pubs.size() > 0); + + // Assume all data have same point cloud. + gz::msgs::InitPointCloudPacked(pcMsg, "some_frame", true, + {{"xyz", gz::msgs::PointCloudPacked::Field::FLOAT32}}); + auto numberOfPoints = xSamples * ySamples * zSamples; + std::size_t dataSize{ + static_cast(numberOfPoints * pcMsg.point_step())}; + pcMsg.mutable_data()->resize(dataSize); + pcMsg.set_height(1); + pcMsg.set_width(numberOfPoints); + + auto session = this->sessions[this->pubs.begin()->first]; + auto frame = data->frame[this->pubs.begin()->first]; + auto [lower_bound, upper_bound] = + frame.Bounds(session); + + auto step = upper_bound - lower_bound; + auto dx = step.X() / xSamples; + auto dy = step.Y() / ySamples; + auto dz = step.Z() / zSamples; + + // Populate point cloud + gz::msgs::PointCloudPackedIterator xIter(pcMsg, "x"); + gz::msgs::PointCloudPackedIterator yIter(pcMsg, "y"); + gz::msgs::PointCloudPackedIterator zIter(pcMsg, "z"); + + for (std::size_t x_steps = 0; x_steps < xSamples; x_steps++) + { + auto x = lower_bound.X() + x_steps * dx; + for (std::size_t y_steps = 0; y_steps < ySamples; y_steps++) + { + auto y = lower_bound.Y() + y_steps * dy; + for (std::size_t z_steps = 0; z_steps < zSamples; z_steps++) + { + auto z = lower_bound.Z() + z_steps * dz; + auto coords = getGridFieldCoordinates( + _ecm, math::Vector3d{x, y, z}, + data); + + if (!coords.has_value()) + { + continue; + } + + auto pos = coords.value(); + *xIter = pos.X(); + *yIter = pos.Y(); + *zIter = pos.Z(); + ++xIter; + ++yIter; + ++zIter; + } + } + } + for (auto key : data->frame.Keys()) + { + this->floatFields[key].mutable_data()->Resize( + numberOfPoints, std::nanf("")); + } + } + + public: transport::Node::Publisher pcPub; + public: std::unordered_map pubs; + public: std::unordered_map floatFields; + public: transport::Node node; + public: gz::msgs::PointCloudPacked pcMsg; + public: std::unordered_map> sessions; + public: std::chrono::time_point lastTick; +}; +} +} +} + +///////////////////////////////////////////////// +EnvironmentVisualization::EnvironmentVisualization() + : GuiSystem(), dataPtr(new EnvironmentVisualizationPrivate) +{ + gui::App()->Engine()->rootContext()->setContextProperty( + "EnvironmentVisualization", this); +} + +///////////////////////////////////////////////// +EnvironmentVisualization::~EnvironmentVisualization() +{ +} + +///////////////////////////////////////////////// +void EnvironmentVisualization::LoadConfig(const tinyxml2::XMLElement *) +{ + if (this->title.empty()) + this->title = "Environment Visualization Resolution"; + + gui::App()->findChild()->installEventFilter(this); +} + +///////////////////////////////////////////////// +void EnvironmentVisualization::Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) +{ + _ecm.EachNew( + [this]( + const Entity &/*_entity*/, + const components::Environment* /*environment*/ + ) { + this->dataPtr->resample = true; + return true; + } + ); + + auto environData = + _ecm.Component( + worldEntity(_ecm)); + + if (environData == nullptr) + { + return; + } + + this->dataPtr->Step( + _info, environData->Data(), _ecm, + this->xSamples, this->ySamples, this->zSamples + ); +} + +///////////////////////////////////////////////// +void EnvironmentVisualization::ResamplePointcloud() +{ + this->dataPtr->resample = true; +} + + +// Register this plugin +GZ_ADD_PLUGIN(gz::sim::EnvironmentVisualization, gz::gui::Plugin) diff --git a/src/gui/plugins/environment_visualization/EnvironmentVisualization.hh b/src/gui/plugins/environment_visualization/EnvironmentVisualization.hh new file mode 100644 index 0000000000..91cd420eb9 --- /dev/null +++ b/src/gui/plugins/environment_visualization/EnvironmentVisualization.hh @@ -0,0 +1,80 @@ +/* + * 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_GUI_ENVIRONMENTVISUALIZATION_HH_ +#define GZ_SIM_GUI_ENVIRONMENTVISUALIZATION_HH_ + +#include + +#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 EnvironmentVisualizationPrivate; + + /// \class EnvironmentVisualization EnvironmentVisualization.hh + /// gz/sim/systems/EnvironmentVisualization.hh + /// \brief A GUI plugin for a user to load an Environment + /// component into the ECM on a live simulation. + class EnvironmentVisualization : public gz::sim::GuiSystem + { + Q_OBJECT + + /// \brief Samples along x axis + Q_PROPERTY(unsigned int xSamples MEMBER xSamples) + + /// \brief Samples along y axis + Q_PROPERTY(unsigned int ySamples MEMBER ySamples) + + /// \brief Samples along z axis + Q_PROPERTY(unsigned int zSamples MEMBER zSamples) + + /// \brief Constructor + public: EnvironmentVisualization(); + + /// \brief Destructor + public: ~EnvironmentVisualization() override; + + // Documentation inherited + public: void LoadConfig(const tinyxml2::XMLElement *_pluginElem) override; + + // Documentation inherited + public: void Update(const UpdateInfo &, + EntityComponentManager &_ecm) override; + + public: Q_INVOKABLE void ResamplePointcloud(); + + /// \internal + /// \brief Pointer to private data + private: std::unique_ptr dataPtr; + + public: unsigned int xSamples{10}; + + public: unsigned int ySamples{10}; + + public: unsigned int zSamples{10}; + }; +} +} +} +#endif diff --git a/src/gui/plugins/environment_visualization/EnvironmentVisualization.qml b/src/gui/plugins/environment_visualization/EnvironmentVisualization.qml new file mode 100644 index 0000000000..2fbdae8030 --- /dev/null +++ b/src/gui/plugins/environment_visualization/EnvironmentVisualization.qml @@ -0,0 +1,111 @@ +/* + * 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. + * +*/ +import QtQuick 2.9 +import QtQuick.Controls 2.1 +import QtQuick.Dialogs 1.0 +import QtQuick.Controls.Material 2.1 +import QtQuick.Layouts 1.3 +import "qrc:/qml" + + +GridLayout { + columns: 8 + columnSpacing: 10 + Layout.minimumWidth: 350 + Layout.minimumHeight: 400 + anchors.fill: parent + anchors.leftMargin: 10 + anchors.rightMargin: 10 + + Label { + Layout.row: 0 + Layout.columnSpan: 8 + horizontalAlignment: Text.AlignCenter + id: instructionLabel + color: "dimgrey" + text: qsTr("For the actual pointcloud please open the point_cloud panel") + } + + Label { + Layout.row: 1 + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: dimensionLabelX + color: "dimgrey" + text: qsTr("X Samples") + } + + Slider { + Layout.row: 1 + Layout.column: 2 + Layout.columnSpan: 6 + id: stepSliderX + from: 5 + value: 10 + to: 50 + onMoved: function() { + EnvironmentVisualization.xSamples = value; + EnvironmentVisualization.ResamplePointcloud(); + } + } + + Label { + Layout.row: 2 + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: dimensionLabelY + color: "dimgrey" + text: qsTr("Y Samples") + } + + Slider { + Layout.row: 2 + Layout.column: 2 + Layout.columnSpan: 6 + id: stepSliderY + from: 5 + value: 10 + to: 50 + onMoved: function() { + EnvironmentVisualization.ySamples = value; + EnvironmentVisualization.ResamplePointcloud(); + } + } + + Label { + Layout.row: 3 + Layout.columnSpan: 2 + horizontalAlignment: Text.AlignRight + id: dimensionLabelZ + color: "dimgrey" + text: qsTr("Z Samples") + } + + Slider { + Layout.row: 3 + Layout.column: 2 + Layout.columnSpan: 6 + id: stepSliderZ + from: 5 + value: 10 + to: 50 + onMoved: function() { + EnvironmentVisualization.zSamples = value; + EnvironmentVisualization.ResamplePointcloud(); + } + } +} diff --git a/src/gui/plugins/environment_visualization/EnvironmentVisualization.qrc b/src/gui/plugins/environment_visualization/EnvironmentVisualization.qrc new file mode 100644 index 0000000000..db66d95327 --- /dev/null +++ b/src/gui/plugins/environment_visualization/EnvironmentVisualization.qrc @@ -0,0 +1,5 @@ + + + EnvironmentVisualization.qml + + diff --git a/src/systems/CMakeLists.txt b/src/systems/CMakeLists.txt index 352a00c1fa..84ad0018ae 100644 --- a/src/systems/CMakeLists.txt +++ b/src/systems/CMakeLists.txt @@ -115,6 +115,7 @@ if (NOT WIN32) add_subdirectory(elevator) endif() add_subdirectory(environment_preload) +add_subdirectory(environmental_sensor_system) add_subdirectory(follow_actor) add_subdirectory(force_torque) add_subdirectory(hydrodynamics) diff --git a/src/systems/environment_preload/EnvironmentPreload.cc b/src/systems/environment_preload/EnvironmentPreload.cc index 92926d0746..fe5b57f940 100644 --- a/src/systems/environment_preload/EnvironmentPreload.cc +++ b/src/systems/environment_preload/EnvironmentPreload.cc @@ -93,14 +93,20 @@ void EnvironmentPreload::PreUpdate( return; } + components::EnvironmentalData::ReferenceUnits unit{ + components::EnvironmentalData::ReferenceUnits::RADIANS}; std::string timeColumnName{"t"}; + bool ignoreTime = false; std::array spatialColumnNames{"x", "y", "z"}; auto spatialReference = math::SphericalCoordinates::GLOBAL; - sdf::ElementConstPtr elem = this->dataPtr->sdf->FindElement("dimensions"); if (elem) { + if (elem->HasElement("ignore_time")) + { + ignoreTime = elem->Get("ignore_time"); + } if (elem->HasElement("time")) { timeColumnName = elem->Get("time"); @@ -119,6 +125,18 @@ void EnvironmentPreload::PreUpdate( else if (referenceName == "spherical") { spatialReference = math::SphericalCoordinates::SPHERICAL; + if (elem->HasAttribute("units")) + { + std::string unitName = elem->Get("units"); + if (unitName == "degrees") + { + unit = components::EnvironmentalData::ReferenceUnits::DEGREES; + } + else if (unitName != "radians") + { + ignerr << "Unrecognized unit " << unitName << "\n"; + } + } } else if (referenceName == "ecef") { @@ -144,13 +162,14 @@ void EnvironmentPreload::PreUpdate( try { + gzmsg << "Loading Environment Data\n"; using ComponentDataT = components::EnvironmentalData; auto data = ComponentDataT::MakeShared( common::IO::ReadFrom( common::CSVIStreamIterator(dataFile), common::CSVIStreamIterator(), timeColumnName, spatialColumnNames), - spatialReference); + spatialReference, unit, ignoreTime); using ComponentT = components::Environment; auto component = ComponentT{std::move(data)}; diff --git a/src/systems/environmental_sensor_system/CMakeLists.txt b/src/systems/environmental_sensor_system/CMakeLists.txt new file mode 100644 index 0000000000..89f30b71dd --- /dev/null +++ b/src/systems/environmental_sensor_system/CMakeLists.txt @@ -0,0 +1,8 @@ +gz_add_system(environmental-sensor + SOURCES + EnvironmentalSensorSystem.cc + PUBLIC_LINK_LIBS + gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER} + gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} + gz-math${GZ_MATH_VER}::eigen3 +) diff --git a/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.cc b/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.cc new file mode 100644 index 0000000000..85268b7fce --- /dev/null +++ b/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.cc @@ -0,0 +1,359 @@ +/* + * 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 "EnvironmentalSensorSystem.hh" + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +using namespace gz; +using namespace gz::sim; + +/// Sensor prefix to be used. All envionment_sensors are to be prefixed by +/// "environment_sensor/" in their gz:type field. +constexpr char SENSOR_TYPE_PREFIX[] = "environmental_sensor/"; + +//////////////////////////////////////////////////////////////// +/// \brief Envirtonment Sensor used for looking up environment values in our +/// CSV file. +class EnvironmentalSensor : public gz::sensors::Sensor +{ + /// \brief Node for communication + private: gz::transport::Node node; + + /// \brief Publishes sensor data + private: gz::transport::Node::Publisher pub; + + //////////////////////////////////////////////////////////////// + /// Documentation inherited + public: virtual bool Load(const sdf::Sensor &_sdf) override + { + auto type = gz::sensors::customType(_sdf); + if (!common::StartsWith(type, SENSOR_TYPE_PREFIX)) + { + gzerr << "Trying to load [" << SENSOR_TYPE_PREFIX + << "] sensor, but got type [" + << type << "] instead." << std::endl; + return false; + } + + // Load common sensor params + gz::sensors::Sensor::Load(_sdf); + + this->pub = this->node.Advertise(this->Topic()); + + // If "environment_variable" is defined then remap + // sensor from existing data. + if (_sdf.Element() != nullptr && + _sdf.Element()->HasElement("environment_variable")) + { + this->fieldName = + _sdf.Element()->Get("environment_variable"); + } + else + { + this->fieldName = type.substr(strlen(SENSOR_TYPE_PREFIX)); + } + + // Allow setting custom frame_ids + if (_sdf.Element() != nullptr && + _sdf.Element()->HasElement("frame_id")) + { + this->frameId = _sdf.Element()->Get("frame_id"); + } + + gzdbg << "Loaded environmental sensor for " << this->fieldName + << " publishing on " << this->Topic() << std::endl; + + return true; + } + + //////////////////////////////////////////////////////////////// + /// \brief Update the sensor and generate data + /// \param[in] _now The current time + /// \return True if the update was successful + public: virtual bool Update( + const std::chrono::steady_clock::duration &_now) override + { + if (!this->ready) return false; + + if (!this->session.has_value()) return false; + + // Step time if its not static + if (!this->gridField->staticTime) + this->session = this->gridField->frame[this->fieldName].StepTo( + this->session.value(), std::chrono::duration(_now).count()); + + if (!this->session.has_value()) return false; + + gz::msgs::Double msg; + *msg.mutable_header()->mutable_stamp() = gz::msgs::Convert(_now); + auto frame = msg.mutable_header()->add_data(); + frame->set_key("frame_id"); + frame->add_value((this->frameId == "") ? this->Name() : this->frameId); + auto data = this->gridField->frame[this->fieldName].LookUp( + this->session.value(), this->position); + if (!data.has_value()) + { + gzwarn << "Failed to acquire value perhaps out of field?\n"; + return false; + } + msg.set_data(data.value()); + // TODO(anyone) Add sensor noise. + this->pub.Publish(msg); + return true; + } + + //////////////////////////////////////////////////////////////// + /// \brief Attempts to set a data table. + /// \param[in] _data - The data table + /// \param[in] _curr_time - The current time. + public: void SetDataTable( + const components::Environment* _data, + const std::chrono::steady_clock::duration &_curr_time) + { + gzdbg << "Setting new data table\n"; + auto data = _data->Data(); + if(!data->frame.Has(this->fieldName)) + { + gzwarn << "Environmental sensor could not find field " + << this->fieldName << "\n"; + this->ready = false; + return; + } + + this->gridField = data; + this->session = this->gridField->frame[this->fieldName].CreateSession(); + if (!this->gridField->staticTime) + { + this->session = this->gridField->frame[this->fieldName].StepTo( + *this->session, + std::chrono::duration(_curr_time).count()); + } + this->ready = true; + + if(!this->session.has_value()) + { + gzerr << "Exceeded time stamp." << std::endl; + } + } + + //////////////////////////////////////////////////////////////// + /// \brief Updates the position of the sensor at each time step + /// to track a given entity, + /// \param[in] - The sensor entity. + /// \param[in] - The ECM to use for tracking. + /// \returns True if successful, false if not. + public: bool UpdatePosition( + const Entity _entity, + const EntityComponentManager& _ecm) + { + if (!this->ready) return false; + + const auto worldPosition = worldPose(_entity, _ecm).Pos(); + auto lookupCoords = + getGridFieldCoordinates(_ecm, worldPosition, this->gridField); + + if (!lookupCoords.has_value()) + { + return false; + } + + this->position = lookupCoords.value(); + return true; + } + + //////////////////////////////////////////////////////////////// + public: std::string Field() const + { + return fieldName; + } + + private: bool ready {false}; + private: math::Vector3d position; + private: std::string fieldName; + private: std::string frameId; + private: std::optional> session; + private: std::shared_ptr + gridField; +}; + +class gz::sim::EnvironmentalSensorSystemPrivate { + public: std::unordered_map> + entitySensorMap; + + public: std::unordered_set fields; + + public: void RemoveSensorEntities( + const gz::sim::EntityComponentManager &_ecm) + { + _ecm.EachRemoved( + [&](const Entity &_entity, + const components::CustomSensor *)->bool + { + if (this->entitySensorMap.erase(_entity) == 0) + { + gzerr << "Internal error, missing environment sensor for entity [" + << _entity << "]" << std::endl; + } + return true; + }); + } + + public: Entity worldEntity; + + public: bool useSphericalCoords{false}; +}; + + +//////////////////////////////////////////////////////////////// +EnvironmentalSensorSystem::EnvironmentalSensorSystem () : + dataPtr(std::make_unique()) +{ + +} + +//////////////////////////////////////////////////////////////// +void EnvironmentalSensorSystem::Configure( + const gz::sim::Entity &_entity, + const std::shared_ptr &/*_sdf*/, + gz::sim::EntityComponentManager &/*_ecm*/, + gz::sim::EventManager &/*_eventMgr*/) +{ + dataPtr->worldEntity = _entity; +} + +//////////////////////////////////////////////////////////////// +void EnvironmentalSensorSystem::PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) +{ + _ecm.EachNew( + [&](const Entity &_entity, + const components::CustomSensor *_custom, + const components::ParentEntity *_parent)->bool + { + // Get sensor's scoped name without the world + auto sensorScopedName = + removeParentScope(scopedName(_entity, _ecm, "::", false), "::"); + sdf::Sensor data = _custom->Data(); + data.SetName(sensorScopedName); + + auto type = gz::sensors::customType(data); + if (!common::StartsWith(type, SENSOR_TYPE_PREFIX)) + { + return true; + } + + // Default to scoped name as topic + if (data.Topic().empty()) + { + std::string topic = scopedName(_entity, _ecm) + "/" + type; + data.SetTopic(topic); + } + + gz::sensors::SensorFactory sensorFactory; + auto sensor = sensorFactory.CreateSensor(data); + + // Set sensor parent + auto parentName = _ecm.Component( + _parent->Data())->Data(); + sensor->SetParent(parentName); + + // Set topic on Gazebo + _ecm.CreateComponent(_entity, + components::SensorTopic(sensor->Topic())); + + // Get current EnvironmentalData component + auto environData = + _ecm.Component( + worldEntity(_ecm)); + + if (environData != nullptr) + { + sensor->SetDataTable(environData, _info.simTime); + } + else + { + gzerr << "No sensor data loaded\n"; + } + + // Keep track of this sensor + this->dataPtr->entitySensorMap.insert(std::make_pair(_entity, + std::move(sensor))); + return true; + }); +} + +//////////////////////////////////////////////////////////////// +void EnvironmentalSensorSystem::PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) +{ + _ecm.EachNew([&](const Entity &/*_entity*/, + const components::Environment *_environmental_data)->bool + { + for (auto &[entity, sensor] : this->dataPtr->entitySensorMap) + { + sensor->SetDataTable(_environmental_data, _info.simTime); + } + return true; + }); + // Only update and publish if not paused. + if (!_info.paused) + { + + for (auto &[entity, sensor] : this->dataPtr->entitySensorMap) + { + sensor->UpdatePosition(entity, _ecm); + sensor->Update(_info.simTime); + } + } + + this->dataPtr->RemoveSensorEntities(_ecm); +} + +GZ_ADD_PLUGIN( + EnvironmentalSensorSystem, System, + EnvironmentalSensorSystem::ISystemConfigure, + EnvironmentalSensorSystem::ISystemPreUpdate, + EnvironmentalSensorSystem::ISystemPostUpdate +) + +GZ_ADD_PLUGIN_ALIAS( + EnvironmentalSensorSystem, + "gz::sim::systems::EnvironmentalSystem") diff --git a/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.hh b/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.hh new file mode 100644 index 0000000000..ecb7ad9845 --- /dev/null +++ b/src/systems/environmental_sensor_system/EnvironmentalSensorSystem.hh @@ -0,0 +1,68 @@ +/* + * 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_ENVIRONMENTAL_SYSTEM_HH_ +#define GZ_ENVIRONMENTAL_SYSTEM_HH_ + +#include +#include +#include + +#include + +namespace gz +{ +namespace sim +{ +class EnvironmentalSensorSystemPrivate; +/// \brief Sensor for reading environmental data loaded from outside world. +/// To use, add this system to the world file, then instantiate sensors of +/// custom type with gz:type="environmental_sensor/{field_name}", where +/// field_name refers to the type of data you would like to output. +/// Alternatively, if you would like to specify a custom field name you may do +/// so using the tag. +class EnvironmentalSensorSystem: + public gz::sim::System, + public gz::sim::ISystemConfigure, + public gz::sim::ISystemPreUpdate, + public gz::sim::ISystemPostUpdate +{ + public: EnvironmentalSensorSystem(); + /// Documentation inherited + public: void Configure( + const gz::sim::Entity &_entity, + const std::shared_ptr &_sdf, + gz::sim::EntityComponentManager &_ecm, + gz::sim::EventManager &/*_eventMgr*/) override; + + // Documentation inherited. + // During PreUpdate, check for new sensors that were inserted + // into simulation and create more components as needed. + public: void PreUpdate(const gz::sim::UpdateInfo &_info, + gz::sim::EntityComponentManager &_ecm) final; + + // Documentation inherited. + // During PostUpdate, update the known sensors and publish their data. + // Also remove sensors that have been deleted. + public: void PostUpdate(const gz::sim::UpdateInfo &_info, + const gz::sim::EntityComponentManager &_ecm) final; + + private: std::unique_ptr dataPtr; +}; +} +} + +#endif diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index 1ee62ed9b7..0e15ef4f04 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -20,6 +20,7 @@ set(tests entity_erase.cc entity_system.cc environment_preload_system.cc + environmental_sensor_system.cc events.cc examples_build.cc follow_actor_system.cc diff --git a/test/integration/environment_preload_system.cc b/test/integration/environment_preload_system.cc index bc4ee515d2..61a9fbffcd 100644 --- a/test/integration/environment_preload_system.cc +++ b/test/integration/environment_preload_system.cc @@ -18,12 +18,12 @@ #include #include +#include #include "gz/sim/components/Environment.hh" #include "gz/sim/Server.hh" #include "gz/sim/TestFixture.hh" - -#include +#include "gz/sim/Util.hh" #include "test_config.hh" #include "../helpers/EnvTestFixture.hh" @@ -73,12 +73,70 @@ TEST_F(EnvironmentPreloadTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(CanPreload)) { const math::Vector3d position{36.80079505, -121.789472517, 0.8}; auto humidity = - humidityData.LookUp(humiditySession.value(), position); + humidityData.LookUp(humiditySession.value(), + position); EXPECT_NEAR(89.5, humidity.value_or(0.), 1e-6); dataLoaded = true; } EXPECT_EQ(data->reference, math::SphericalCoordinates::SPHERICAL); + return true; + }); + }); + + server.AddSystem(testSystem.systemPtr); + + // Run server + server.RunOnce(); + + EXPECT_TRUE(dataLoaded); +} + +///////////////////////////////////////////////// +TEST_F(EnvironmentPreloadTest, + GZ_UTILS_TEST_DISABLED_ON_WIN32(CorrectSphericalTransform)) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = common::joinPaths( + std::string(PROJECT_BINARY_PATH), "test", + "worlds", "environmental_data.sdf"); + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + bool dataLoaded{false}; + + // Create a system that looks for environmental data components + test::Relay testSystem; + testSystem.OnPostUpdate( + [&](const sim::UpdateInfo &, + const sim::EntityComponentManager &_ecm) + { + _ecm.EachNew( + [&](const gz::sim::Entity &, + const components::Environment *_component) -> bool + { + auto data = _component->Data(); + EXPECT_TRUE(data->frame.Has("humidity")); + const auto &humidityData = data->frame["humidity"]; + auto humiditySession = humidityData.StepTo( + humidityData.CreateSession(), 1658923062.5); + EXPECT_TRUE(humiditySession.has_value()); + if (humiditySession.has_value()) + { + const math::Vector3d position{0, 0, 0.8}; + auto transformedCoordinates = + getGridFieldCoordinates(_ecm, position, data); + auto humidity = + humidityData.LookUp(humiditySession.value(), + transformedCoordinates.value()); + EXPECT_NEAR(89.5, humidity.value_or(0.), 1e-6); + dataLoaded = true; + } + EXPECT_EQ(data->reference, math::SphericalCoordinates::SPHERICAL); return true; }); }); diff --git a/test/integration/environmental_sensor_system.cc b/test/integration/environmental_sensor_system.cc new file mode 100644 index 0000000000..71e4fda198 --- /dev/null +++ b/test/integration/environmental_sensor_system.cc @@ -0,0 +1,84 @@ +/* + * 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 + +#include +#include + +#include "gz/sim/components/Environment.hh" +#include "gz/sim/Server.hh" +#include "gz/sim/TestFixture.hh" + +#include + +#include "gz/transport/Node.hh" +#include "test_config.hh" +#include "../helpers/EnvTestFixture.hh" +#include "../helpers/Relay.hh" + +using namespace gz; +using namespace sim; + +/// \brief Test EnvironmentPreload system +class EnvironmentSensorTest : public InternalFixture<::testing::Test> +{ + ///////////////////////////////////////////////// + public: EnvironmentSensorTest() + { + node.Subscribe("/world/environmental_sensor_test/" + "model/model_with_sensor/link/link/sensor/custom_sensor/" + "environmental_sensor/humidity", + &EnvironmentSensorTest::OnReceiveMsg, + this); + } + + ///////////////////////////////////////////////// + public: void OnReceiveMsg(const gz::msgs::Double& msg) + { + // Data set is such that sensor value == time for the first second. + double nsec = msg.header().stamp().nsec(); + double sec = static_cast(msg.header().stamp().sec()); + auto time = nsec * 1e-9 + sec; + EXPECT_NEAR(time, msg.data(), 1e-9); + this->receivedData = true; + } + + ///////////////////////////////////////////////// + public: std::atomic receivedData{false}; + + ///////////////////////////////////////////////// + public: transport::Node node; + +}; + +///////////////////////////////////////////////// +TEST_F(EnvironmentSensorTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(CanPreload)) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = common::joinPaths( + std::string(PROJECT_BINARY_PATH), "test", + "worlds", "environmental_sensor.sdf"); + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + // Run server + server.Run(true, 1000, false); + EXPECT_TRUE(this->receivedData.load()); +} diff --git a/test/worlds/CMakeLists.txt b/test/worlds/CMakeLists.txt index cddef0af3b..dbc095a2c7 100644 --- a/test/worlds/CMakeLists.txt +++ b/test/worlds/CMakeLists.txt @@ -3,3 +3,5 @@ configure_file (mesh.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/mesh.sdf) configure_file (thermal.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/thermal.sdf) configure_file (heightmap.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/heightmap.sdf) configure_file (environmental_data.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/environmental_data.sdf) + +configure_file (environmental_sensor.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/environmental_sensor.sdf) diff --git a/test/worlds/environmental_data.sdf.in b/test/worlds/environmental_data.sdf.in index ac3ec2a73d..47cc7e2cb2 100644 --- a/test/worlds/environmental_data.sdf.in +++ b/test/worlds/environmental_data.sdf.in @@ -28,13 +28,24 @@ -0.5 0.1 -0.9 + + + EARTH_WGS84 + ENU + 36.80079505 + -121.789472517 + 0 + 0 + + + @CMAKE_SOURCE_DIR@/test/worlds/environmental_data.csv - + latitude longitude altitude diff --git a/test/worlds/environmental_sensor.csv b/test/worlds/environmental_sensor.csv new file mode 100644 index 0000000000..3ec2c0a571 --- /dev/null +++ b/test/worlds/environmental_sensor.csv @@ -0,0 +1,17 @@ +timestamp,humidity,x,y,z +0,0,-1,-1,-1 +0,0,-1,-1, 1 +0,0,-1, 1,-1 +0,0,-1, 1, 1 +0,0, 1,-1,-1 +0,0, 1,-1, 1 +0,0, 1, 1,-1 +0,0, 1, 1, 1 +1,1,-1,-1,-1 +1,1,-1,-1, 1 +1,1,-1, 1,-1 +1,1,-1, 1, 1 +1,1, 1,-1,-1 +1,1, 1,-1, 1 +1,1, 1, 1,-1 +1,1, 1, 1, 1 diff --git a/test/worlds/environmental_sensor.sdf.in b/test/worlds/environmental_sensor.sdf.in new file mode 100644 index 0000000000..46b3673ea7 --- /dev/null +++ b/test/worlds/environmental_sensor.sdf.in @@ -0,0 +1,112 @@ + + + + + + + + + + + + + + + @CMAKE_SOURCE_DIR@/test/worlds/environmental_sensor.csv + + + + x + y + z + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0.05 0 0 0 + + + 0.1 + + 0.000166667 + 0.000166667 + 0.000166667 + + + + + + 0.1 0.1 0.1 + + + + + + + 0.1 0.1 0.1 + + + + + + 1 + 30 + true + + + + + + From 3d94c0ba2afbe0480a1dfccd9d9fdf94aa91b761 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Tue, 22 Nov 2022 01:03:56 -0800 Subject: [PATCH 5/6] Remove fixed width from world control (#1805) Signed-off-by: Nate Koenig --- src/gui/gui.config | 1 - 1 file changed, 1 deletion(-) diff --git a/src/gui/gui.config b/src/gui/gui.config index 62f930cc71..4ea3b1be53 100644 --- a/src/gui/gui.config +++ b/src/gui/gui.config @@ -126,7 +126,6 @@ false false 72 - 121 1 floating From e5c3ee9a69d5781bddfc5379836c26b2f35b98c0 Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Wed, 23 Nov 2022 23:46:51 +0800 Subject: [PATCH 6/6] Fixes buoyancy flakiness when spawning entities (#1808) * Fixes buoyancy flakiness when spawning entities For reference see https://github.com/osrf/lrauv/pull/272#issuecomment-1323426611 Essentially, if we spawn an entity using the `UserCommand` system, it will create the entity during the `PreUpdate` phase. However, the `Buoyancy` system only checks for new entities during the `PreUpdate` phase (It does this to precompute volume so it does not need to be computed on every run). This means the buoyancy system may or may not catch the newly created entities. Signed-off-by: Arjo Chakravarty --- src/systems/buoyancy/Buoyancy.cc | 333 +++++++++++++++++++------------ src/systems/buoyancy/Buoyancy.hh | 12 +- 2 files changed, 209 insertions(+), 136 deletions(-) diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index 55f44bfded..a018c1bf36 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -19,6 +19,7 @@ #include #include #include +#include #include #include #include @@ -88,6 +89,23 @@ class gz::sim::systems::BuoyancyPrivate void GradedFluidDensity( const math::Pose3d &_pose, const T &_shape, const math::Vector3d &_gravity); + /// \brief Check for new links to apply buoyancy forces to. Calculates the + /// volume and center of volume for every new link and stages them to be + /// commited when `CommitNewEntities` is called. + /// \param[in] _ecm The Entity Component Manager. + public: void CheckForNewEntities(const EntityComponentManager &_ecm); + + /// \brief Commits the new entities to the ECM. + /// \param[in] _ecm The Entity Component Manager. + public: void CommitNewEntities(EntityComponentManager &_ecm); + + /// \brief Check if an entity is enabled or not. + /// \param[in] _entity Target entity + /// \param[in] _ecm Entity component manager + /// \return True if buoyancy should be applied. + public: bool IsEnabled(Entity _entity, + const EntityComponentManager &_ecm) const; + /// \brief Model interface public: Entity world{kNullEntity}; @@ -136,6 +154,12 @@ class gz::sim::systems::BuoyancyPrivate /// \brief Scoped names of entities that buoyancy should apply to. If empty, /// all links will receive buoyancy. public: std::unordered_set enabled; + + /// \brief Center of volumes to be added on the next Pre-update + public: std::unordered_map centerOfVolumes; + + /// \brief Volumes to be added on the next. + public: std::unordered_map volumes; }; ////////////////////////////////////////////////// @@ -245,6 +269,165 @@ std::pair BuoyancyPrivate::ResolveForces( return {force, torque}; } +////////////////////////////////////////////////// +void BuoyancyPrivate::CheckForNewEntities(const EntityComponentManager &_ecm) +{ + // Compute the volume and center of volume for each new link + _ecm.EachNew( + [&](const Entity &_entity, + const components::Link *, + const components::Inertial *) -> bool + { + // Skip if the entity already has a volume and center of volume + if (_ecm.EntityHasComponentType(_entity, + components::CenterOfVolume().TypeId()) && + _ecm.EntityHasComponentType(_entity, + components::Volume().TypeId())) + { + return true; + } + + if (!this->IsEnabled(_entity, _ecm)) + { + return true; + } + + Link link(_entity); + + std::vector collisions = _ecm.ChildrenByComponents( + _entity, components::Collision()); + + double volumeSum = 0; + gz::math::Vector3d weightedPosInLinkSum = + gz::math::Vector3d::Zero; + + // Compute the volume of the link by iterating over all the collision + // elements and storing each geometry's volume. + for (const Entity &collision : collisions) + { + double volume = 0; + const components::CollisionElement *coll = + _ecm.Component(collision); + + if (!coll) + { + gzerr << "Invalid collision pointer. This shouldn't happen\n"; + continue; + } + + switch (coll->Data().Geom()->Type()) + { + case sdf::GeometryType::BOX: + volume = coll->Data().Geom()->BoxShape()->Shape().Volume(); + break; + case sdf::GeometryType::SPHERE: + volume = coll->Data().Geom()->SphereShape()->Shape().Volume(); + break; + case sdf::GeometryType::CYLINDER: + volume = coll->Data().Geom()->CylinderShape()->Shape().Volume(); + break; + case sdf::GeometryType::PLANE: + // Ignore plane shapes. They have no volume and are not expected + // to be buoyant. + break; + case sdf::GeometryType::MESH: + { + std::string file = asFullPath( + coll->Data().Geom()->MeshShape()->Uri(), + coll->Data().Geom()->MeshShape()->FilePath()); + if (common::MeshManager::Instance()->IsValidFilename(file)) + { + const common::Mesh *mesh = + common::MeshManager::Instance()->Load(file); + if (mesh) + volume = mesh->Volume(); + else + gzerr << "Unable to load mesh[" << file << "]\n"; + } + else + { + gzerr << "Invalid mesh filename[" << file << "]\n"; + } + break; + } + default: + gzerr << "Unsupported collision geometry[" + << static_cast(coll->Data().Geom()->Type()) << "]\n"; + break; + } + + volumeSum += volume; + auto poseInLink = _ecm.Component(collision)->Data(); + weightedPosInLinkSum += volume * poseInLink.Pos(); + } + + if (volumeSum > 0) + { + // Stage calculation results for future commit. We do this because + // during PostUpdate the ECM is const, so we can't modify it, + this->centerOfVolumes[_entity] = weightedPosInLinkSum / volumeSum; + this->volumes[_entity] = volumeSum; + } + + return true; + }); +} + +////////////////////////////////////////////////// +void BuoyancyPrivate::CommitNewEntities(EntityComponentManager &_ecm) +{ + for (const auto [_entity, _cov] : this->centerOfVolumes) + { + if (_ecm.HasEntity(_entity)) + { + _ecm.CreateComponent(_entity, components::CenterOfVolume(_cov)); + } + } + + for (const auto [_entity, _vol] : this->volumes) + { + if (_ecm.HasEntity(_entity)) + { + _ecm.CreateComponent(_entity, components::Volume(_vol)); + } + } + + this->centerOfVolumes.clear(); + this->volumes.clear(); +} + +////////////////////////////////////////////////// +bool BuoyancyPrivate::IsEnabled(Entity _entity, + const EntityComponentManager &_ecm) const +{ + // If there's nothing enabled, all entities are enabled + if (this->enabled.empty()) + return true; + + auto entity = _entity; + while (entity != kNullEntity) + { + // Fully scoped name + auto name = scopedName(entity, _ecm, "::", false); + + // Remove world name + name = removeParentScope(name, "::"); + + if (this->enabled.find(name) != this->enabled.end()) + return true; + + // Check parent + auto parentComp = _ecm.Component(entity); + + if (nullptr == parentComp) + return false; + + entity = parentComp->Data(); + } + + return false; +} + ////////////////////////////////////////////////// Buoyancy::Buoyancy() : dataPtr(std::make_unique()) @@ -341,6 +524,12 @@ void Buoyancy::PreUpdate(const gz::sim::UpdateInfo &_info, gz::sim::EntityComponentManager &_ecm) { GZ_PROFILE("Buoyancy::PreUpdate"); + this->dataPtr->CheckForNewEntities(_ecm); + this->dataPtr->CommitNewEntities(_ecm); + // Only update if not paused. + if (_info.paused) + return; + const components::Gravity *gravity = _ecm.Component( this->dataPtr->world); if (!gravity) @@ -350,112 +539,6 @@ void Buoyancy::PreUpdate(const gz::sim::UpdateInfo &_info, return; } - // Compute the volume and center of volume for each new link - _ecm.EachNew( - [&](const Entity &_entity, - const components::Link *, - const components::Inertial *) -> bool - { - // Skip if the entity already has a volume and center of volume - if (_ecm.EntityHasComponentType(_entity, - components::CenterOfVolume().TypeId()) && - _ecm.EntityHasComponentType(_entity, - components::Volume().TypeId())) - { - return true; - } - - if (!this->IsEnabled(_entity, _ecm)) - { - return true; - } - - Link link(_entity); - - std::vector collisions = _ecm.ChildrenByComponents( - _entity, components::Collision()); - - double volumeSum = 0; - gz::math::Vector3d weightedPosInLinkSum = - gz::math::Vector3d::Zero; - - // Compute the volume of the link by iterating over all the collision - // elements and storing each geometry's volume. - for (const Entity &collision : collisions) - { - double volume = 0; - const components::CollisionElement *coll = - _ecm.Component(collision); - - if (!coll) - { - gzerr << "Invalid collision pointer. This shouldn't happen\n"; - continue; - } - - switch (coll->Data().Geom()->Type()) - { - case sdf::GeometryType::BOX: - volume = coll->Data().Geom()->BoxShape()->Shape().Volume(); - break; - case sdf::GeometryType::SPHERE: - volume = coll->Data().Geom()->SphereShape()->Shape().Volume(); - break; - case sdf::GeometryType::CYLINDER: - volume = coll->Data().Geom()->CylinderShape()->Shape().Volume(); - break; - case sdf::GeometryType::PLANE: - // Ignore plane shapes. They have no volume and are not expected - // to be buoyant. - break; - case sdf::GeometryType::MESH: - { - std::string file = asFullPath( - coll->Data().Geom()->MeshShape()->Uri(), - coll->Data().Geom()->MeshShape()->FilePath()); - if (common::MeshManager::Instance()->IsValidFilename(file)) - { - const common::Mesh *mesh = - common::MeshManager::Instance()->Load(file); - if (mesh) - volume = mesh->Volume(); - else - gzerr << "Unable to load mesh[" << file << "]\n"; - } - else - { - gzerr << "Invalid mesh filename[" << file << "]\n"; - } - break; - } - default: - gzerr << "Unsupported collision geometry[" - << static_cast(coll->Data().Geom()->Type()) << "]\n"; - break; - } - - volumeSum += volume; - auto poseInLink = _ecm.Component(collision)->Data(); - weightedPosInLinkSum += volume * poseInLink.Pos(); - } - - if (volumeSum > 0) - { - // Store the center of volume expressed in the link frame - _ecm.CreateComponent(_entity, components::CenterOfVolume( - weightedPosInLinkSum / volumeSum)); - - // Store the volume - _ecm.CreateComponent(_entity, components::Volume(volumeSum)); - } - - return true; - }); - - // Only update if not paused. - if (_info.paused) - return; - _ecm.Each( @@ -548,42 +631,26 @@ void Buoyancy::PreUpdate(const gz::sim::UpdateInfo &_info, }); } +////////////////////////////////////////////////// +void Buoyancy::PostUpdate( + const UpdateInfo &/*_info*/, + const EntityComponentManager &_ecm) +{ + this->dataPtr->CheckForNewEntities(_ecm); +} + ////////////////////////////////////////////////// bool Buoyancy::IsEnabled(Entity _entity, const EntityComponentManager &_ecm) const { - // If there's nothing enabled, all entities are enabled - if (this->dataPtr->enabled.empty()) - return true; - - auto entity = _entity; - while (entity != kNullEntity) - { - // Fully scoped name - auto name = scopedName(entity, _ecm, "::", false); - - // Remove world name - name = removeParentScope(name, "::"); - - if (this->dataPtr->enabled.find(name) != this->dataPtr->enabled.end()) - return true; - - // Check parent - auto parentComp = _ecm.Component(entity); - - if (nullptr == parentComp) - return false; - - entity = parentComp->Data(); - } - - return false; + return this->IsEnabled(_entity, _ecm); } GZ_ADD_PLUGIN(Buoyancy, gz::sim::System, Buoyancy::ISystemConfigure, - Buoyancy::ISystemPreUpdate) + Buoyancy::ISystemPreUpdate, + Buoyancy::ISystemPostUpdate) GZ_ADD_PLUGIN_ALIAS(Buoyancy, "gz::sim::systems::Buoyancy") diff --git a/src/systems/buoyancy/Buoyancy.hh b/src/systems/buoyancy/Buoyancy.hh index 858b1e7775..5eae0f0864 100644 --- a/src/systems/buoyancy/Buoyancy.hh +++ b/src/systems/buoyancy/Buoyancy.hh @@ -113,7 +113,8 @@ namespace systems class Buoyancy : public System, public ISystemConfigure, - public ISystemPreUpdate + public ISystemPreUpdate, + public ISystemPostUpdate { /// \brief Constructor public: Buoyancy(); @@ -129,8 +130,13 @@ namespace systems // Documentation inherited public: void PreUpdate( - const gz::sim::UpdateInfo &_info, - gz::sim::EntityComponentManager &_ecm) override; + const UpdateInfo &_info, + EntityComponentManager &_ecm) override; + + // Documentation inherited + public: void PostUpdate( + const UpdateInfo &_info, + const EntityComponentManager &_ecm) override; /// \brief Check if an entity is enabled or not. /// \param[in] _entity Target entity