From d4fc6974c2d5e9ffa90804a2ba0e0afe793fcc8f Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 10 Dec 2020 23:53:48 +0100 Subject: [PATCH 01/42] Add Light Usercommand and include Light parameters in the componentInspector Signed-off-by: ahcorde --- .../component_inspector/ComponentInspector.cc | 70 +- .../component_inspector/ComponentInspector.hh | 28 + .../ComponentInspector.qml | 13 + .../ComponentInspector.qrc | 1 + src/gui/plugins/component_inspector/Light.qml | 788 ++++++++++++++++++ src/rendering/RenderUtil.cc | 41 +- src/systems/user_commands/UserCommands.cc | 106 +++ 7 files changed, 1039 insertions(+), 8 deletions(-) create mode 100644 src/gui/plugins/component_inspector/Light.qml diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index de0cf8afee..f31e75d201 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -76,6 +76,9 @@ namespace ignition::gazebo /// \brief Name of the world public: std::string worldName; + /// \brief Entity name + public: std::string entityName; + /// \brief Entity type, such as 'world' or 'model'. public: QString type; @@ -112,6 +115,29 @@ void ignition::gazebo::setData(QStandardItem *_item, const math::Pose3d &_data) }), ComponentsModel::RoleNames().key("data")); } +////////////////////////////////////////////////// +template<> +void ignition::gazebo::setData(QStandardItem *_item, const sdf::Light &_data) +{ + _item->setData(QString("Light"), + ComponentsModel::RoleNames().key("dataType")); + _item->setData(QList({ + QVariant(_data.Specular().R()), + QVariant(_data.Specular().G()), + QVariant(_data.Specular().B()), + QVariant(_data.Specular().A()), + QVariant(_data.Diffuse().R()), + QVariant(_data.Diffuse().G()), + QVariant(_data.Diffuse().B()), + QVariant(_data.Diffuse().A()), + QVariant(_data.AttenuationRange()), + QVariant(_data.LinearAttenuationFactor()), + QVariant(_data.ConstantAttenuationFactor()), + QVariant(_data.QuadraticAttenuationFactor()), + QVariant(_data.CastShadows()) + }), ComponentsModel::RoleNames().key("data")); +} + ////////////////////////////////////////////////// template<> void ignition::gazebo::setData(QStandardItem *_item, @@ -370,12 +396,6 @@ void ComponentInspector::Update(const UpdateInfo &, continue; } - if (typeId == components::Light::typeId) - { - this->SetType("light"); - continue; - } - if (typeId == components::Actor::typeId) { this->SetType("actor"); @@ -499,6 +519,9 @@ void ComponentInspector::Update(const UpdateInfo &, if (this->dataPtr->entity == this->dataPtr->worldEntity) this->dataPtr->worldName = comp->Data(); + else + this->dataPtr->entityName = comp->Data(); + } else if (typeId == components::ParentEntity::typeId) { @@ -521,6 +544,12 @@ void ComponentInspector::Update(const UpdateInfo &, if (comp) setData(item, comp->Data()); } + else if (typeId == components::Light::typeId) + { + auto comp = _ecm.Component(this->dataPtr->entity); + if (comp) + setData(item, comp->Data()); + } else if (typeId == components::Pose::typeId) { auto comp = _ecm.Component(this->dataPtr->entity); @@ -728,6 +757,35 @@ void ComponentInspector::OnPose(double _x, double _y, double _z, double _roll, this->dataPtr->node.Request(poseCmdService, req, cb); } +///////////////////////////////////////////////// +void ComponentInspector::OnLight( + double _rSpecular, double _gSpecular, double _bSpecular, double _aSpecular, + double _rDiffuse, double _gDiffuse, double _bDiffuse, double _aDiffuse, + double _attRange, double _attLinear, double _attConstant, + double _attQuadratic, bool _castShadows) +{ + std::function cb = + [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) + { + if (!_result) + ignerr << "Error setting light configuration" << std::endl; + }; + + ignition::msgs::Light req; + req.set_name(this->dataPtr->entityName); + ignition::msgs::Set(req.mutable_diffuse(), + ignition::math::Color(_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse)); + ignition::msgs::Set(req.mutable_specular(), + ignition::math::Color(_rSpecular, _gSpecular, _bSpecular, _aSpecular)); + req.set_range(_attRange); + req.set_attenuation_linear(_attLinear); + req.set_attenuation_constant(_attConstant); + req.set_attenuation_quadratic(_attQuadratic); + req.set_cast_shadows(_castShadows); + auto lightConfigService = "/world/lights/config"; + this->dataPtr->node.Request(lightConfigService, req, cb); +} + ///////////////////////////////////////////////// bool ComponentInspector::NestedModel() const { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index 470c7b508f..dff17346d1 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -28,6 +28,8 @@ #include #include +#include + Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) namespace ignition @@ -69,6 +71,12 @@ namespace gazebo template<> void setData(QStandardItem *_item, const math::Pose3d &_data); + /// \brief Specialized to set ligth data. + /// \param[in] _item Item whose data will be set. + /// \param[in] _data Data to set. + template<> + void setData(QStandardItem *_item, const sdf::Light &_data); + /// \brief Specialized to set vector data. /// \param[in] _item Item whose data will be set. /// \param[in] _data Data to set. @@ -207,6 +215,26 @@ namespace gazebo public: Q_INVOKABLE void OnPose(double _x, double _y, double _z, double _roll, double _pitch, double _yaw); + /// \brief Callback in Qt thread when specular changes. + /// \param[in] _rSpecular specular red + /// \param[in] _gSpecular specular green + /// \param[in] _bSpecular specular blue + /// \param[in] _aSpecular specular alpha + /// \param[in] _rDiffuse Diffuse red + /// \param[in] _gDiffuse Diffuse green + /// \param[in] _bDiffuse Diffuse blue + /// \param[in] _aDiffuse Diffuse alpha + /// \param[in] _attRange Range attenuation + /// \param[in] _attLinear Linear attenuation + /// \param[in] _attConstant Constant attenuation + /// \param[in] _attQuadratic Quadratic attenuation + /// \param[in] _castShadows Cast Shadows attenuation + public: Q_INVOKABLE void OnLight( + double _rSpecular, double _gSpecular, double _bSpecular, double _aSpecular, + double _rDiffuse, double _gDiffuse, double _bDiffuse, double _aDiffuse, + double _attRange, double _attLinear, double _attConstant, double _attQuadratic, + bool _castShadows); + /// \brief Get whether the entity is a nested model or not /// \return True if the entity is a nested model, false otherwise public: Q_INVOKABLE bool NestedModel() const; diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qml b/src/gui/plugins/component_inspector/ComponentInspector.qml index aa058cae4f..f817ec7741 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qml +++ b/src/gui/plugins/component_inspector/ComponentInspector.qml @@ -85,6 +85,19 @@ Rectangle { ComponentInspector.OnPose(_x, _y, _z, _roll, _pitch, _yaw) } + /** + * Forward light changes to C++ + */ + function onLight(_rSpecular, _gSpecular, _bSpecular, _aSpecular, + _rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse, + _attRange, _attLinear, _attConstant, _attQuadratic, + _castShadows) { + ComponentInspector.OnLight(_rSpecular, _gSpecular, _bSpecular, _aSpecular, + _rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse, + _attRange, _attLinear, _attConstant, _attQuadratic, + _castShadows) + } + Rectangle { id: header height: lockButton.height diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qrc b/src/gui/plugins/component_inspector/ComponentInspector.qrc index 43efec19d1..b78b769aee 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qrc +++ b/src/gui/plugins/component_inspector/ComponentInspector.qrc @@ -2,6 +2,7 @@ Boolean.qml ComponentInspector.qml + Light.qml NoData.qml Pose3d.qml String.qml diff --git a/src/gui/plugins/component_inspector/Light.qml b/src/gui/plugins/component_inspector/Light.qml new file mode 100644 index 0000000000..7db0c33faf --- /dev/null +++ b/src/gui/plugins/component_inspector/Light.qml @@ -0,0 +1,788 @@ +/* + * Copyright (C) 2020 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 1.4 +import QtQuick.Controls 2.2 +import QtQuick.Controls.Material 2.1 +import QtQuick.Layouts 1.3 +import QtQuick.Controls.Styles 1.4 +import "qrc:/ComponentInspector" +import "qrc:/qml" + +// Item displaying 3D pose information. +Rectangle { + height: header.height + content.height + width: componentInspector.width + color: index % 2 == 0 ? lightGrey : darkGrey + + // Left indentation + property int indentation: 10 + + // Horizontal margins + property int margin: 5 + + // Maximum spinbox value + property double spinMax: 1 + + // Read-only / write + property bool readOnly: { + return false; + } + + property int iconWidth: 20 + property int iconHeight: 20 + + // Loaded item for R + property var rSpecularItem: {} + + // Loaded item for G + property var gSpecularItem: {} + + // Loaded item for B + property var bSpecularItem: {} + + // Loaded item for A + property var aSpecularItem: {} + + // Loaded item for R + property var rDiffuseItem: {} + + // Loaded item for G + property var gDiffuseItem: {} + + // Loaded item for B + property var bDiffuseItem: {} + + // Loaded item for A + property var aDiffuseItem: {} + + // Loaded item for R + property var attRangeItem: {} + + // Loaded item for G + property var attLinearItem: {} + + // Loaded item for B + property var attConstantItem: {} + + // Loaded item for A + property var attQuadraticItem: {} + + property var castShadowsItem: {} + + // Send new pose to C++ + function sendLight() { + // TODO(anyone) There's a loss of precision when these values get to C++ + componentInspector.onLight( + rSpecularItem.value, + gSpecularItem.value, + bSpecularItem.value, + aSpecularItem.value, + rDiffuseItem.value, + gDiffuseItem.value, + bDiffuseItem.value, + aDiffuseItem.value, + attRangeItem.value, + attLinearItem.value, + attConstantItem.value, + attQuadraticItem.value, + castShadowsItem + ); + } + + FontMetrics { + id: fontMetrics + font.family: "Roboto" + } + + /** + * Used to create a spin box + */ + Component { + id: spinZeroOne + IgnSpinBox { + id: writableSpin + value: writableSpin.activeFocus ? writableSpin.value : numberValue + minimumValue: 0 + maximumValue: spinMax + decimals: 6 + onEditingFinished: { + sendLight() + } + } + } + Component { + id: spinZeroMax + IgnSpinBox { + id: writableSpin + value: writableSpin.activeFocus ? writableSpin.value : numberValue + minimumValue: 0 + maximumValue: 1000000 + decimals: 6 + onEditingFinished: { + sendLight() + } + } + } + + /** + * Used to create a read-only number + */ + Component { + id: readOnlyNumber + Text { + id: numberText + anchors.fill: parent + horizontalAlignment: Text.AlignRight + verticalAlignment: Text.AlignVCenter + text: { + var decimals = numberText.width < 100 ? 2 : 6 + return numberValue.toFixed(decimals) + } + } + } + + Column { + anchors.fill: parent + + // Header + Rectangle { + id: header + width: parent.width + height: typeHeader.height + color: "transparent" + + RowLayout { + anchors.fill: parent + Item { + width: margin + } + Image { + id: icon + sourceSize.height: indentation + sourceSize.width: indentation + fillMode: Image.Pad + Layout.alignment : Qt.AlignVCenter + source: content.show ? + "qrc:/Gazebo/images/minus.png" : "qrc:/Gazebo/images/plus.png" + } + TypeHeader { + id: typeHeader + } + Item { + Layout.fillWidth: true + } + } + MouseArea { + anchors.fill: parent + hoverEnabled: true + cursorShape: Qt.PointingHandCursor + onClicked: { + content.show = !content.show + } + onEntered: { + header.color = highlightColor + } + onExited: { + header.color = "transparent" + } + } + } + + // Content + Rectangle { + id: content + property bool show: false + width: parent.width + height: show ? grid.height : 0 + clip: true + color: "transparent" + + Behavior on height { + NumberAnimation { + duration: 200; + easing.type: Easing.InOutQuad + } + } + + + GridLayout { + id: grid + width: parent.width + columns: 6 + + Text { + Layout.columnSpan: 6 + text: "Specular" + color: "dimgrey" + width: margin + indentation + } + + // Left spacer + Item { + Layout.rowSpan: 3 + width: margin + indentation + } + + Component { + id: plotIcon + Image { + property string componentInfo: "" + source: "plottable_icon.svg" + anchors.top: parent.top + anchors.left: parent.left + + Drag.mimeData: { "text/plain" : (model === null) ? "" : + "Component," + model.entity + "," + model.typeId + "," + + model.dataType + "," + componentInfo + "," + model.shortName + } + Drag.dragType: Drag.Automatic + Drag.supportedActions : Qt.CopyAction + Drag.active: dragMouse.drag.active + // a point to drag from + Drag.hotSpot.x: 0 + Drag.hotSpot.y: y + MouseArea { + id: dragMouse + anchors.fill: parent + drag.target: (model === null) ? null : parent + onPressed: parent.grabToImage(function(result) {parent.Drag.imageSource = result.url }) + onReleased: parent.Drag.drop(); + cursorShape: Qt.DragCopyCursor + } + } + } + + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: rSpecularText.width + indentation*3 + Loader { + id: loaderSpecularR + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularR.item.componentInfo = "r" + + Text { + id : rSpecularText + text: ' R' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: rSpecularLoader + anchors.fill: parent + property double numberValue: model.data[0] + sourceComponent: spinZeroOne + onLoaded: { + rSpecularItem = rSpecularLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: gSpecularText.width + indentation*3 + Loader { + id: loaderSpecularG + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularG.item.componentInfo = "g" + + Text { + id : gSpecularText + text: ' G' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + + // Right spacer + Item { + Layout.rowSpan: 3 + width: margin + indentation + } + + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: gSpecularLoader + anchors.fill: parent + property double numberValue: model.data[1] + sourceComponent: spinZeroOne + onLoaded: { + gSpecularItem = gSpecularLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: bSpecularText.width + indentation*3 + Loader { + id: loaderSpecularB + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularB.item.componentInfo = "b" + + Text { + id : bSpecularText + text: ' B' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: bSpecularLoader + anchors.fill: parent + property double numberValue: model.data[2] + sourceComponent: spinZeroOne + onLoaded: { + bSpecularItem = bSpecularLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: aSpecularText.width + indentation*3 + Loader { + id: loaderSpecularA + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularA.item.componentInfo = "a" + + Text { + id : aSpecularText + text: ' A' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: aSpecularLoader + anchors.fill: parent + property double numberValue: model.data[3] + sourceComponent: spinZeroOne + onLoaded: { + aSpecularItem = aSpecularLoader.item + } + } + } + // Right spacer + Item { + Layout.rowSpan: 3 + width: margin + indentation + } + + Text { + Layout.columnSpan: 6 + text: "Diffuse" + color: "dimgrey" + width: margin + indentation + } + + // Left spacer + Item { + Layout.rowSpan: 3 + width: margin + indentation + } + + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: rDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseR + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseR.item.componentInfo = "r" + + Text { + id : rDiffuseText + text: ' R' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: rDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[4] + sourceComponent: spinZeroOne + onLoaded: { + rDiffuseItem = rDiffuseLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: gDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseG + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseG.item.componentInfo = "g" + + Text { + id : gDiffuseText + text: ' G' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + + // Right spacer + Item { + Layout.rowSpan: 3 + width: margin + indentation + } + + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: gDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[5] + sourceComponent: spinZeroOne + onLoaded: { + gDiffuseItem = gDiffuseLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: bDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseB + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseB.item.componentInfo = "b" + + Text { + id : bDiffuseText + text: ' B' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: bDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[6] + sourceComponent: spinZeroOne + onLoaded: { + bDiffuseItem = bDiffuseLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: aDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseA + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseA.item.componentInfo = "a" + + Text { + id : aDiffuseText + text: ' A' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: aDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[7] + sourceComponent: spinZeroOne + onLoaded: { + aDiffuseItem = aDiffuseLoader.item + } + } + } + + Text { + Layout.columnSpan: 6 + text: "Attenuation" + color: "dimgrey" + width: margin + indentation + } + + // Left spacer + Item { + Layout.rowSpan: 3 + width: margin + indentation + } + + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attRangeText.width + indentation*3 + Loader { + id: loaderAttRange + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttRange.item.componentInfo = "Attenuation Range" + + Text { + id : attRangeText + text: ' Range' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attRangeLoader + anchors.fill: parent + property double numberValue: model.data[8] + sourceComponent: spinZeroMax + onLoaded: { + attRangeItem = attRangeLoader.item + } + } + } + + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attLinearText.width + indentation*3 + Loader { + id: loaderAttLinear + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttLinear.item.componentInfo = "Attenuation linear" + + Text { + id : attLinearText + text: ' Linear' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + + // Right spacer + Item { + Layout.rowSpan: 3 + width: margin + indentation + } + + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attLinearLoader + anchors.fill: parent + property double numberValue: model.data[9] + sourceComponent: spinZeroOne + onLoaded: { + attLinearItem = attLinearLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attConstantText.width + indentation*3 + Loader { + id: loaderAttConstant + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttConstant.item.componentInfo = "Attenuation constant" + + Text { + id : attConstantText + text: ' Constant' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attConstantLoader + anchors.fill: parent + property double numberValue: model.data[10] + sourceComponent: spinZeroOne + onLoaded: { + attConstantItem = attConstantLoader.item + } + } + } + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attQuadraticText.width + indentation*3 + Loader { + id: loaderAttQuadratic + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttQuadratic.item.componentInfo = "Attenuation quadratic" + + Text { + id : attQuadraticText + text: ' Quadratic' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attQuadraticLoader + anchors.fill: parent + property double numberValue: model.data[11] + sourceComponent: spinZeroMax + onLoaded: { + attQuadraticItem = attQuadraticLoader.item + } + } + } + +////////////// + + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: castShadowsText.width + indentation*3 + Loader { + id: loaderCastShadows + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderCastShadows.item.componentInfo = "Cast shadows" + + Text { + id : castShadowsText + text: ' Cast shadows' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + Layout.fillWidth: true + height: 40 + + Switch { + id: booleanSwitchCastShadows + checked: model.data[12] + enabled: true + + onToggled: { + castShadowsItem = checked + sendLight() + } + } + } + } + } + } +} diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 710862c326..b57e19c6e1 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -163,6 +163,9 @@ class ignition::gazebo::RenderUtilPrivate /// \brief A map of entity ids and pose updates. public: std::unordered_map entityPoses; + /// \brief A map of entity ids and light updates. + public: std::unordered_map entityLights; + /// \brief A map of entity ids and actor transforms. public: std::map> actorTransforms; @@ -284,6 +287,7 @@ void RenderUtil::Update() auto newLights = std::move(this->dataPtr->newLights); auto removeEntities = std::move(this->dataPtr->removeEntities); auto entityPoses = std::move(this->dataPtr->entityPoses); + auto entityLights = std::move(this->dataPtr->entityLights); auto trajectoryPoses = std::move(this->dataPtr->trajectoryPoses); auto actorTransforms = std::move(this->dataPtr->actorTransforms); auto actorAnimationData = std::move(this->dataPtr->actorAnimationData); @@ -297,6 +301,7 @@ void RenderUtil::Update() this->dataPtr->newLights.clear(); this->dataPtr->removeEntities.clear(); this->dataPtr->entityPoses.clear(); + this->dataPtr->entityLights.clear(); this->dataPtr->trajectoryPoses.clear(); this->dataPtr->actorTransforms.clear(); this->dataPtr->actorAnimationData.clear(); @@ -427,6 +432,37 @@ void RenderUtil::Update() } } + // update entities' pose + { + IGN_PROFILE("RenderUtil::Update Lights"); + for (const auto &light : entityLights) { + auto node = this->dataPtr->sceneManager.NodeById(light.first); + if (!node) + continue; + auto l = std::dynamic_pointer_cast(node); + if (l) + { + if (l->DiffuseColor() != light.second.Diffuse()) + l->SetDiffuseColor(light.second.Diffuse()); + if (l->SpecularColor() != light.second.Specular()) + l->SetSpecularColor(light.second.Specular()); + if (ignition::math::equal( + l->AttenuationRange(), light.second.AttenuationRange())) + l->SetAttenuationRange(light.second.AttenuationRange()); + if (ignition::math::equal( + l->AttenuationLinear(), light.second.LinearAttenuationFactor())) + l->SetAttenuationLinear(light.second.LinearAttenuationFactor()); + if (ignition::math::equal( + l->AttenuationConstant(), light.second.ConstantAttenuationFactor())) + l->SetAttenuationConstant(light.second.ConstantAttenuationFactor()); + if (ignition::math::equal( + l->AttenuationQuadratic(), light.second.QuadraticAttenuationFactor())) + l->SetAttenuationQuadratic(light.second.QuadraticAttenuationFactor()); + if (l->CastShadows() != light.second.CastShadows()) + l->SetCastShadows(light.second.CastShadows()); + } + } + } // update entities' pose { IGN_PROFILE("RenderUtil::Update Poses"); @@ -1070,13 +1106,14 @@ void RenderUtilPrivate::UpdateRenderingEntities( return true; }); - // lights + // update lights _ecm.Each( [&](const Entity &_entity, - const components::Light *, + const components::Light *_light, const components::Pose *_pose)->bool { this->entityPoses[_entity] = _pose->Data(); + this->entityLights[_entity] = _light->Data(); return true; }); diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 25e1a3ec15..8f5427afe4 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -19,6 +19,7 @@ #include #include +#include #include #include @@ -30,6 +31,7 @@ #include #include +#include #include #include @@ -123,6 +125,19 @@ class RemoveCommand : public UserCommandBase public: bool Execute() final; }; +/// \brief Command to modify a light entity from simulation. +class LightCommand : public UserCommandBase +{ + /// \brief Constructor + /// \param[in] _msg Message identifying the entity to be removed. + /// \param[in] _iface Pointer to user commands interface. + public: LightCommand(msgs::Light *_msg, + std::shared_ptr &_iface); + + // Documentation inherited + public: bool Execute() final; +}; + /// \brief Command to update an entity's pose transform. class PoseCommand : public UserCommandBase { @@ -178,6 +193,13 @@ class ignition::gazebo::systems::UserCommandsPrivate public: bool RemoveService(const msgs::Entity &_req, msgs::Boolean &_res); + /// \brief Callback for light service + /// \param[in] _req Request containing light update of an entity. + /// \param[in] _res True if message successfully received and queued. + /// It does not mean that the entity will be successfully moved. + /// \return True if successful. + public: bool LightService(const msgs::Light &_req, msgs::Boolean &_res); + /// \brief Callback for pose service /// \param[in] _req Request containing pose update of an entity. /// \param[in] _res True if message successfully received and queued. @@ -248,6 +270,13 @@ void UserCommands::Configure(const Entity &_entity, &UserCommandsPrivate::PoseService, this->dataPtr.get()); ignmsg << "Pose service on [" << poseService << "]" << std::endl; + + // Pose service + std::string lightService{"/world/" + worldName + "/config"}; + this->dataPtr->node.Advertise(lightService, + &UserCommandsPrivate::LightService, this->dataPtr.get()); + + ignmsg << "Pose service on [" << lightService << "]" << std::endl; } ////////////////////////////////////////////////// @@ -340,6 +369,25 @@ bool UserCommandsPrivate::RemoveService(const msgs::Entity &_req, return true; } +////////////////////////////////////////////////// +bool UserCommandsPrivate::LightService(const msgs::Light &_req, + msgs::Boolean &_res) +{ + // Create command and push it to queue + auto msg = _req.New(); + msg->CopyFrom(_req); + auto cmd = std::make_unique(msg, this->iface); + + // Push to pending + { + std::lock_guard lock(this->pendingMutex); + this->pendingCmds.push_back(std::move(cmd)); + } + + _res.set_data(true); + return true; +} + ////////////////////////////////////////////////// bool UserCommandsPrivate::PoseService(const msgs::Pose &_req, msgs::Boolean &_res) @@ -630,6 +678,64 @@ bool RemoveCommand::Execute() return true; } + +////////////////////////////////////////////////// +LightCommand::LightCommand(msgs::Light *_msg, + std::shared_ptr &_iface) + : UserCommandBase(_msg, _iface) +{ +} + +////////////////////////////////////////////////// +bool LightCommand::Execute() +{ + auto LightMsg = dynamic_cast(this->msg); + if (nullptr == LightMsg) + { + ignerr << "Internal error, null create message" << std::endl; + return false; + } + + auto entity = this->iface->ecm->EntityByComponents( + components::Name(LightMsg->name()), + components::ParentEntity(this->iface->worldEntity)); + + auto lightComp = this->iface->ecm->Component(entity); + if (nullptr == lightComp) + entity = kNullEntity; + + if (!entity) { + ignmsg << "Light component not available" << std::endl; + return false; + } + + lightComp->Data().SetDiffuse(msgs::Convert(LightMsg->diffuse())); + lightComp->Data().SetSpecular(msgs::Convert(LightMsg->specular())); + lightComp->Data().SetAttenuationRange(LightMsg->range()); + lightComp->Data().SetLinearAttenuationFactor(LightMsg->attenuation_linear()); + lightComp->Data().SetConstantAttenuationFactor(LightMsg->attenuation_constant()); + lightComp->Data().SetQuadraticAttenuationFactor(LightMsg->attenuation_quadratic()); + lightComp->Data().SetCastShadows(LightMsg->cast_shadows()); + + auto lightPose = this->iface->ecm->Component(entity); + if (nullptr == lightPose) + entity = kNullEntity; + + if (!entity) { + ignmsg << "Pose component not available" << std::endl; + return false; + } + + if (LightMsg->has_pose()) { + lightPose->Data().Pos() = msgs::Convert(LightMsg->pose()).Pos(); + } + + this->iface->ecm->SetChanged(entity, + components::Pose::typeId, ComponentState::OneTimeChange); + + return true; +} + ////////////////////////////////////////////////// PoseCommand::PoseCommand(msgs::Pose *_msg, std::shared_ptr &_iface) From 2b81da54ad1a9e6569ea14fbfb78f5c3b9ba788c Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 11 Dec 2020 00:18:29 +0100 Subject: [PATCH 02/42] make linters happy Signed-off-by: ahcorde --- src/gui/plugins/component_inspector/ComponentInspector.cc | 1 - src/gui/plugins/component_inspector/ComponentInspector.hh | 7 ++++--- src/rendering/RenderUtil.cc | 3 ++- src/systems/user_commands/UserCommands.cc | 6 ++++-- 4 files changed, 10 insertions(+), 7 deletions(-) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index f31e75d201..e68e98e217 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -521,7 +521,6 @@ void ComponentInspector::Update(const UpdateInfo &, this->dataPtr->worldName = comp->Data(); else this->dataPtr->entityName = comp->Data(); - } else if (typeId == components::ParentEntity::typeId) { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index dff17346d1..eebd6812db 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -230,9 +230,10 @@ namespace gazebo /// \param[in] _attQuadratic Quadratic attenuation /// \param[in] _castShadows Cast Shadows attenuation public: Q_INVOKABLE void OnLight( - double _rSpecular, double _gSpecular, double _bSpecular, double _aSpecular, - double _rDiffuse, double _gDiffuse, double _bDiffuse, double _aDiffuse, - double _attRange, double _attLinear, double _attConstant, double _attQuadratic, + double _rSpecular, double _gSpecular, double _bSpecular, + double _aSpecular, double _rDiffuse, double _gDiffuse, + double _bDiffuse, double _aDiffuse, double _attRange, + double _attLinear, double _attConstant, double _attQuadratic, bool _castShadows); /// \brief Get whether the entity is a nested model or not diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index b57e19c6e1..16e6aa99c5 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -456,7 +456,8 @@ void RenderUtil::Update() l->AttenuationConstant(), light.second.ConstantAttenuationFactor())) l->SetAttenuationConstant(light.second.ConstantAttenuationFactor()); if (ignition::math::equal( - l->AttenuationQuadratic(), light.second.QuadraticAttenuationFactor())) + l->AttenuationQuadratic(), + light.second.QuadraticAttenuationFactor())) l->SetAttenuationQuadratic(light.second.QuadraticAttenuationFactor()); if (l->CastShadows() != light.second.CastShadows()) l->SetCastShadows(light.second.CastShadows()); diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 8f5427afe4..3e10ba4204 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -713,8 +713,10 @@ bool LightCommand::Execute() lightComp->Data().SetSpecular(msgs::Convert(LightMsg->specular())); lightComp->Data().SetAttenuationRange(LightMsg->range()); lightComp->Data().SetLinearAttenuationFactor(LightMsg->attenuation_linear()); - lightComp->Data().SetConstantAttenuationFactor(LightMsg->attenuation_constant()); - lightComp->Data().SetQuadraticAttenuationFactor(LightMsg->attenuation_quadratic()); + lightComp->Data().SetConstantAttenuationFactor( + LightMsg->attenuation_constant()); + lightComp->Data().SetQuadraticAttenuationFactor( + LightMsg->attenuation_quadratic()); lightComp->Data().SetCastShadows(LightMsg->cast_shadows()); auto lightPose = this->iface->ecm->Component(entity); From 8adc695424d837ddb919e4fef222a96c7db0623a Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 14 Dec 2020 14:35:49 +0100 Subject: [PATCH 03/42] Included spot and directional features Signed-off-by: ahcorde --- .../component_inspector/ComponentInspector.cc | 37 +- .../component_inspector/ComponentInspector.hh | 4 +- .../ComponentInspector.qml | 6 +- src/gui/plugins/component_inspector/Light.qml | 349 +++++++++++++++++- src/rendering/RenderUtil.cc | 20 + src/systems/user_commands/UserCommands.cc | 10 + 6 files changed, 406 insertions(+), 20 deletions(-) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index e68e98e217..204314182f 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -119,6 +119,13 @@ void ignition::gazebo::setData(QStandardItem *_item, const math::Pose3d &_data) template<> void ignition::gazebo::setData(QStandardItem *_item, const sdf::Light &_data) { + int lightType = 0; + if (_data.Type() == sdf::LightType::SPOT) { + lightType = 1; + } else if (_data.Type() == sdf::LightType::DIRECTIONAL) { + lightType = 2; + } + _item->setData(QString("Light"), ComponentsModel::RoleNames().key("dataType")); _item->setData(QList({ @@ -134,7 +141,14 @@ void ignition::gazebo::setData(QStandardItem *_item, const sdf::Light &_data) QVariant(_data.LinearAttenuationFactor()), QVariant(_data.ConstantAttenuationFactor()), QVariant(_data.QuadraticAttenuationFactor()), - QVariant(_data.CastShadows()) + QVariant(_data.CastShadows()), + QVariant(lightType), + QVariant(_data.Direction().X()), + QVariant(_data.Direction().Y()), + QVariant(_data.Direction().Z()), + QVariant(_data.SpotInnerAngle().Radian()), + QVariant(_data.SpotOuterAngle().Radian()), + QVariant(_data.SpotFalloff()) }), ComponentsModel::RoleNames().key("data")); } @@ -761,7 +775,9 @@ void ComponentInspector::OnLight( double _rSpecular, double _gSpecular, double _bSpecular, double _aSpecular, double _rDiffuse, double _gDiffuse, double _bDiffuse, double _aDiffuse, double _attRange, double _attLinear, double _attConstant, - double _attQuadratic, bool _castShadows) + double _attQuadratic, bool _castShadows, double _directionX, + double _directionY, double _directionZ, double _innerAngle, + double _outerAngle, double _falloff, int _type) { std::function cb = [](const ignition::msgs::Boolean &/*_rep*/, const bool _result) @@ -781,6 +797,23 @@ void ComponentInspector::OnLight( req.set_attenuation_constant(_attConstant); req.set_attenuation_quadratic(_attQuadratic); req.set_cast_shadows(_castShadows); + if (_type == 0) + req.set_type(ignition::msgs::Light::POINT); + else if (_type == 1) + req.set_type(ignition::msgs::Light::SPOT); + else + req.set_type(ignition::msgs::Light::DIRECTIONAL); + + if (_type == 1) { // sdf::LightType::SPOT + req.set_spot_inner_angle(_innerAngle); + req.set_spot_outer_angle(_outerAngle); + req.set_spot_falloff(_falloff); + } + if (_type == 1 || _type == 2) { // sdf::LightType::SPOT || sdf::LightType::DIRECTIONAL + ignition::msgs::Set(req.mutable_direction(), + ignition::math::Vector3d(_directionX, _directionY, _directionZ)); + } + auto lightConfigService = "/world/lights/config"; this->dataPtr->node.Request(lightConfigService, req, cb); } diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index eebd6812db..b6d94b383c 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -234,7 +234,9 @@ namespace gazebo double _aSpecular, double _rDiffuse, double _gDiffuse, double _bDiffuse, double _aDiffuse, double _attRange, double _attLinear, double _attConstant, double _attQuadratic, - bool _castShadows); + bool _castShadows, double _directionX, double _directionY, + double _directionZ, double _innerAngle, double _outerAngle, + double _falloff, int _type); /// \brief Get whether the entity is a nested model or not /// \return True if the entity is a nested model, false otherwise diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qml b/src/gui/plugins/component_inspector/ComponentInspector.qml index f817ec7741..094ae784d1 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qml +++ b/src/gui/plugins/component_inspector/ComponentInspector.qml @@ -91,11 +91,13 @@ Rectangle { function onLight(_rSpecular, _gSpecular, _bSpecular, _aSpecular, _rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse, _attRange, _attLinear, _attConstant, _attQuadratic, - _castShadows) { + _castShadows, _directionX, _directionY, _directionZ, + _innerAngle, _outerAngle, _falloff, _type) { ComponentInspector.OnLight(_rSpecular, _gSpecular, _bSpecular, _aSpecular, _rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse, _attRange, _attLinear, _attConstant, _attQuadratic, - _castShadows) + _castShadows, _directionX, _directionY, _directionZ, + _innerAngle, _outerAngle, _falloff, _type) } Rectangle { diff --git a/src/gui/plugins/component_inspector/Light.qml b/src/gui/plugins/component_inspector/Light.qml index 7db0c33faf..01ece47701 100644 --- a/src/gui/plugins/component_inspector/Light.qml +++ b/src/gui/plugins/component_inspector/Light.qml @@ -46,44 +46,63 @@ Rectangle { property int iconWidth: 20 property int iconHeight: 20 - // Loaded item for R + // Loaded item for specular red property var rSpecularItem: {} - // Loaded item for G + // Loaded item for specular green property var gSpecularItem: {} - // Loaded item for B + // Loaded item for specular blue property var bSpecularItem: {} - // Loaded item for A + // Loaded item for specular alpha property var aSpecularItem: {} - // Loaded item for R + // Loaded item for diffuse red property var rDiffuseItem: {} - // Loaded item for G + // Loaded item for diffuse green property var gDiffuseItem: {} - // Loaded item for B + // Loaded item for diffuse blue property var bDiffuseItem: {} - // Loaded item for A + // Loaded item for diffuse alpha property var aDiffuseItem: {} - // Loaded item for R + // Loaded item for attenuation range property var attRangeItem: {} - // Loaded item for G + // Loaded item for attenuation linear property var attLinearItem: {} - // Loaded item for B + // Loaded item for attenuation constant property var attConstantItem: {} - // Loaded item for A + // Loaded item for attenuation quadratic property var attQuadraticItem: {} + // Loaded item for cast shadows property var castShadowsItem: {} + // Loaded item for direction X (spotlight or directional) + property var directionXItem: {} + + // Loaded item for direction Y (spotlight or directional) + property var directionYItem: {} + + // Loaded item for direction Z (spotlight or directional) + property var directionZItem: {} + + // Loaded item for inner angle (spotlight) + property var innerAngleItem: {} + + // Loaded item for inner angle (spotlight) + property var outerAngleItem: {} + + // Loaded item for falloff (spotlight) + property var falloffItem: {} + // Send new pose to C++ function sendLight() { // TODO(anyone) There's a loss of precision when these values get to C++ @@ -100,7 +119,14 @@ Rectangle { attLinearItem.value, attConstantItem.value, attQuadraticItem.value, - castShadowsItem + castShadowsItem, + directionXItem.value, + directionYItem.value, + directionZItem.value, + innerAngleItem.value, + outerAngleItem.value, + falloffItem.value, + model.data[13] ); } @@ -138,6 +164,32 @@ Rectangle { } } } + Component { + id: spinAngle + IgnSpinBox { + id: writableSpin + value: writableSpin.activeFocus ? writableSpin.value : numberValue + minimumValue: -3.1416 + maximumValue: 3.1416 + decimals: 6 + onEditingFinished: { + sendLight() + } + } + } + Component { + id: spinNoLimit + IgnSpinBox { + id: writableSpin + value: writableSpin.activeFocus ? writableSpin.value : numberValue + minimumValue: -100000 + maximumValue: 100000 + decimals: 6 + onEditingFinished: { + sendLight() + } + } + } /** * Used to create a read-only number @@ -743,8 +795,6 @@ Rectangle { } } -////////////// - Rectangle { color: "transparent" height: 40 @@ -782,6 +832,275 @@ Rectangle { } } } + + Text { + visible: model.data[13] === 1 || model.data[13] === 2 + Layout.columnSpan: 6 + text: "Direction" + color: "dimgrey" + width: margin + indentation + } + + // Left spacer + Item { + visible: model.data[13] === 1 || model.data[13] === 2 + Layout.rowSpan: 3 + width: margin + indentation + } + + Rectangle { + visible: model.data[13] === 1 || model.data[13] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: xDirectionText.width + indentation*3 + Loader { + id: loaderDirectionX + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionX.item.componentInfo = "X direction" + + Text { + visible: model.data[13] === 1 || model.data[13] === 2 + id : xDirectionText + text: ' X:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[13] === 1 || model.data[13] === 2 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: xDirectionLoader + anchors.fill: parent + property double numberValue: model.data[14] + sourceComponent: spinNoLimit + onLoaded: { + directionXItem = xDirectionLoader.item + } + } + } + + Rectangle { + visible: model.data[13] === 1 || model.data[13] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: yDirectionText.width + indentation*3 + Loader { + id: loaderDirectionY + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionY.item.componentInfo = "Y direction" + + Text { + visible: model.data[13] === 1 || model.data[13] === 2 + id : yDirectionText + text: ' Y:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[13] === 1 || model.data[13] === 2 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: yDirectionLoader + anchors.fill: parent + property double numberValue: model.data[15] + sourceComponent: spinNoLimit + onLoaded: { + directionYItem = yDirectionLoader.item + } + } + } + + Rectangle { + visible: model.data[13] === 1 || model.data[13] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: zDirectionText.width + indentation*3 + Loader { + id: loaderDirectionZ + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionZ.item.componentInfo = "Z direction" + + Text { + visible: model.data[13] === 1 || model.data[13] === 2 + id : zDirectionText + text: ' Z:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[13] === 1 || model.data[13] === 2 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: zDirectionLoader + anchors.fill: parent + property double numberValue: model.data[16] + sourceComponent: spinNoLimit + onLoaded: { + directionZItem = zDirectionLoader.item + } + } + } + + Text { + visible: model.data[13] === 1 + Layout.columnSpan: 6 + text: "Spot features" + color: "dimgrey" + width: margin + indentation + } + + // Left spacer + Item { + visible: model.data[13] === 1 + Layout.rowSpan: 3 + width: margin + indentation + } + + Rectangle { + visible: model.data[13] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: innerAngleText.width + indentation*3 + Loader { + id: loaderInnerAngle + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderInnerAngle.item.componentInfo = "Inner Angle" + + Text { + visible: model.data[13] === 1 + id : innerAngleText + text: ' Inner Angle:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[13] === 1 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: innerAngleLoader + anchors.fill: parent + property double numberValue: model.data[17] + sourceComponent: spinAngle + onLoaded: { + innerAngleItem = innerAngleLoader.item + } + } + } + + Rectangle { + visible: model.data[13] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: outerAngleText.width + indentation*3 + Loader { + id: loaderOuterAngle + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderOuterAngle.item.componentInfo = "Outer Angle" + + Text { + visible: model.data[13] === 1 + id : outerAngleText + text: ' Outer angle:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[13] === 1 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: outerAngleLoader + anchors.fill: parent + property double numberValue: model.data[18] + sourceComponent: spinAngle + onLoaded: { + outerAngleItem = outerAngleLoader.item + } + } + } + Rectangle { + visible: model.data[13] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: fallOffText.width + indentation*3 + Loader { + id: loaderFallOff + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderFallOff.item.componentInfo = "Spot falloff" + + Text { + visible: model.data[13] === 1 + id : fallOffText + text: ' Falloff:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[13] === 1 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: fallOffLoader + anchors.fill: parent + property double numberValue: model.data[19] + sourceComponent: spinZeroMax + onLoaded: { + falloffItem = fallOffLoader.item + } + } + } } } } diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 16e6aa99c5..6f29087c9f 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -461,6 +461,26 @@ void RenderUtil::Update() l->SetAttenuationQuadratic(light.second.QuadraticAttenuationFactor()); if (l->CastShadows() != light.second.CastShadows()) l->SetCastShadows(light.second.CastShadows()); + auto lDirectional = + std::dynamic_pointer_cast(node); + if (lDirectional) + { + if (lDirectional->Direction() != light.second.Direction()) + lDirectional->SetDirection(light.second.Direction()); + } + auto lSpotLight = + std::dynamic_pointer_cast(node); + if (lSpotLight) + { + if (lSpotLight->Direction() != light.second.Direction()) + lSpotLight->SetDirection(light.second.Direction()); + if (lSpotLight->InnerAngle() != light.second.SpotInnerAngle()) + lSpotLight->SetInnerAngle(light.second.SpotInnerAngle()); + if (lSpotLight->OuterAngle() != light.second.SpotOuterAngle()) + lSpotLight->SetOuterAngle(light.second.SpotOuterAngle()); + if (lSpotLight->Falloff() != light.second.SpotFalloff()) + lSpotLight->SetFalloff(light.second.SpotFalloff()); + } } } } diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 3e10ba4204..7f82c90628 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -719,6 +719,16 @@ bool LightCommand::Execute() LightMsg->attenuation_quadratic()); lightComp->Data().SetCastShadows(LightMsg->cast_shadows()); + if (LightMsg->type() != ignition::msgs::Light::POINT) { + lightComp->Data().SetDirection(msgs::Convert(LightMsg->direction())); + } + + if (LightMsg->type() == ignition::msgs::Light::SPOT) { + lightComp->Data().SetSpotInnerAngle(ignition::math::Angle(LightMsg->spot_inner_angle())); + lightComp->Data().SetSpotOuterAngle(ignition::math::Angle(LightMsg->spot_outer_angle())); + lightComp->Data().SetSpotFalloff(LightMsg->spot_falloff()); + } + auto lightPose = this->iface->ecm->Component(entity); if (nullptr == lightPose) entity = kNullEntity; From deea4522da6eef1a7703873280072f876795a0e5 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 14 Dec 2020 14:40:33 +0100 Subject: [PATCH 04/42] Fix compile warning Signed-off-by: ahcorde --- src/rendering/RenderUtil.cc | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 6f29087c9f..3f7b5c9215 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -478,7 +478,9 @@ void RenderUtil::Update() lSpotLight->SetInnerAngle(light.second.SpotInnerAngle()); if (lSpotLight->OuterAngle() != light.second.SpotOuterAngle()) lSpotLight->SetOuterAngle(light.second.SpotOuterAngle()); - if (lSpotLight->Falloff() != light.second.SpotFalloff()) + if (ignition::math::equal( + lSpotLight->Falloff(), + light.second.SpotFalloff())) lSpotLight->SetFalloff(light.second.SpotFalloff()); } } From ef53a13d8d1d5c6628c642c02f087b0c985b7a6f Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 14 Dec 2020 18:24:58 +0100 Subject: [PATCH 05/42] make linters happy Signed-off-by: ahcorde --- .../plugins/component_inspector/ComponentInspector.cc | 11 ++++++++--- src/systems/user_commands/UserCommands.cc | 6 ++++-- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 204314182f..ceb90ca0c4 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -120,9 +120,12 @@ template<> void ignition::gazebo::setData(QStandardItem *_item, const sdf::Light &_data) { int lightType = 0; - if (_data.Type() == sdf::LightType::SPOT) { + if (_data.Type() == sdf::LightType::SPOT) + { lightType = 1; - } else if (_data.Type() == sdf::LightType::DIRECTIONAL) { + } + else if (_data.Type() == sdf::LightType::DIRECTIONAL) + { lightType = 2; } @@ -809,7 +812,9 @@ void ComponentInspector::OnLight( req.set_spot_outer_angle(_outerAngle); req.set_spot_falloff(_falloff); } - if (_type == 1 || _type == 2) { // sdf::LightType::SPOT || sdf::LightType::DIRECTIONAL + + // if sdf::LightType::SPOT || sdf::LightType::DIRECTIONAL + if (_type == 1 || _type == 2) { ignition::msgs::Set(req.mutable_direction(), ignition::math::Vector3d(_directionX, _directionY, _directionZ)); } diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 7f82c90628..8c5899483f 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -724,8 +724,10 @@ bool LightCommand::Execute() } if (LightMsg->type() == ignition::msgs::Light::SPOT) { - lightComp->Data().SetSpotInnerAngle(ignition::math::Angle(LightMsg->spot_inner_angle())); - lightComp->Data().SetSpotOuterAngle(ignition::math::Angle(LightMsg->spot_outer_angle())); + lightComp->Data().SetSpotInnerAngle( + ignition::math::Angle(LightMsg->spot_inner_angle())); + lightComp->Data().SetSpotOuterAngle( + ignition::math::Angle(LightMsg->spot_outer_angle())); lightComp->Data().SetSpotFalloff(LightMsg->spot_falloff()); } From c11d628b0c002214929054cea5d8204783aff12a Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 15 Dec 2020 17:42:35 +0100 Subject: [PATCH 06/42] Added feedback Signed-off-by: ahcorde --- .../component_inspector/ComponentInspector.cc | 22 ++-- .../component_inspector/ComponentInspector.hh | 11 +- src/gui/plugins/component_inspector/Light.qml | 102 +++++++----------- src/rendering/RenderUtil.cc | 13 ++- src/systems/user_commands/UserCommands.cc | 57 +++++----- 5 files changed, 104 insertions(+), 101 deletions(-) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index ceb90ca0c4..9119788d0e 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -119,8 +119,12 @@ void ignition::gazebo::setData(QStandardItem *_item, const math::Pose3d &_data) template<> void ignition::gazebo::setData(QStandardItem *_item, const sdf::Light &_data) { - int lightType = 0; - if (_data.Type() == sdf::LightType::SPOT) + int lightType = -1; + if (_data.Type() == sdf::LightType::POINT) + { + lightType = 0; + } + else if (_data.Type() == sdf::LightType::SPOT) { lightType = 1; } @@ -145,13 +149,13 @@ void ignition::gazebo::setData(QStandardItem *_item, const sdf::Light &_data) QVariant(_data.ConstantAttenuationFactor()), QVariant(_data.QuadraticAttenuationFactor()), QVariant(_data.CastShadows()), - QVariant(lightType), QVariant(_data.Direction().X()), QVariant(_data.Direction().Y()), QVariant(_data.Direction().Z()), QVariant(_data.SpotInnerAngle().Radian()), QVariant(_data.SpotOuterAngle().Radian()), - QVariant(_data.SpotFalloff()) + QVariant(_data.SpotFalloff()), + QVariant(lightType) }), ComponentsModel::RoleNames().key("data")); } @@ -536,8 +540,7 @@ void ComponentInspector::Update(const UpdateInfo &, if (this->dataPtr->entity == this->dataPtr->worldEntity) this->dataPtr->worldName = comp->Data(); - else - this->dataPtr->entityName = comp->Data(); + this->dataPtr->entityName = comp->Data(); } else if (typeId == components::ParentEntity::typeId) { @@ -562,6 +565,7 @@ void ComponentInspector::Update(const UpdateInfo &, } else if (typeId == components::Light::typeId) { + this->SetType("light"); auto comp = _ecm.Component(this->dataPtr->entity); if (comp) setData(item, comp->Data()); @@ -791,6 +795,7 @@ void ComponentInspector::OnLight( ignition::msgs::Light req; req.set_name(this->dataPtr->entityName); + req.set_id(this->dataPtr->entity); ignition::msgs::Set(req.mutable_diffuse(), ignition::math::Color(_rDiffuse, _gDiffuse, _bDiffuse, _aDiffuse)); ignition::msgs::Set(req.mutable_specular(), @@ -807,7 +812,8 @@ void ComponentInspector::OnLight( else req.set_type(ignition::msgs::Light::DIRECTIONAL); - if (_type == 1) { // sdf::LightType::SPOT + if (_type == 1) // sdf::LightType::SPOT + { req.set_spot_inner_angle(_innerAngle); req.set_spot_outer_angle(_outerAngle); req.set_spot_falloff(_falloff); @@ -819,7 +825,7 @@ void ComponentInspector::OnLight( ignition::math::Vector3d(_directionX, _directionY, _directionZ)); } - auto lightConfigService = "/world/lights/config"; + auto lightConfigService = "/world/" + this->dataPtr->worldName + "/light/config"; this->dataPtr->node.Request(lightConfigService, req, cb); } diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index b6d94b383c..5a4f5c593b 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -71,7 +71,7 @@ namespace gazebo template<> void setData(QStandardItem *_item, const math::Pose3d &_data); - /// \brief Specialized to set ligth data. + /// \brief Specialized to set light data. /// \param[in] _item Item whose data will be set. /// \param[in] _data Data to set. template<> @@ -228,7 +228,14 @@ namespace gazebo /// \param[in] _attLinear Linear attenuation /// \param[in] _attConstant Constant attenuation /// \param[in] _attQuadratic Quadratic attenuation - /// \param[in] _castShadows Cast Shadows attenuation + /// \param[in] _castShadows Specify if this light should cast shadows + /// \param[in] _directionX X direction of the light + /// \param[in] _directionY Y direction of the light + /// \param[in] _directionZ Z direction of the light + /// \param[in] _innerAngle Inner angle of the spotlight + /// \param[in] _outerAngle Outer angle of the spotlight + /// \param[in] _falloff Falloff of the spotlight + /// \param[in] _type light type public: Q_INVOKABLE void OnLight( double _rSpecular, double _gSpecular, double _bSpecular, double _aSpecular, double _rDiffuse, double _gDiffuse, diff --git a/src/gui/plugins/component_inspector/Light.qml b/src/gui/plugins/component_inspector/Light.qml index 01ece47701..f48315564c 100644 --- a/src/gui/plugins/component_inspector/Light.qml +++ b/src/gui/plugins/component_inspector/Light.qml @@ -23,7 +23,7 @@ import QtQuick.Controls.Styles 1.4 import "qrc:/ComponentInspector" import "qrc:/qml" -// Item displaying 3D pose information. +// Item displaying light information. Rectangle { height: header.height + content.height width: componentInspector.width @@ -35,14 +35,6 @@ Rectangle { // Horizontal margins property int margin: 5 - // Maximum spinbox value - property double spinMax: 1 - - // Read-only / write - property bool readOnly: { - return false; - } - property int iconWidth: 20 property int iconHeight: 20 @@ -103,7 +95,7 @@ Rectangle { // Loaded item for falloff (spotlight) property var falloffItem: {} - // Send new pose to C++ + // Send new light data to C++ function sendLight() { // TODO(anyone) There's a loss of precision when these values get to C++ componentInspector.onLight( @@ -126,7 +118,7 @@ Rectangle { innerAngleItem.value, outerAngleItem.value, falloffItem.value, - model.data[13] + model.data[19] ); } @@ -144,7 +136,7 @@ Rectangle { id: writableSpin value: writableSpin.activeFocus ? writableSpin.value : numberValue minimumValue: 0 - maximumValue: spinMax + maximumValue: 1 decimals: 6 onEditingFinished: { sendLight() @@ -164,19 +156,6 @@ Rectangle { } } } - Component { - id: spinAngle - IgnSpinBox { - id: writableSpin - value: writableSpin.activeFocus ? writableSpin.value : numberValue - minimumValue: -3.1416 - maximumValue: 3.1416 - decimals: 6 - onEditingFinished: { - sendLight() - } - } - } Component { id: spinNoLimit IgnSpinBox { @@ -191,9 +170,6 @@ Rectangle { } } - /** - * Used to create a read-only number - */ Component { id: readOnlyNumber Text { @@ -279,7 +255,7 @@ Rectangle { Text { Layout.columnSpan: 6 - text: "Specular" + text: " Specular" color: "dimgrey" width: margin + indentation } @@ -474,7 +450,7 @@ Rectangle { Text { Layout.columnSpan: 6 - text: "Diffuse" + text: " Diffuse" color: "dimgrey" width: margin + indentation } @@ -635,7 +611,7 @@ Rectangle { Text { Layout.columnSpan: 6 - text: "Attenuation" + text: " Attenuation" color: "dimgrey" width: margin + indentation } @@ -834,22 +810,22 @@ Rectangle { } Text { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 Layout.columnSpan: 6 - text: "Direction" + text: " Direction" color: "dimgrey" width: margin + indentation } // Left spacer Item { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 Layout.rowSpan: 3 width: margin + indentation } Rectangle { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 color: "transparent" height: 40 Layout.preferredWidth: xDirectionText.width + indentation*3 @@ -863,7 +839,7 @@ Rectangle { Component.onCompleted: loaderDirectionX.item.componentInfo = "X direction" Text { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 id : xDirectionText text: ' X:' leftPadding: 5 @@ -873,14 +849,14 @@ Rectangle { } } Item { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 Layout.fillWidth: true height: 40 Layout.columnSpan: 4 Loader { id: xDirectionLoader anchors.fill: parent - property double numberValue: model.data[14] + property double numberValue: model.data[13] sourceComponent: spinNoLimit onLoaded: { directionXItem = xDirectionLoader.item @@ -889,7 +865,7 @@ Rectangle { } Rectangle { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 color: "transparent" height: 40 Layout.preferredWidth: yDirectionText.width + indentation*3 @@ -903,7 +879,7 @@ Rectangle { Component.onCompleted: loaderDirectionY.item.componentInfo = "Y direction" Text { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 id : yDirectionText text: ' Y:' leftPadding: 5 @@ -913,14 +889,14 @@ Rectangle { } } Item { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 Layout.fillWidth: true height: 40 Layout.columnSpan: 4 Loader { id: yDirectionLoader anchors.fill: parent - property double numberValue: model.data[15] + property double numberValue: model.data[14] sourceComponent: spinNoLimit onLoaded: { directionYItem = yDirectionLoader.item @@ -929,7 +905,7 @@ Rectangle { } Rectangle { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 color: "transparent" height: 40 Layout.preferredWidth: zDirectionText.width + indentation*3 @@ -943,7 +919,7 @@ Rectangle { Component.onCompleted: loaderDirectionZ.item.componentInfo = "Z direction" Text { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 id : zDirectionText text: ' Z:' leftPadding: 5 @@ -953,14 +929,14 @@ Rectangle { } } Item { - visible: model.data[13] === 1 || model.data[13] === 2 + visible: model.data[19] === 1 || model.data[19] === 2 Layout.fillWidth: true height: 40 Layout.columnSpan: 4 Loader { id: zDirectionLoader anchors.fill: parent - property double numberValue: model.data[16] + property double numberValue: model.data[15] sourceComponent: spinNoLimit onLoaded: { directionZItem = zDirectionLoader.item @@ -969,22 +945,22 @@ Rectangle { } Text { - visible: model.data[13] === 1 + visible: model.data[19] === 1 Layout.columnSpan: 6 - text: "Spot features" + text: " Spot features" color: "dimgrey" width: margin + indentation } // Left spacer Item { - visible: model.data[13] === 1 + visible: model.data[19] === 1 Layout.rowSpan: 3 width: margin + indentation } Rectangle { - visible: model.data[13] === 1 + visible: model.data[19] === 1 color: "transparent" height: 40 Layout.preferredWidth: innerAngleText.width + indentation*3 @@ -998,7 +974,7 @@ Rectangle { Component.onCompleted: loaderInnerAngle.item.componentInfo = "Inner Angle" Text { - visible: model.data[13] === 1 + visible: model.data[19] === 1 id : innerAngleText text: ' Inner Angle:' leftPadding: 5 @@ -1008,15 +984,15 @@ Rectangle { } } Item { - visible: model.data[13] === 1 + visible: model.data[19] === 1 Layout.fillWidth: true height: 40 Layout.columnSpan: 4 Loader { id: innerAngleLoader anchors.fill: parent - property double numberValue: model.data[17] - sourceComponent: spinAngle + property double numberValue: model.data[16] + sourceComponent: spinNoLimit onLoaded: { innerAngleItem = innerAngleLoader.item } @@ -1024,7 +1000,7 @@ Rectangle { } Rectangle { - visible: model.data[13] === 1 + visible: model.data[19] === 1 color: "transparent" height: 40 Layout.preferredWidth: outerAngleText.width + indentation*3 @@ -1038,7 +1014,7 @@ Rectangle { Component.onCompleted: loaderOuterAngle.item.componentInfo = "Outer Angle" Text { - visible: model.data[13] === 1 + visible: model.data[19] === 1 id : outerAngleText text: ' Outer angle:' leftPadding: 5 @@ -1048,22 +1024,22 @@ Rectangle { } } Item { - visible: model.data[13] === 1 + visible: model.data[19] === 1 Layout.fillWidth: true height: 40 Layout.columnSpan: 4 Loader { id: outerAngleLoader anchors.fill: parent - property double numberValue: model.data[18] - sourceComponent: spinAngle + property double numberValue: model.data[17] + sourceComponent: spinNoLimit onLoaded: { outerAngleItem = outerAngleLoader.item } } } Rectangle { - visible: model.data[13] === 1 + visible: model.data[19] === 1 color: "transparent" height: 40 Layout.preferredWidth: fallOffText.width + indentation*3 @@ -1077,7 +1053,7 @@ Rectangle { Component.onCompleted: loaderFallOff.item.componentInfo = "Spot falloff" Text { - visible: model.data[13] === 1 + visible: model.data[19] === 1 id : fallOffText text: ' Falloff:' leftPadding: 5 @@ -1087,14 +1063,14 @@ Rectangle { } } Item { - visible: model.data[13] === 1 + visible: model.data[19] === 1 Layout.fillWidth: true height: 40 Layout.columnSpan: 4 Loader { id: fallOffLoader anchors.fill: parent - property double numberValue: model.data[19] + property double numberValue: model.data[18] sourceComponent: spinZeroMax onLoaded: { falloffItem = fallOffLoader.item diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 3f7b5c9215..263bed9d38 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -448,17 +448,25 @@ void RenderUtil::Update() l->SetSpecularColor(light.second.Specular()); if (ignition::math::equal( l->AttenuationRange(), light.second.AttenuationRange())) + { l->SetAttenuationRange(light.second.AttenuationRange()); + } if (ignition::math::equal( l->AttenuationLinear(), light.second.LinearAttenuationFactor())) + { l->SetAttenuationLinear(light.second.LinearAttenuationFactor()); + } if (ignition::math::equal( l->AttenuationConstant(), light.second.ConstantAttenuationFactor())) + { l->SetAttenuationConstant(light.second.ConstantAttenuationFactor()); + } if (ignition::math::equal( l->AttenuationQuadratic(), light.second.QuadraticAttenuationFactor())) + { l->SetAttenuationQuadratic(light.second.QuadraticAttenuationFactor()); + } if (l->CastShadows() != light.second.CastShadows()) l->SetCastShadows(light.second.CastShadows()); auto lDirectional = @@ -479,9 +487,10 @@ void RenderUtil::Update() if (lSpotLight->OuterAngle() != light.second.SpotOuterAngle()) lSpotLight->SetOuterAngle(light.second.SpotOuterAngle()); if (ignition::math::equal( - lSpotLight->Falloff(), - light.second.SpotFalloff())) + lSpotLight->Falloff(), light.second.SpotFalloff())) + { lSpotLight->SetFalloff(light.second.SpotFalloff()); + } } } } diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 8c5899483f..6ac247a3e3 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -19,8 +19,8 @@ #include #include -#include #include +#include #include #include @@ -129,7 +129,7 @@ class RemoveCommand : public UserCommandBase class LightCommand : public UserCommandBase { /// \brief Constructor - /// \param[in] _msg Message identifying the entity to be removed. + /// \param[in] _msg Message identifying the entity to be edited. /// \param[in] _iface Pointer to user commands interface. public: LightCommand(msgs::Light *_msg, std::shared_ptr &_iface); @@ -196,7 +196,7 @@ class ignition::gazebo::systems::UserCommandsPrivate /// \brief Callback for light service /// \param[in] _req Request containing light update of an entity. /// \param[in] _res True if message successfully received and queued. - /// It does not mean that the entity will be successfully moved. + /// It does not mean that the light will be successfully updated. /// \return True if successful. public: bool LightService(const msgs::Light &_req, msgs::Boolean &_res); @@ -271,12 +271,12 @@ void UserCommands::Configure(const Entity &_entity, ignmsg << "Pose service on [" << poseService << "]" << std::endl; - // Pose service + // Light service std::string lightService{"/world/" + worldName + "/config"}; this->dataPtr->node.Advertise(lightService, &UserCommandsPrivate::LightService, this->dataPtr.get()); - ignmsg << "Pose service on [" << lightService << "]" << std::endl; + ignmsg << "Light service on [" << lightService << "]" << std::endl; } ////////////////////////////////////////////////// @@ -689,59 +689,64 @@ LightCommand::LightCommand(msgs::Light *_msg, ////////////////////////////////////////////////// bool LightCommand::Execute() { - auto LightMsg = dynamic_cast(this->msg); - if (nullptr == LightMsg) + auto lightMsg = dynamic_cast(this->msg); + if (nullptr == lightMsg) { ignerr << "Internal error, null create message" << std::endl; return false; } auto entity = this->iface->ecm->EntityByComponents( - components::Name(LightMsg->name()), + components::Name(lightMsg->name()), components::ParentEntity(this->iface->worldEntity)); auto lightComp = this->iface->ecm->Component(entity); if (nullptr == lightComp) entity = kNullEntity; - if (!entity) { - ignmsg << "Light component not available" << std::endl; + if (!entity) + { + ignmsg << "Failed to find light entity named [" << lightMsg->name() << "]." << std::endl; return false; } - lightComp->Data().SetDiffuse(msgs::Convert(LightMsg->diffuse())); - lightComp->Data().SetSpecular(msgs::Convert(LightMsg->specular())); - lightComp->Data().SetAttenuationRange(LightMsg->range()); - lightComp->Data().SetLinearAttenuationFactor(LightMsg->attenuation_linear()); + lightComp->Data().SetDiffuse(msgs::Convert(lightMsg->diffuse())); + lightComp->Data().SetSpecular(msgs::Convert(lightMsg->specular())); + lightComp->Data().SetAttenuationRange(lightMsg->range()); + lightComp->Data().SetLinearAttenuationFactor(lightMsg->attenuation_linear()); lightComp->Data().SetConstantAttenuationFactor( - LightMsg->attenuation_constant()); + lightMsg->attenuation_constant()); lightComp->Data().SetQuadraticAttenuationFactor( - LightMsg->attenuation_quadratic()); - lightComp->Data().SetCastShadows(LightMsg->cast_shadows()); + lightMsg->attenuation_quadratic()); + lightComp->Data().SetCastShadows(lightMsg->cast_shadows()); - if (LightMsg->type() != ignition::msgs::Light::POINT) { - lightComp->Data().SetDirection(msgs::Convert(LightMsg->direction())); + if (lightMsg->type() != ignition::msgs::Light::POINT) + { + lightComp->Data().SetDirection(msgs::Convert(lightMsg->direction())); } - if (LightMsg->type() == ignition::msgs::Light::SPOT) { + if (lightMsg->type() == ignition::msgs::Light::SPOT) + { lightComp->Data().SetSpotInnerAngle( - ignition::math::Angle(LightMsg->spot_inner_angle())); + ignition::math::Angle(lightMsg->spot_inner_angle())); lightComp->Data().SetSpotOuterAngle( - ignition::math::Angle(LightMsg->spot_outer_angle())); - lightComp->Data().SetSpotFalloff(LightMsg->spot_falloff()); + ignition::math::Angle(lightMsg->spot_outer_angle())); + lightComp->Data().SetSpotFalloff(lightMsg->spot_falloff()); } auto lightPose = this->iface->ecm->Component(entity); if (nullptr == lightPose) entity = kNullEntity; - if (!entity) { + if (!entity) + { ignmsg << "Pose component not available" << std::endl; return false; } - if (LightMsg->has_pose()) { - lightPose->Data().Pos() = msgs::Convert(LightMsg->pose()).Pos(); + if (lightMsg->has_pose()) + { + lightPose->Data().Pos() = msgs::Convert(lightMsg->pose()).Pos(); } this->iface->ecm->SetChanged(entity, From 6609c2609d529abc38b0628361366470e211ad48 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 15 Dec 2020 17:51:04 +0100 Subject: [PATCH 07/42] make linters happy Signed-off-by: ahcorde --- src/gui/plugins/component_inspector/ComponentInspector.cc | 3 ++- src/systems/user_commands/UserCommands.cc | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 9119788d0e..4a6da95da8 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -825,7 +825,8 @@ void ComponentInspector::OnLight( ignition::math::Vector3d(_directionX, _directionY, _directionZ)); } - auto lightConfigService = "/world/" + this->dataPtr->worldName + "/light/config"; + auto lightConfigService = "/world/" + this->dataPtr->worldName + + "/light/config"; this->dataPtr->node.Request(lightConfigService, req, cb); } diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 6ac247a3e3..39335e075e 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -706,7 +706,8 @@ bool LightCommand::Execute() if (!entity) { - ignmsg << "Failed to find light entity named [" << lightMsg->name() << "]." << std::endl; + ignmsg << "Failed to find light entity named [" << lightMsg->name() + << "]." << std::endl; return false; } From f8519aeaefc8086acb19042bdea2d40c39f8caf5 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 15 Dec 2020 19:14:26 +0100 Subject: [PATCH 08/42] Added light user commands tests Signed-off-by: ahcorde --- test/integration/user_commands.cc | 214 ++++++++++++++++++++++++++++++ test/worlds/lights.sdf | 5 +- 2 files changed, 218 insertions(+), 1 deletion(-) diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 84c6f2fc3e..6fdcd20248 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -18,6 +18,7 @@ #include #include +#include #include #include @@ -671,3 +672,216 @@ TEST_F(UserCommandsTest, Pose) ASSERT_NE(nullptr, poseComp); EXPECT_NEAR(500.0, poseComp->Data().Pos().Y(), 0.2); } + +///////////////////////////////////////////////// +TEST_F(UserCommandsTest, Light) +{ + // Start server + ServerConfig serverConfig; + const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + + "/test/worlds/lights.sdf"; + serverConfig.SetSdfFile(sdfFile); + + Server server(serverConfig); + EXPECT_FALSE(server.Running()); + EXPECT_FALSE(*server.Running(0)); + + // Create a system just to get the ECM + EntityComponentManager *ecm{nullptr}; + test::Relay testSystem; + testSystem.OnPreUpdate([&](const gazebo::UpdateInfo &, + gazebo::EntityComponentManager &_ecm) + { + ecm = &_ecm; + }); + + server.AddSystem(testSystem.systemPtr); + + // Run server and check we have the ECM + EXPECT_EQ(nullptr, ecm); + server.Run(true, 1, false); + EXPECT_NE(nullptr, ecm); + + msgs::Light req; + req.set_name("point"); + + msgs::Boolean res; + bool result; + unsigned int timeout = 1000; + std::string service{"/world/lights/config"}; + + transport::Node node; + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + // Point light + auto pointLightEntity = ecm->EntityByComponents(components::Name("point")); + EXPECT_NE(kNullEntity, pointLightEntity); + + // Check entity has not been moved yet + auto pointLightComp = ecm->Component(pointLightEntity); + ASSERT_NE(nullptr, pointLightComp); + EXPECT_EQ(math::Pose3d(0, -1.5, 3, 0, 0, 0), pointLightComp->Data().RawPose()); + EXPECT_EQ(math::Color(1, 0, 0, 1), pointLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.1, 0.1, 0.1, 1), pointLightComp->Data().Specular()); + EXPECT_NEAR(4.0, pointLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.5, pointLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.2, pointLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(0.01, pointLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_FALSE(pointLightComp->Data().CastShadows()); + + req.Clear(); + ignition::msgs::Set(req.mutable_diffuse(), + ignition::math::Color(0, 1, 1, 0)); + ignition::msgs::Set(req.mutable_specular(), + ignition::math::Color(0.2, 0.2, 0.2, 0.2)); + req.set_range(2.6); + req.set_name("point"); + req.set_type(ignition::msgs::Light::POINT); + req.set_attenuation_linear(0.7); + req.set_attenuation_constant(0.6); + req.set_attenuation_quadratic(0.001); + req.set_cast_shadows(true); + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 1, false); + // Sleep for a small duration to allow Run thread to start + IGN_SLEEP_MS(10); + + pointLightComp = ecm->Component(pointLightEntity); + ASSERT_NE(nullptr, pointLightComp); + + EXPECT_EQ(math::Color(0, 1, 1, 0), pointLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.2, 0.2, 0.2, 0.2), + pointLightComp->Data().Specular()); + EXPECT_NEAR(2.6, pointLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.7, pointLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.6, pointLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(0.001, pointLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_TRUE(pointLightComp->Data().CastShadows()); + + // directional light + auto directionalLightEntity = ecm->EntityByComponents( + components::Name("directional")); + EXPECT_NE(kNullEntity, directionalLightEntity); + + // Check entity has not been moved yet + auto directionalLightComp = + ecm->Component(directionalLightEntity); + ASSERT_NE(nullptr, directionalLightComp); + + EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), directionalLightComp->Data().RawPose()); + EXPECT_EQ(math::Color(0.8, 0.8, 0.8, 1), directionalLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.2, 0.2, 0.2, 1), directionalLightComp->Data().Specular()); + EXPECT_NEAR(100, directionalLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.01, directionalLightComp->Data().LinearAttenuationFactor(), 0.01); + EXPECT_NEAR(0.9, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(0.001, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.001); + EXPECT_EQ(math::Vector3d(0.5, 0.2, -0.9), directionalLightComp->Data().Direction()); + EXPECT_TRUE(directionalLightComp->Data().CastShadows()); + + req.Clear(); + ignition::msgs::Set(req.mutable_diffuse(), + ignition::math::Color(0, 1, 1, 0)); + ignition::msgs::Set(req.mutable_specular(), + ignition::math::Color(0.3, 0.3, 0.3, 0.3)); + req.set_range(2.6); + req.set_name("directional"); + req.set_type(ignition::msgs::Light::DIRECTIONAL); + req.set_attenuation_linear(0.7); + req.set_attenuation_constant(0.6); + req.set_attenuation_quadratic(1); + req.set_cast_shadows(false); + ignition::msgs::Set(req.mutable_direction(), + ignition::math::Vector3d(1, 2, 3)); + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 1, false); + // Sleep for a small duration to allow Run thread to start + IGN_SLEEP_MS(10); + + directionalLightComp = ecm->Component(directionalLightEntity); + ASSERT_NE(nullptr, directionalLightComp); + + EXPECT_EQ(math::Color(0, 1, 1, 0), directionalLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.3, 0.3, 0.3, 0.3), + directionalLightComp->Data().Specular()); + EXPECT_NEAR(2.6, directionalLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.7, directionalLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.6, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(1, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_EQ(math::Vector3d(1, 2, 3), directionalLightComp->Data().Direction()); + EXPECT_FALSE(directionalLightComp->Data().CastShadows()); + + // spot light + auto spotLightEntity = ecm->EntityByComponents( + components::Name("spot")); + EXPECT_NE(kNullEntity, spotLightEntity); + + // Check entity has not been moved yet + auto spotLightComp = + ecm->Component(spotLightEntity); + ASSERT_NE(nullptr, spotLightComp); + + EXPECT_EQ(math::Pose3d(0, 1.5, 3, 0, 0, 0), spotLightComp->Data().RawPose()); + EXPECT_EQ(math::Color(0, 1, 0, 1), spotLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.2, 0.2, 0.2, 1), spotLightComp->Data().Specular()); + EXPECT_NEAR(5, spotLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.4, spotLightComp->Data().LinearAttenuationFactor(), 0.01); + EXPECT_NEAR(0.3, spotLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.001, spotLightComp->Data().QuadraticAttenuationFactor(), 0.001); + EXPECT_EQ(math::Vector3d(0, 0, -1), spotLightComp->Data().Direction()); + EXPECT_FALSE(spotLightComp->Data().CastShadows()); + EXPECT_NEAR(0.1, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); + EXPECT_NEAR(0.5, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); + EXPECT_NEAR(0.8, spotLightComp->Data().SpotFalloff(), 0.1); + + req.Clear(); + ignition::msgs::Set(req.mutable_diffuse(), + ignition::math::Color(1, 0, 1, 0)); + ignition::msgs::Set(req.mutable_specular(), + ignition::math::Color(0.3, 0.3, 0.3, 0.3)); + req.set_range(2.6); + req.set_name("spot"); + req.set_type(ignition::msgs::Light::SPOT); + req.set_attenuation_linear(0.7); + req.set_attenuation_constant(0.6); + req.set_attenuation_quadratic(1); + req.set_cast_shadows(true); + ignition::msgs::Set(req.mutable_direction(), + ignition::math::Vector3d(1, 2, 3)); + req.set_spot_inner_angle(1.5); + req.set_spot_outer_angle(0.3); + req.set_spot_falloff(0.9); + + EXPECT_TRUE(node.Request(service, req, timeout, res, result)); + EXPECT_TRUE(result); + EXPECT_TRUE(res.data()); + + server.Run(true, 1, false); + // Sleep for a small duration to allow Run thread to start + IGN_SLEEP_MS(10); + + spotLightComp = ecm->Component(spotLightEntity); + ASSERT_NE(nullptr, spotLightComp); + + EXPECT_EQ(math::Color(1, 0, 1, 0), spotLightComp->Data().Diffuse()); + EXPECT_EQ(math::Color(0.3, 0.3, 0.3, 0.3), + spotLightComp->Data().Specular()); + EXPECT_NEAR(2.6, spotLightComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.7, spotLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.6, spotLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(1, spotLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_EQ(math::Vector3d(1, 2, 3), spotLightComp->Data().Direction()); + EXPECT_TRUE(spotLightComp->Data().CastShadows()); + EXPECT_NEAR(1.5, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); + EXPECT_NEAR(0.3, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); + EXPECT_NEAR(0.9, spotLightComp->Data().SpotFalloff(), 0.1); + +} diff --git a/test/worlds/lights.sdf b/test/worlds/lights.sdf index 5454c28fd6..a8aa63006c 100644 --- a/test/worlds/lights.sdf +++ b/test/worlds/lights.sdf @@ -13,7 +13,10 @@ filename="ignition-gazebo-scene-broadcaster-system" name="ignition::gazebo::systems::SceneBroadcaster"> - + + true 0 0 10 0 0 0 From 248af9e54e80f98de693b68f00221d895ec4332d Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 15 Dec 2020 19:55:32 +0100 Subject: [PATCH 09/42] make linters happy Signed-off-by: ahcorde --- test/integration/user_commands.cc | 37 ++++++++++++++++++++----------- 1 file changed, 24 insertions(+), 13 deletions(-) diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 6fdcd20248..e671182f88 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -722,7 +722,8 @@ TEST_F(UserCommandsTest, Light) // Check entity has not been moved yet auto pointLightComp = ecm->Component(pointLightEntity); ASSERT_NE(nullptr, pointLightComp); - EXPECT_EQ(math::Pose3d(0, -1.5, 3, 0, 0, 0), pointLightComp->Data().RawPose()); + EXPECT_EQ( + math::Pose3d(0, -1.5, 3, 0, 0, 0), pointLightComp->Data().RawPose()); EXPECT_EQ(math::Color(1, 0, 0, 1), pointLightComp->Data().Diffuse()); EXPECT_EQ(math::Color(0.1, 0.1, 0.1, 1), pointLightComp->Data().Specular()); EXPECT_NEAR(4.0, pointLightComp->Data().AttenuationRange(), 0.1); @@ -773,14 +774,21 @@ TEST_F(UserCommandsTest, Light) ecm->Component(directionalLightEntity); ASSERT_NE(nullptr, directionalLightComp); - EXPECT_EQ(math::Pose3d(0, 0, 10, 0, 0, 0), directionalLightComp->Data().RawPose()); - EXPECT_EQ(math::Color(0.8, 0.8, 0.8, 1), directionalLightComp->Data().Diffuse()); - EXPECT_EQ(math::Color(0.2, 0.2, 0.2, 1), directionalLightComp->Data().Specular()); + EXPECT_EQ( + math::Pose3d(0, 0, 10, 0, 0, 0), directionalLightComp->Data().RawPose()); + EXPECT_EQ( + math::Color(0.8, 0.8, 0.8, 1), directionalLightComp->Data().Diffuse()); + EXPECT_EQ( + math::Color(0.2, 0.2, 0.2, 1), directionalLightComp->Data().Specular()); EXPECT_NEAR(100, directionalLightComp->Data().AttenuationRange(), 0.1); - EXPECT_NEAR(0.01, directionalLightComp->Data().LinearAttenuationFactor(), 0.01); - EXPECT_NEAR(0.9, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); - EXPECT_NEAR(0.001, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.001); - EXPECT_EQ(math::Vector3d(0.5, 0.2, -0.9), directionalLightComp->Data().Direction()); + EXPECT_NEAR( + 0.01, directionalLightComp->Data().LinearAttenuationFactor(), 0.01); + EXPECT_NEAR( + 0.9, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.001, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.001); + EXPECT_EQ( + math::Vector3d(0.5, 0.2, -0.9), directionalLightComp->Data().Direction()); EXPECT_TRUE(directionalLightComp->Data().CastShadows()); req.Clear(); @@ -805,16 +813,20 @@ TEST_F(UserCommandsTest, Light) // Sleep for a small duration to allow Run thread to start IGN_SLEEP_MS(10); - directionalLightComp = ecm->Component(directionalLightEntity); + directionalLightComp = + ecm->Component(directionalLightEntity); ASSERT_NE(nullptr, directionalLightComp); EXPECT_EQ(math::Color(0, 1, 1, 0), directionalLightComp->Data().Diffuse()); EXPECT_EQ(math::Color(0.3, 0.3, 0.3, 0.3), directionalLightComp->Data().Specular()); EXPECT_NEAR(2.6, directionalLightComp->Data().AttenuationRange(), 0.1); - EXPECT_NEAR(0.7, directionalLightComp->Data().LinearAttenuationFactor(), 0.1); - EXPECT_NEAR(0.6, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); - EXPECT_NEAR(1, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.7, directionalLightComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR( + 0.6, directionalLightComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR( + 1, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.1); EXPECT_EQ(math::Vector3d(1, 2, 3), directionalLightComp->Data().Direction()); EXPECT_FALSE(directionalLightComp->Data().CastShadows()); @@ -883,5 +895,4 @@ TEST_F(UserCommandsTest, Light) EXPECT_NEAR(1.5, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); EXPECT_NEAR(0.3, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); EXPECT_NEAR(0.9, spotLightComp->Data().SpotFalloff(), 0.1); - } From 9823e741e360ca0ce0d4dfebdb513ab1645a6b03 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 16 Dec 2020 19:46:18 +0100 Subject: [PATCH 10/42] Allow to plot Light values with the plotting plugin Signed-off-by: ahcorde --- src/gui/plugins/component_inspector/Light.qml | 38 +++++----- src/gui/plugins/plotting/Plotting.cc | 71 +++++++++++++++++++ src/gui/plugins/plotting/Plotting.hh | 8 +++ 3 files changed, 98 insertions(+), 19 deletions(-) diff --git a/src/gui/plugins/component_inspector/Light.qml b/src/gui/plugins/component_inspector/Light.qml index f48315564c..6a23e997e7 100644 --- a/src/gui/plugins/component_inspector/Light.qml +++ b/src/gui/plugins/component_inspector/Light.qml @@ -306,7 +306,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderSpecularR.item.componentInfo = "r" + Component.onCompleted: loaderSpecularR.item.componentInfo = "specularR" Text { id : rSpecularText @@ -341,7 +341,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderSpecularG.item.componentInfo = "g" + Component.onCompleted: loaderSpecularG.item.componentInfo = "specularG" Text { id : gSpecularText @@ -383,7 +383,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderSpecularB.item.componentInfo = "b" + Component.onCompleted: loaderSpecularB.item.componentInfo = "specularB" Text { id : bSpecularText @@ -418,7 +418,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderSpecularA.item.componentInfo = "a" + Component.onCompleted: loaderSpecularA.item.componentInfo = "specularA" Text { id : aSpecularText @@ -472,7 +472,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderDiffuseR.item.componentInfo = "r" + Component.onCompleted: loaderDiffuseR.item.componentInfo = "diffuseR" Text { id : rDiffuseText @@ -507,7 +507,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderDiffuseG.item.componentInfo = "g" + Component.onCompleted: loaderDiffuseG.item.componentInfo = "diffuseG" Text { id : gDiffuseText @@ -549,7 +549,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderDiffuseB.item.componentInfo = "b" + Component.onCompleted: loaderDiffuseB.item.componentInfo = "diffuseB" Text { id : bDiffuseText @@ -584,7 +584,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderDiffuseA.item.componentInfo = "a" + Component.onCompleted: loaderDiffuseA.item.componentInfo = "diffuseA" Text { id : aDiffuseText @@ -633,7 +633,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderAttRange.item.componentInfo = "Attenuation Range" + Component.onCompleted: loaderAttRange.item.componentInfo = "attRange" Text { id : attRangeText @@ -669,7 +669,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderAttLinear.item.componentInfo = "Attenuation linear" + Component.onCompleted: loaderAttLinear.item.componentInfo = "attLinear" Text { id : attLinearText @@ -711,7 +711,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderAttConstant.item.componentInfo = "Attenuation constant" + Component.onCompleted: loaderAttConstant.item.componentInfo = "attConstant" Text { id : attConstantText @@ -746,7 +746,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderAttQuadratic.item.componentInfo = "Attenuation quadratic" + Component.onCompleted: loaderAttQuadratic.item.componentInfo = "attQuadratic" Text { id : attQuadraticText @@ -782,7 +782,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderCastShadows.item.componentInfo = "Cast shadows" + Component.onCompleted: loaderCastShadows.item.componentInfo = "castshadows" Text { id : castShadowsText @@ -836,7 +836,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderDirectionX.item.componentInfo = "X direction" + Component.onCompleted: loaderDirectionX.item.componentInfo = "directionX" Text { visible: model.data[19] === 1 || model.data[19] === 2 @@ -876,7 +876,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderDirectionY.item.componentInfo = "Y direction" + Component.onCompleted: loaderDirectionY.item.componentInfo = "directionY" Text { visible: model.data[19] === 1 || model.data[19] === 2 @@ -916,7 +916,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderDirectionZ.item.componentInfo = "Z direction" + Component.onCompleted: loaderDirectionZ.item.componentInfo = "directionZ" Text { visible: model.data[19] === 1 || model.data[19] === 2 @@ -971,7 +971,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderInnerAngle.item.componentInfo = "Inner Angle" + Component.onCompleted: loaderInnerAngle.item.componentInfo = "innerAngle" Text { visible: model.data[19] === 1 @@ -1011,7 +1011,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderOuterAngle.item.componentInfo = "Outer Angle" + Component.onCompleted: loaderOuterAngle.item.componentInfo = "outerAngle" Text { visible: model.data[19] === 1 @@ -1050,7 +1050,7 @@ Rectangle { y:10 sourceComponent: plotIcon } - Component.onCompleted: loaderFallOff.item.componentInfo = "Spot falloff" + Component.onCompleted: loaderFallOff.item.componentInfo = "falloff" Text { visible: model.data[19] === 1 diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index d470f2e3d3..b212e64680 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -23,6 +23,7 @@ #include "ignition/gazebo/components/CastShadows.hh" #include "ignition/gazebo/components/Factory.hh" #include "ignition/gazebo/components/Gravity.hh" +#include "ignition/gazebo/components/Light.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" #include "ignition/gazebo/components/LinearVelocity.hh" #include "ignition/gazebo/components/LinearVelocitySeed.hh" @@ -94,6 +95,28 @@ PlotComponent::PlotComponent(const std::string &_type, this->dataPtr->data["pitch"] = std::make_shared(); this->dataPtr->data["yaw"] = std::make_shared(); } + else if (_type == "Light") + { + this->dataPtr->data["diffuseR"] = std::make_shared(); + this->dataPtr->data["diffuseG"] = std::make_shared(); + this->dataPtr->data["diffuseB"] = std::make_shared(); + this->dataPtr->data["diffuseA"] = std::make_shared(); + this->dataPtr->data["specularR"] = std::make_shared(); + this->dataPtr->data["specularG"] = std::make_shared(); + this->dataPtr->data["specularB"] = std::make_shared(); + this->dataPtr->data["specularA"] = std::make_shared(); + this->dataPtr->data["attRange"] = std::make_shared(); + this->dataPtr->data["attConstant"] = std::make_shared(); + this->dataPtr->data["attLinear"] = std::make_shared(); + this->dataPtr->data["attQuadratic"] = std::make_shared(); + this->dataPtr->data["castshadows"] = std::make_shared(); + this->dataPtr->data["directionX"] = std::make_shared(); + this->dataPtr->data["directionY"] = std::make_shared(); + this->dataPtr->data["directionZ"] = std::make_shared(); + this->dataPtr->data["innerAngle"] = std::make_shared(); + this->dataPtr->data["outerAngle"] = std::make_shared(); + this->dataPtr->data["falloff"] = std::make_shared(); + } else if (_type == "double") this->dataPtr->data["value"] = std::make_shared(); else @@ -203,6 +226,48 @@ void Plotting::SetData(std::string _Id, const ignition::math::Vector3d &_vector) this->dataPtr->components[_Id]->SetAttributeValue("z", _vector.Z()); } +void Plotting::SetData(std::string _Id, const sdf::Light &_light) +{ + this->dataPtr->components[_Id]->SetAttributeValue("diffuseR", + _light.Specular().R()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseG", + _light.Specular().G()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseB", + _light.Specular().B()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseA", + _light.Specular().A()); + this->dataPtr->components[_Id]->SetAttributeValue("specularR", + _light.Diffuse().R()); + this->dataPtr->components[_Id]->SetAttributeValue("specularG", + _light.Diffuse().G()); + this->dataPtr->components[_Id]->SetAttributeValue("specularB", + _light.Diffuse().B()); + this->dataPtr->components[_Id]->SetAttributeValue("specularA", + _light.Diffuse().A()); + this->dataPtr->components[_Id]->SetAttributeValue("attRange", + _light.AttenuationRange()); + this->dataPtr->components[_Id]->SetAttributeValue("attConstant", + _light.LinearAttenuationFactor()); + this->dataPtr->components[_Id]->SetAttributeValue("attLinear", + _light.ConstantAttenuationFactor()); + this->dataPtr->components[_Id]->SetAttributeValue("attQuadratic", + _light.QuadraticAttenuationFactor()); + this->dataPtr->components[_Id]->SetAttributeValue("castshadows", + _light.CastShadows()); + this->dataPtr->components[_Id]->SetAttributeValue("directionX", + _light.Direction().X()); + this->dataPtr->components[_Id]->SetAttributeValue("directionY", + _light.Direction().Y()); + this->dataPtr->components[_Id]->SetAttributeValue("directionZ", + _light.Direction().Z()); + this->dataPtr->components[_Id]->SetAttributeValue("innerAngle", + _light.SpotInnerAngle().Radian()); + this->dataPtr->components[_Id]->SetAttributeValue("outerAngle", + _light.SpotOuterAngle().Radian()); + this->dataPtr->components[_Id]->SetAttributeValue("falloff", + _light.SpotFalloff()); +} + ////////////////////////////////////////////////// void Plotting::SetData(std::string _Id, const ignition::math::Pose3d &_pose) { @@ -382,6 +447,12 @@ void Plotting ::Update(const ignition::gazebo::UpdateInfo &_info, if (comp) this->SetData(component.first, comp->Data()); } + else if (typeId == components::Light::typeId) + { + auto comp = _ecm.Component(entity); + if (comp) + this->SetData(component.first, comp->Data()); + } for (auto attribute : component.second->Data()) { diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index bf9c54c69b..c82ce9762a 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -24,6 +24,8 @@ #include #include +#include + #include #include #include @@ -113,6 +115,12 @@ class Plotting : public ignition::gazebo::GuiSystem public: void SetData(std::string _Id, const ignition::math::Vector3d &_vector); + /// \brief Set the Component data of giving id to the giving vector + /// \param [in] _Id Component Key of the components map + /// \param [in] _vector Vector Data to be set to the component + public: void SetData(std::string _Id, + const sdf::Light &_light); + /// \brief Set the Component data of giving id to the giving pose /// \param [in] _Id Component Key of the components map /// \param [in] _pose Position Data to be set to the component From 89f2791d65a62188621b08239d1f395491843cd9 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 16 Dec 2020 20:20:51 +0100 Subject: [PATCH 11/42] Fixed plotting plugin Signed-off-by: ahcorde --- .../component_inspector/ComponentInspector.cc | 2 +- src/gui/plugins/plotting/Plotting.cc | 20 +++++++++---------- src/systems/user_commands/UserCommands.cc | 2 +- test/integration/user_commands.cc | 2 +- 4 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 4a6da95da8..7e4e5dee29 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -826,7 +826,7 @@ void ComponentInspector::OnLight( } auto lightConfigService = "/world/" + this->dataPtr->worldName + - "/light/config"; + "/light_config"; this->dataPtr->node.Request(lightConfigService, req, cb); } diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index b212e64680..a80b8bde1e 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -228,27 +228,27 @@ void Plotting::SetData(std::string _Id, const ignition::math::Vector3d &_vector) void Plotting::SetData(std::string _Id, const sdf::Light &_light) { - this->dataPtr->components[_Id]->SetAttributeValue("diffuseR", + this->dataPtr->components[_Id]->SetAttributeValue("specularR", _light.Specular().R()); - this->dataPtr->components[_Id]->SetAttributeValue("diffuseG", + this->dataPtr->components[_Id]->SetAttributeValue("specularG", _light.Specular().G()); - this->dataPtr->components[_Id]->SetAttributeValue("diffuseB", + this->dataPtr->components[_Id]->SetAttributeValue("specularB", _light.Specular().B()); - this->dataPtr->components[_Id]->SetAttributeValue("diffuseA", + this->dataPtr->components[_Id]->SetAttributeValue("specularA", _light.Specular().A()); - this->dataPtr->components[_Id]->SetAttributeValue("specularR", + this->dataPtr->components[_Id]->SetAttributeValue("diffuseR", _light.Diffuse().R()); - this->dataPtr->components[_Id]->SetAttributeValue("specularG", + this->dataPtr->components[_Id]->SetAttributeValue("diffuseG", _light.Diffuse().G()); - this->dataPtr->components[_Id]->SetAttributeValue("specularB", + this->dataPtr->components[_Id]->SetAttributeValue("diffuseB", _light.Diffuse().B()); - this->dataPtr->components[_Id]->SetAttributeValue("specularA", + this->dataPtr->components[_Id]->SetAttributeValue("diffuseA", _light.Diffuse().A()); this->dataPtr->components[_Id]->SetAttributeValue("attRange", _light.AttenuationRange()); - this->dataPtr->components[_Id]->SetAttributeValue("attConstant", - _light.LinearAttenuationFactor()); this->dataPtr->components[_Id]->SetAttributeValue("attLinear", + _light.LinearAttenuationFactor()); + this->dataPtr->components[_Id]->SetAttributeValue("attConstant", _light.ConstantAttenuationFactor()); this->dataPtr->components[_Id]->SetAttributeValue("attQuadratic", _light.QuadraticAttenuationFactor()); diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 39335e075e..7117b65d10 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -272,7 +272,7 @@ void UserCommands::Configure(const Entity &_entity, ignmsg << "Pose service on [" << poseService << "]" << std::endl; // Light service - std::string lightService{"/world/" + worldName + "/config"}; + std::string lightService{"/world/" + worldName + "/light_config"}; this->dataPtr->node.Advertise(lightService, &UserCommandsPrivate::LightService, this->dataPtr.get()); diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index e671182f88..b8227cf3f2 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -708,7 +708,7 @@ TEST_F(UserCommandsTest, Light) msgs::Boolean res; bool result; unsigned int timeout = 1000; - std::string service{"/world/lights/config"}; + std::string service{"/world/lights/light_config"}; transport::Node node; EXPECT_TRUE(node.Request(service, req, timeout, res, result)); From 55e20e605ab3d656d18cb4530cce91501c62f704 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 17 Dec 2020 00:33:39 +0100 Subject: [PATCH 12/42] Added feedback Signed-off-by: ahcorde --- include/ignition/gazebo/Model.hh | 8 +++ .../ignition/gazebo/components/LightCmd.hh | 45 ++++++++++++++++ src/Model.cc | 19 +++++++ .../component_inspector/ComponentInspector.cc | 7 +++ src/gui/plugins/plotting/Plotting.cc | 7 +++ src/gui/plugins/plotting/Plotting.hh | 4 +- src/systems/user_commands/UserCommands.cc | 49 +++++++++++++++++- test/integration/model.cc | 51 +++++++++++++++++++ 8 files changed, 186 insertions(+), 4 deletions(-) create mode 100644 include/ignition/gazebo/components/LightCmd.hh diff --git a/include/ignition/gazebo/Model.hh b/include/ignition/gazebo/Model.hh index 89450cb45c..573e5ce2b4 100644 --- a/include/ignition/gazebo/Model.hh +++ b/include/ignition/gazebo/Model.hh @@ -28,6 +28,8 @@ #include #include +#include + namespace ignition { namespace gazebo @@ -169,6 +171,12 @@ namespace ignition public: void SetWorldPoseCmd(EntityComponentManager &_ecm, const math::Pose3d &_pose); + /// \brief Set a command to change the light. + /// \param[in] _ecm Entity-component manager. + /// \param[in] _light New model light. + public: void SetLightCmd(EntityComponentManager &_ecm, + const sdf::Light &_light); + /// \brief Pointer to private data. private: std::unique_ptr dataPtr; }; diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh new file mode 100644 index 0000000000..29991e9e78 --- /dev/null +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2019 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ +#define IGNITION_GAZEBO_COMPONENTS_LIGHTCMD_HH_ + +#include + +#include +#include + +#include +#include "ignition/gazebo/components/Component.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace components +{ + /// \brief A component type that contains commanded pose of an + /// entity in the world frame represented by ignition::math::Pose3d. + using LightCmd = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightCmd", + LightCmd) +} +} +} +} +#endif diff --git a/src/Model.cc b/src/Model.cc index d9776b94a3..f60b90a29f 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -16,6 +16,7 @@ */ #include "ignition/gazebo/components/Joint.hh" +#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" @@ -193,3 +194,21 @@ void Model::SetWorldPoseCmd(EntityComponentManager &_ecm, } } +////////////////////////////////////////////////// +void Model::SetLightCmd(EntityComponentManager &_ecm, + const sdf::Light &_light) +{ + auto lightCmdComp = _ecm.Component( + this->dataPtr->id); + if (!lightCmdComp) + { + _ecm.CreateComponent(this->dataPtr->id, components::LightCmd(_light)); + } + else + { + lightCmdComp->SetData(_light, + [](const sdf::Light &, const sdf::Light &){return false;}); + _ecm.SetChanged(this->dataPtr->id, + components::LightCmd::typeId, ComponentState::OneTimeChange); + } +} diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 7e4e5dee29..87d0d53f8d 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -35,6 +35,7 @@ #include "ignition/gazebo/components/Joint.hh" #include "ignition/gazebo/components/Level.hh" #include "ignition/gazebo/components/Light.hh" +#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" #include "ignition/gazebo/components/LinearVelocity.hh" #include "ignition/gazebo/components/LinearVelocitySeed.hh" @@ -570,6 +571,12 @@ void ComponentInspector::Update(const UpdateInfo &, if (comp) setData(item, comp->Data()); } + else if (typeId == components::LightCmd::typeId) + { + auto comp = _ecm.Component(this->dataPtr->entity); + if (comp) + setData(item, comp->Data()); + } else if (typeId == components::Pose::typeId) { auto comp = _ecm.Component(this->dataPtr->entity); diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index 620ddd7770..f65a7587c2 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -24,6 +24,7 @@ #include "ignition/gazebo/components/Factory.hh" #include "ignition/gazebo/components/Gravity.hh" #include "ignition/gazebo/components/Light.hh" +#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" #include "ignition/gazebo/components/LinearVelocity.hh" #include "ignition/gazebo/components/LinearVelocitySeed.hh" @@ -453,6 +454,12 @@ void Plotting ::Update(const ignition::gazebo::UpdateInfo &_info, if (comp) this->SetData(component.first, comp->Data()); } + else if (typeId == components::LightCmd::typeId) + { + auto comp = _ecm.Component(entity); + if (comp) + this->SetData(component.first, comp->Data()); + } for (auto attribute : component.second->Data()) { diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index c82ce9762a..faab999706 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -115,9 +115,9 @@ class Plotting : public ignition::gazebo::GuiSystem public: void SetData(std::string _Id, const ignition::math::Vector3d &_vector); - /// \brief Set the Component data of giving id to the giving vector + /// \brief Set the Component data of giving id to the giving light /// \param [in] _Id Component Key of the components map - /// \param [in] _vector Vector Data to be set to the component + /// \param [in] _light Vector Data to be set to the component public: void SetData(std::string _Id, const sdf::Light &_light); diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 7117b65d10..115fccd8d5 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -39,6 +39,7 @@ #include "ignition/common/Profiler.hh" #include "ignition/gazebo/components/Light.hh" +#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentEntity.hh" @@ -136,6 +137,27 @@ class LightCommand : public UserCommandBase // Documentation inherited public: bool Execute() final; + + /// \brief Light equality comparison function. + public: std::function + lightEql { [](const sdf::Light &_a, const sdf::Light &_b) + { + return + _a.Type() == _b.Type() && + _a.Name() == _b.Name() && + _a.Diffuse() == _b.Diffuse() && + _a.Specular() == _b.Specular() && + math::equal(_a.AttenuationRange(), _b.AttenuationRange(), 1e-6) && + math::equal(_a.LinearAttenuationFactor(), _b.LinearAttenuationFactor(), 1e-6) && + math::equal(_a.ConstantAttenuationFactor(), _b.ConstantAttenuationFactor(), 1e-6) && + math::equal(_a.ConstantAttenuationFactor(), _b.ConstantAttenuationFactor(), 1e-6) && + math::equal(_a.QuadraticAttenuationFactor(), _b.QuadraticAttenuationFactor(), 1e-6) && + _a.CastShadows() == _b.CastShadows() && + _a.Direction() == _b.Direction() && + _a.SpotInnerAngle() == _b.SpotInnerAngle() && + _a.SpotOuterAngle() == _b.SpotOuterAngle() && + math::equal(_a.SpotFalloff(), _b.SpotFalloff(), 1e-6); + }}; }; /// \brief Command to update an entity's pose transform. @@ -721,6 +743,15 @@ bool LightCommand::Execute() lightMsg->attenuation_quadratic()); lightComp->Data().SetCastShadows(lightMsg->cast_shadows()); + if (lightMsg->type() == ignition::msgs::Light::POINT) + lightComp->Data().SetType(sdf::LightType::POINT); + else if (lightMsg->type() == ignition::msgs::Light::SPOT) + lightComp->Data().SetType(sdf::LightType::SPOT); + else if (lightMsg->type() == ignition::msgs::Light::DIRECTIONAL) + lightComp->Data().SetType(sdf::LightType::DIRECTIONAL); + + lightComp->Data().SetName(lightMsg->name()); + if (lightMsg->type() != ignition::msgs::Light::POINT) { lightComp->Data().SetDirection(msgs::Convert(lightMsg->direction())); @@ -750,8 +781,22 @@ bool LightCommand::Execute() lightPose->Data().Pos() = msgs::Convert(lightMsg->pose()).Pos(); } - this->iface->ecm->SetChanged(entity, - components::Pose::typeId, ComponentState::OneTimeChange); + auto lightCmdComp = + this->iface->ecm->Component(entity); + if (!lightCmdComp) + { + this->iface->ecm->CreateComponent( + entity, components::LightCmd(lightComp->Data())); + } + else + { + /// \todo(anyone) Moving an object is not captured in a log file. + auto state = lightCmdComp->SetData(lightComp->Data(), this->lightEql) ? + ComponentState::OneTimeChange : + ComponentState::NoChange; + this->iface->ecm->SetChanged(entity, components::LightCmd::typeId, + state); + } return true; } diff --git a/test/integration/model.cc b/test/integration/model.cc index 07c7c2623c..cf188ad46c 100644 --- a/test/integration/model.cc +++ b/test/integration/model.cc @@ -23,6 +23,8 @@ #include #include #include +#include +#include #include #include #include @@ -33,6 +35,8 @@ #include #include +#include + using namespace ignition; using namespace gazebo; @@ -233,3 +237,50 @@ TEST_F(ModelIntegrationTest, SetWorldPoseCmd) EXPECT_TRUE(ecm.HasOneTimeComponentChanges()); } +////////////////////////////////////////////////// +TEST_F(ModelIntegrationTest, SetLightCmd) +{ + EntityComponentManager ecm; + + // Model + auto eModel = ecm.CreateEntity(); + Model model(eModel); + + auto lightCmdComp = ecm.Component(eModel); + EXPECT_EQ(nullptr, lightCmdComp); + EXPECT_FALSE(ecm.HasOneTimeComponentChanges()); + + sdf::Light light; + light.SetType(sdf::LightType::SPOT); + light.SetName("spot"); + light.SetCastShadows(true); + light.SetDiffuse(math::Color(0.8, 0.8, 0.8, 1)); + light.SetSpecular(math::Color(0.2, 0.2, 0.2, 1)); + light.SetDirection(math::Vector3d(0.5, 0.2, -0.9)); + light.SetAttenuationRange(1.0); + light.SetLinearAttenuationFactor(0.5); + light.SetConstantAttenuationFactor(0.3); + light.SetQuadraticAttenuationFactor(4.0); + light.SetSpotInnerAngle(math::Angle(0.1)); + light.SetSpotOuterAngle(math::Angle(0.2)); + light.SetSpotFalloff(0.001); + + model.SetLightCmd(ecm, light); + + lightCmdComp = ecm.Component(eModel); + ASSERT_NE(nullptr, lightCmdComp); + EXPECT_EQ(sdf::LightType::SPOT, lightCmdComp->Data().Type()); + EXPECT_EQ("spot", lightCmdComp->Data().Name()); + EXPECT_TRUE(lightCmdComp->Data().CastShadows()); + EXPECT_EQ(math::Color(0.2, 0.2, 0.2, 1), lightCmdComp->Data().Specular()); + EXPECT_EQ(math::Color(0.8, 0.8, 0.8, 1), lightCmdComp->Data().Diffuse()); + EXPECT_EQ(math::Vector3d(0.5, 0.2, -0.9), lightCmdComp->Data().Direction()); + EXPECT_NEAR(1.0, lightCmdComp->Data().AttenuationRange(), 0.1); + EXPECT_NEAR(0.5, lightCmdComp->Data().LinearAttenuationFactor(), 0.1); + EXPECT_NEAR(0.3, lightCmdComp->Data().ConstantAttenuationFactor(), 0.1); + EXPECT_NEAR(4.0, lightCmdComp->Data().QuadraticAttenuationFactor(), 0.1); + EXPECT_EQ(math::Angle(0.1), lightCmdComp->Data().SpotInnerAngle()); + EXPECT_EQ(math::Angle(0.2), lightCmdComp->Data().SpotOuterAngle()); + EXPECT_NEAR(0.001, lightCmdComp->Data().SpotFalloff(), 0.0001); + EXPECT_TRUE(ecm.HasOneTimeComponentChanges()); +} From 19b3c9f06d5c097dc923324501a2a05bb889a2dd Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 17 Dec 2020 12:26:23 +0100 Subject: [PATCH 13/42] Removed LightCmd Signed-off-by: ahcorde --- .../ignition/gazebo/components/LightCmd.hh | 13 ++++++++--- src/rendering/RenderUtil.cc | 23 +++++++++++++++++-- 2 files changed, 31 insertions(+), 5 deletions(-) diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh index 29991e9e78..3dfb26a7d3 100644 --- a/include/ignition/gazebo/components/LightCmd.hh +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -24,6 +24,7 @@ #include #include "ignition/gazebo/components/Component.hh" +#include namespace ignition { @@ -31,11 +32,17 @@ namespace gazebo { // Inline bracket to help doxygen filtering. inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace serializers +{ + using LightCmdSerializer = + serializers::ComponentToMsgSerializer; +} + namespace components { - /// \brief A component type that contains commanded pose of an - /// entity in the world frame represented by ignition::math::Pose3d. - using LightCmd = Component; + /// \brief A component type that contains commanded light of an + /// entity in the world frame represented by sdf::Light. + using LightCmd = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightCmd", LightCmd) } diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 263bed9d38..fef6a34fa1 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -50,6 +50,7 @@ #include "ignition/gazebo/components/GpuLidar.hh" #include "ignition/gazebo/components/Geometry.hh" #include "ignition/gazebo/components/Light.hh" +#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Material.hh" #include "ignition/gazebo/components/Model.hh" @@ -1141,14 +1142,32 @@ void RenderUtilPrivate::UpdateRenderingEntities( // update lights _ecm.Each( [&](const Entity &_entity, - const components::Light *_light, + const components::Light *, const components::Pose *_pose)->bool { this->entityPoses[_entity] = _pose->Data(); - this->entityLights[_entity] = _light->Data(); return true; }); + std::vector entitiesLightCmd; + _ecm.Each( + [&](const Entity &_entity, + const components::LightCmd *_lightCmd) -> bool + { + this->entityLights[_entity] = _lightCmd->Data(); + entitiesLightCmd.push_back(_entity); + return true; + }); + + // Converting the const EntityComponentManager to a + // non-const EntityComponentManager to be able to remove the LightCmd + EntityComponentManager& _ecm_remove = + const_cast(_ecm); + for (const auto entity : entitiesLightCmd) + { + _ecm_remove.RemoveComponent(entity); + } + // Update cameras _ecm.Each( [&](const Entity &_entity, From eb00612166e7b920605470d88652ebfacd8b8ca4 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 17 Dec 2020 12:35:01 +0100 Subject: [PATCH 14/42] make linters happy Signed-off-by: ahcorde --- src/systems/user_commands/UserCommands.cc | 47 +++++++++++++++-------- 1 file changed, 30 insertions(+), 17 deletions(-) diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 115fccd8d5..790fe24659 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -141,23 +141,36 @@ class LightCommand : public UserCommandBase /// \brief Light equality comparison function. public: std::function lightEql { [](const sdf::Light &_a, const sdf::Light &_b) - { - return - _a.Type() == _b.Type() && - _a.Name() == _b.Name() && - _a.Diffuse() == _b.Diffuse() && - _a.Specular() == _b.Specular() && - math::equal(_a.AttenuationRange(), _b.AttenuationRange(), 1e-6) && - math::equal(_a.LinearAttenuationFactor(), _b.LinearAttenuationFactor(), 1e-6) && - math::equal(_a.ConstantAttenuationFactor(), _b.ConstantAttenuationFactor(), 1e-6) && - math::equal(_a.ConstantAttenuationFactor(), _b.ConstantAttenuationFactor(), 1e-6) && - math::equal(_a.QuadraticAttenuationFactor(), _b.QuadraticAttenuationFactor(), 1e-6) && - _a.CastShadows() == _b.CastShadows() && - _a.Direction() == _b.Direction() && - _a.SpotInnerAngle() == _b.SpotInnerAngle() && - _a.SpotOuterAngle() == _b.SpotOuterAngle() && - math::equal(_a.SpotFalloff(), _b.SpotFalloff(), 1e-6); - }}; + { + return + _a.Type() == _b.Type() && + _a.Name() == _b.Name() && + _a.Diffuse() == _b.Diffuse() && + _a.Specular() == _b.Specular() && + math::equal( + _a.AttenuationRange(), _b.AttenuationRange(), 1e-6) && + math::equal( + _a.LinearAttenuationFactor(), + _b.LinearAttenuationFactor(), + 1e-6) && + math::equal( + _a.ConstantAttenuationFactor(), + _b.ConstantAttenuationFactor(), + 1e-6) && + math::equal( + _a.ConstantAttenuationFactor(), + _b.ConstantAttenuationFactor(), + 1e-6) && + math::equal( + _a.QuadraticAttenuationFactor(), + _b.QuadraticAttenuationFactor(), + 1e-6) && + _a.CastShadows() == _b.CastShadows() && + _a.Direction() == _b.Direction() && + _a.SpotInnerAngle() == _b.SpotInnerAngle() && + _a.SpotOuterAngle() == _b.SpotOuterAngle() && + math::equal(_a.SpotFalloff(), _b.SpotFalloff(), 1e-6); + }}; }; /// \brief Command to update an entity's pose transform. From 88775426dce937d6da554021a3b1cd28c47ba09a Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 17 Dec 2020 12:36:05 +0100 Subject: [PATCH 15/42] make linters happy Signed-off-by: ahcorde --- include/ignition/gazebo/components/LightCmd.hh | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh index 3dfb26a7d3..2c8e79002b 100644 --- a/include/ignition/gazebo/components/LightCmd.hh +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -42,7 +42,8 @@ namespace components { /// \brief A component type that contains commanded light of an /// entity in the world frame represented by sdf::Light. - using LightCmd = Component; + using LightCmd = + Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightCmd", LightCmd) } From 0e660f93578f097fd8e72337febb3009eeebacad Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 18 Dec 2020 14:25:34 +0100 Subject: [PATCH 16/42] Added UpdateECM method Signed-off-by: ahcorde --- .../ignition/gazebo/rendering/RenderUtil.hh | 4 ++ src/gui/plugins/scene3d/Scene3D.cc | 1 + src/rendering/RenderUtil.cc | 47 +++++++++++-------- src/systems/sensors/Sensors.cc | 11 +++++ src/systems/sensors/Sensors.hh | 5 ++ 5 files changed, 48 insertions(+), 20 deletions(-) diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh index 36cb1ad63e..2e3656060d 100644 --- a/include/ignition/gazebo/rendering/RenderUtil.hh +++ b/include/ignition/gazebo/rendering/RenderUtil.hh @@ -66,6 +66,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \return Pointer to the scene public: rendering::ScenePtr Scene() const; + /// \brief Helper Update function for updating the scene + public: void UpdateECM(const UpdateInfo &_info, + EntityComponentManager &_ecm); + /// \brief Helper PostUpdate function for updating the scene public: void UpdateFromECM(const UpdateInfo &_info, const EntityComponentManager &_ecm); diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 8522b91259..59269f964e 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -2408,6 +2408,7 @@ void Scene3D::Update(const UpdateInfo &_info, msgs::Pose poseMsg = msgs::Convert(renderWindow->CameraPose()); this->dataPtr->cameraPosePub.Publish(poseMsg); } + this->dataPtr->renderUtil->UpdateECM(_info, _ecm); this->dataPtr->renderUtil->UpdateFromECM(_info, _ecm); } diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index fef6a34fa1..1d35113793 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -167,6 +167,9 @@ class ignition::gazebo::RenderUtilPrivate /// \brief A map of entity ids and light updates. public: std::unordered_map entityLights; + /// \brief A map of entity ids and light updates. + public: std::vector entityLightsCmdToDelete; + /// \brief A map of entity ids and actor transforms. public: std::map> actorTransforms; @@ -239,6 +242,29 @@ rendering::ScenePtr RenderUtil::Scene() const { return this->dataPtr->scene; } +////////////////////////////////////////////////// +void RenderUtil::UpdateECM(const UpdateInfo &, + EntityComponentManager &_ecm) +{ + std::lock_guard lock(this->dataPtr->updateMutex); + + auto entityLightsCmdToDelete = std::move(this->dataPtr->entityLightsCmdToDelete); + this->dataPtr->entityLightsCmdToDelete.clear(); + + _ecm.Each( + [&](const Entity &_entity, + const components::LightCmd * _lightCmd) -> bool + { + this->dataPtr->entityLights[_entity] = _lightCmd->Data(); + this->dataPtr->entityLightsCmdToDelete.push_back(_entity); + return true; + }); + + for (const auto entity : entityLightsCmdToDelete) + { + _ecm.RemoveComponent(entity); + } +} ////////////////////////////////////////////////// void RenderUtil::UpdateFromECM(const UpdateInfo &_info, @@ -433,7 +459,7 @@ void RenderUtil::Update() } } - // update entities' pose + // update lights { IGN_PROFILE("RenderUtil::Update Lights"); for (const auto &light : entityLights) { @@ -1149,25 +1175,6 @@ void RenderUtilPrivate::UpdateRenderingEntities( return true; }); - std::vector entitiesLightCmd; - _ecm.Each( - [&](const Entity &_entity, - const components::LightCmd *_lightCmd) -> bool - { - this->entityLights[_entity] = _lightCmd->Data(); - entitiesLightCmd.push_back(_entity); - return true; - }); - - // Converting the const EntityComponentManager to a - // non-const EntityComponentManager to be able to remove the LightCmd - EntityComponentManager& _ecm_remove = - const_cast(_ecm); - for (const auto entity : entitiesLightCmd) - { - _ecm_remove.RemoveComponent(entity); - } - // Update cameras _ecm.Each( [&](const Entity &_entity, diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 74b5b36bd1..b77f9d5806 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -405,6 +405,16 @@ void Sensors::Configure(const Entity &/*_id*/, this->dataPtr->Run(); } +////////////////////////////////////////////////// +void Sensors::Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) +{ + if (this->dataPtr->running && this->dataPtr->initialized) + { + this->dataPtr->renderUtil.UpdateECM(_info, _ecm); + } +} + ////////////////////////////////////////////////// void Sensors::PostUpdate(const UpdateInfo &_info, const EntityComponentManager &_ecm) @@ -570,6 +580,7 @@ std::string Sensors::CreateSensor(const Entity &_entity, IGNITION_ADD_PLUGIN(Sensors, System, Sensors::ISystemConfigure, + Sensors::ISystemUpdate, Sensors::ISystemPostUpdate ) diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index b295159cf8..cd8f132bc5 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -41,6 +41,7 @@ namespace systems /// sensor / sensor type? class IGNITION_GAZEBO_VISIBLE Sensors: public System, + public ISystemUpdate, public ISystemConfigure, public ISystemPostUpdate { @@ -56,6 +57,10 @@ namespace systems EntityComponentManager &_ecm, EventManager &_eventMgr) final; + // Documentation inherited + public: void Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) final; + // Documentation inherited public: void PostUpdate(const UpdateInfo &_info, const EntityComponentManager &_ecm) final; From 9ff266b877ec7e2e511652cee211e34281232bad Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 21 Dec 2020 09:47:17 +0100 Subject: [PATCH 17/42] Fixed year in the License Signed-off-by: ahcorde --- include/ignition/gazebo/components/LightCmd.hh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh index 2c8e79002b..20ade522ec 100644 --- a/include/ignition/gazebo/components/LightCmd.hh +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -1,5 +1,5 @@ /* - * Copyright (C) 2019 Open Source Robotics Foundation + * Copyright (C) 2020 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. From eb1d45032109c1534760917bb7d70b8ce5af39e5 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 21 Dec 2020 13:20:31 +0100 Subject: [PATCH 18/42] Fix lights inside link Signed-off-by: ahcorde --- src/systems/user_commands/UserCommands.cc | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 790fe24659..2533787414 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -737,7 +737,24 @@ bool LightCommand::Execute() auto lightComp = this->iface->ecm->Component(entity); if (nullptr == lightComp) + { entity = kNullEntity; + // try to find the light inside a link + this->iface->ecm->Each( + [&](const Entity & _entity, + const components::Name *_name) -> bool + { + auto subentity_light = this->iface->ecm->EntityByComponents( + components::Name(lightMsg->name()), + components::ParentEntity(_entity)); + if (subentity_light) + { + entity = subentity_light; + lightComp = this->iface->ecm->Component(subentity_light); + } + return true; + }); + } if (!entity) { From dc97cf2d99c4b9efc7be8adf93bfe4e2fed53191 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 21 Dec 2020 14:01:32 +0100 Subject: [PATCH 19/42] Removed compiler warning Signed-off-by: ahcorde --- src/systems/user_commands/UserCommands.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 2533787414..7b719fe931 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -742,7 +742,7 @@ bool LightCommand::Execute() // try to find the light inside a link this->iface->ecm->Each( [&](const Entity & _entity, - const components::Name *_name) -> bool + const components::Name *) -> bool { auto subentity_light = this->iface->ecm->EntityByComponents( components::Name(lightMsg->name()), From d175a115e650739ad73a7629a6c71dec8b0e8f95 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 21 Dec 2020 18:44:33 +0100 Subject: [PATCH 20/42] make linters happy Signed-off-by: ahcorde --- src/rendering/RenderUtil.cc | 3 ++- src/systems/user_commands/UserCommands.cc | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 1d35113793..7640e06668 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -248,7 +248,8 @@ void RenderUtil::UpdateECM(const UpdateInfo &, { std::lock_guard lock(this->dataPtr->updateMutex); - auto entityLightsCmdToDelete = std::move(this->dataPtr->entityLightsCmdToDelete); + auto entityLightsCmdToDelete = + std::move(this->dataPtr->entityLightsCmdToDelete); this->dataPtr->entityLightsCmdToDelete.clear(); _ecm.Each( diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 7b719fe931..e55fe23249 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -750,7 +750,8 @@ bool LightCommand::Execute() if (subentity_light) { entity = subentity_light; - lightComp = this->iface->ecm->Component(subentity_light); + lightComp = + this->iface->ecm->Component(subentity_light); } return true; }); From 2d8b9d53bb69021e5840047b026d2941f7ddbf88 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 22 Dec 2020 10:45:39 +0100 Subject: [PATCH 21/42] simplifying the search for lights attached to links Signed-off-by: ahcorde --- src/systems/user_commands/UserCommands.cc | 30 +++++++++++------------ 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index e55fe23249..b42302aee5 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -40,6 +40,7 @@ #include "ignition/gazebo/components/Light.hh" #include "ignition/gazebo/components/LightCmd.hh" +#include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentEntity.hh" @@ -740,21 +741,20 @@ bool LightCommand::Execute() { entity = kNullEntity; // try to find the light inside a link - this->iface->ecm->Each( - [&](const Entity & _entity, - const components::Name *) -> bool - { - auto subentity_light = this->iface->ecm->EntityByComponents( - components::Name(lightMsg->name()), - components::ParentEntity(_entity)); - if (subentity_light) - { - entity = subentity_light; - lightComp = - this->iface->ecm->Component(subentity_light); - } - return true; - }); + auto lightEnt = this->iface->ecm->EntityByComponents( + components::Name(lightMsg->name())); + if (lightEnt != kNullEntity) + { + // check if light parent is a link + auto parentComp = this->iface->ecm->Component( + lightEnt); + if (parentComp && this->iface->ecm->Component( + parentComp->Data())) + { + lightComp = this->iface->ecm->Component(lightEnt); + entity = lightEnt; + } + } } if (!entity) From 135c827c1edf57bbffd2fdd13c71899a9ea1a5cd Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 23 Dec 2020 16:53:44 +0100 Subject: [PATCH 22/42] used convert method Signed-off-by: ahcorde --- src/systems/user_commands/UserCommands.cc | 34 ++--------------------- 1 file changed, 2 insertions(+), 32 deletions(-) diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index b42302aee5..cd83ce1173 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -764,38 +764,8 @@ bool LightCommand::Execute() return false; } - lightComp->Data().SetDiffuse(msgs::Convert(lightMsg->diffuse())); - lightComp->Data().SetSpecular(msgs::Convert(lightMsg->specular())); - lightComp->Data().SetAttenuationRange(lightMsg->range()); - lightComp->Data().SetLinearAttenuationFactor(lightMsg->attenuation_linear()); - lightComp->Data().SetConstantAttenuationFactor( - lightMsg->attenuation_constant()); - lightComp->Data().SetQuadraticAttenuationFactor( - lightMsg->attenuation_quadratic()); - lightComp->Data().SetCastShadows(lightMsg->cast_shadows()); - - if (lightMsg->type() == ignition::msgs::Light::POINT) - lightComp->Data().SetType(sdf::LightType::POINT); - else if (lightMsg->type() == ignition::msgs::Light::SPOT) - lightComp->Data().SetType(sdf::LightType::SPOT); - else if (lightMsg->type() == ignition::msgs::Light::DIRECTIONAL) - lightComp->Data().SetType(sdf::LightType::DIRECTIONAL); - - lightComp->Data().SetName(lightMsg->name()); - - if (lightMsg->type() != ignition::msgs::Light::POINT) - { - lightComp->Data().SetDirection(msgs::Convert(lightMsg->direction())); - } - - if (lightMsg->type() == ignition::msgs::Light::SPOT) - { - lightComp->Data().SetSpotInnerAngle( - ignition::math::Angle(lightMsg->spot_inner_angle())); - lightComp->Data().SetSpotOuterAngle( - ignition::math::Angle(lightMsg->spot_outer_angle())); - lightComp->Data().SetSpotFalloff(lightMsg->spot_falloff()); - } + sdf::Light lightSDF = convert(*lightMsg); + lightComp->Data() = lightSDF; auto lightPose = this->iface->ecm->Component(entity); if (nullptr == lightPose) From 254a19785a126bc15529a67b9bb068339697a65e Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 24 Dec 2020 12:58:54 +0100 Subject: [PATCH 23/42] added some feedback Signed-off-by: ahcorde --- include/ignition/gazebo/Model.hh | 6 --- src/Model.cc | 19 -------- .../component_inspector/ComponentInspector.cc | 3 +- src/gui/plugins/component_inspector/Light.qml | 14 ------ src/systems/sensors/Sensors.cc | 1 + src/systems/user_commands/UserCommands.cc | 6 +-- test/integration/model.cc | 48 ------------------- test/integration/user_commands.cc | 12 +++-- 8 files changed, 15 insertions(+), 94 deletions(-) diff --git a/include/ignition/gazebo/Model.hh b/include/ignition/gazebo/Model.hh index 573e5ce2b4..1528cd61e7 100644 --- a/include/ignition/gazebo/Model.hh +++ b/include/ignition/gazebo/Model.hh @@ -171,12 +171,6 @@ namespace ignition public: void SetWorldPoseCmd(EntityComponentManager &_ecm, const math::Pose3d &_pose); - /// \brief Set a command to change the light. - /// \param[in] _ecm Entity-component manager. - /// \param[in] _light New model light. - public: void SetLightCmd(EntityComponentManager &_ecm, - const sdf::Light &_light); - /// \brief Pointer to private data. private: std::unique_ptr dataPtr; }; diff --git a/src/Model.cc b/src/Model.cc index f60b90a29f..7c90f06933 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -193,22 +193,3 @@ void Model::SetWorldPoseCmd(EntityComponentManager &_ecm, components::WorldPoseCmd::typeId, ComponentState::OneTimeChange); } } - -////////////////////////////////////////////////// -void Model::SetLightCmd(EntityComponentManager &_ecm, - const sdf::Light &_light) -{ - auto lightCmdComp = _ecm.Component( - this->dataPtr->id); - if (!lightCmdComp) - { - _ecm.CreateComponent(this->dataPtr->id, components::LightCmd(_light)); - } - else - { - lightCmdComp->SetData(_light, - [](const sdf::Light &, const sdf::Light &){return false;}); - _ecm.SetChanged(this->dataPtr->id, - components::LightCmd::typeId, ComponentState::OneTimeChange); - } -} diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 87d0d53f8d..c1ecdc13be 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -827,7 +827,8 @@ void ComponentInspector::OnLight( } // if sdf::LightType::SPOT || sdf::LightType::DIRECTIONAL - if (_type == 1 || _type == 2) { + if (_type == 1 || _type == 2) + { ignition::msgs::Set(req.mutable_direction(), ignition::math::Vector3d(_directionX, _directionY, _directionZ)); } diff --git a/src/gui/plugins/component_inspector/Light.qml b/src/gui/plugins/component_inspector/Light.qml index 6a23e997e7..17a7374af5 100644 --- a/src/gui/plugins/component_inspector/Light.qml +++ b/src/gui/plugins/component_inspector/Light.qml @@ -170,20 +170,6 @@ Rectangle { } } - Component { - id: readOnlyNumber - Text { - id: numberText - anchors.fill: parent - horizontalAlignment: Text.AlignRight - verticalAlignment: Text.AlignVCenter - text: { - var decimals = numberText.width < 100 ? 2 : 6 - return numberValue.toFixed(decimals) - } - } - } - Column { anchors.fill: parent diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 0c5ea0d179..12c6d609af 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -410,6 +410,7 @@ void Sensors::Configure(const Entity &/*_id*/, void Sensors::Update(const UpdateInfo &_info, EntityComponentManager &_ecm) { + IGN_PROFILE("Sensors::Update"); if (this->dataPtr->running && this->dataPtr->initialized) { this->dataPtr->renderUtil.UpdateECM(_info, _ecm); diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index cd83ce1173..1d6d6e6ab2 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -312,7 +312,8 @@ void UserCommands::Configure(const Entity &_entity, this->dataPtr->node.Advertise(lightService, &UserCommandsPrivate::LightService, this->dataPtr.get()); - ignmsg << "Light service on [" << lightService << "]" << std::endl; + ignmsg << "Light configuration service on [" << lightService << "]" + << std::endl; } ////////////////////////////////////////////////// @@ -728,7 +729,7 @@ bool LightCommand::Execute() auto lightMsg = dynamic_cast(this->msg); if (nullptr == lightMsg) { - ignerr << "Internal error, null create message" << std::endl; + ignerr << "Internal error, null light message" << std::endl; return false; } @@ -791,7 +792,6 @@ bool LightCommand::Execute() } else { - /// \todo(anyone) Moving an object is not captured in a log file. auto state = lightCmdComp->SetData(lightComp->Data(), this->lightEql) ? ComponentState::OneTimeChange : ComponentState::NoChange; diff --git a/test/integration/model.cc b/test/integration/model.cc index cf188ad46c..0fb534a36f 100644 --- a/test/integration/model.cc +++ b/test/integration/model.cc @@ -236,51 +236,3 @@ TEST_F(ModelIntegrationTest, SetWorldPoseCmd) EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), worldPoseCmdComp->Data()); EXPECT_TRUE(ecm.HasOneTimeComponentChanges()); } - -////////////////////////////////////////////////// -TEST_F(ModelIntegrationTest, SetLightCmd) -{ - EntityComponentManager ecm; - - // Model - auto eModel = ecm.CreateEntity(); - Model model(eModel); - - auto lightCmdComp = ecm.Component(eModel); - EXPECT_EQ(nullptr, lightCmdComp); - EXPECT_FALSE(ecm.HasOneTimeComponentChanges()); - - sdf::Light light; - light.SetType(sdf::LightType::SPOT); - light.SetName("spot"); - light.SetCastShadows(true); - light.SetDiffuse(math::Color(0.8, 0.8, 0.8, 1)); - light.SetSpecular(math::Color(0.2, 0.2, 0.2, 1)); - light.SetDirection(math::Vector3d(0.5, 0.2, -0.9)); - light.SetAttenuationRange(1.0); - light.SetLinearAttenuationFactor(0.5); - light.SetConstantAttenuationFactor(0.3); - light.SetQuadraticAttenuationFactor(4.0); - light.SetSpotInnerAngle(math::Angle(0.1)); - light.SetSpotOuterAngle(math::Angle(0.2)); - light.SetSpotFalloff(0.001); - - model.SetLightCmd(ecm, light); - - lightCmdComp = ecm.Component(eModel); - ASSERT_NE(nullptr, lightCmdComp); - EXPECT_EQ(sdf::LightType::SPOT, lightCmdComp->Data().Type()); - EXPECT_EQ("spot", lightCmdComp->Data().Name()); - EXPECT_TRUE(lightCmdComp->Data().CastShadows()); - EXPECT_EQ(math::Color(0.2, 0.2, 0.2, 1), lightCmdComp->Data().Specular()); - EXPECT_EQ(math::Color(0.8, 0.8, 0.8, 1), lightCmdComp->Data().Diffuse()); - EXPECT_EQ(math::Vector3d(0.5, 0.2, -0.9), lightCmdComp->Data().Direction()); - EXPECT_NEAR(1.0, lightCmdComp->Data().AttenuationRange(), 0.1); - EXPECT_NEAR(0.5, lightCmdComp->Data().LinearAttenuationFactor(), 0.1); - EXPECT_NEAR(0.3, lightCmdComp->Data().ConstantAttenuationFactor(), 0.1); - EXPECT_NEAR(4.0, lightCmdComp->Data().QuadraticAttenuationFactor(), 0.1); - EXPECT_EQ(math::Angle(0.1), lightCmdComp->Data().SpotInnerAngle()); - EXPECT_EQ(math::Angle(0.2), lightCmdComp->Data().SpotOuterAngle()); - EXPECT_NEAR(0.001, lightCmdComp->Data().SpotFalloff(), 0.0001); - EXPECT_TRUE(ecm.HasOneTimeComponentChanges()); -} diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index b8227cf3f2..55d05517df 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -678,8 +678,8 @@ TEST_F(UserCommandsTest, Light) { // Start server ServerConfig serverConfig; - const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + - "/test/worlds/lights.sdf"; + const auto sdfFile = ignition::common::joinPaths( + std::string(PROJECT_SOURCE_PATH), "test", "worlds", "lights.sdf"); serverConfig.SetSdfFile(sdfFile); Server server(serverConfig); @@ -719,7 +719,7 @@ TEST_F(UserCommandsTest, Light) auto pointLightEntity = ecm->EntityByComponents(components::Name("point")); EXPECT_NE(kNullEntity, pointLightEntity); - // Check entity has not been moved yet + // Check entity has not been edited yet auto pointLightComp = ecm->Component(pointLightEntity); ASSERT_NE(nullptr, pointLightComp); EXPECT_EQ( @@ -763,6 +763,7 @@ TEST_F(UserCommandsTest, Light) EXPECT_NEAR(0.6, pointLightComp->Data().ConstantAttenuationFactor(), 0.1); EXPECT_NEAR(0.001, pointLightComp->Data().QuadraticAttenuationFactor(), 0.1); EXPECT_TRUE(pointLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type()); // directional light auto directionalLightEntity = ecm->EntityByComponents( @@ -790,6 +791,7 @@ TEST_F(UserCommandsTest, Light) EXPECT_EQ( math::Vector3d(0.5, 0.2, -0.9), directionalLightComp->Data().Direction()); EXPECT_TRUE(directionalLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type()); req.Clear(); ignition::msgs::Set(req.mutable_diffuse(), @@ -829,6 +831,8 @@ TEST_F(UserCommandsTest, Light) 1, directionalLightComp->Data().QuadraticAttenuationFactor(), 0.1); EXPECT_EQ(math::Vector3d(1, 2, 3), directionalLightComp->Data().Direction()); EXPECT_FALSE(directionalLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::DIRECTIONAL, + directionalLightComp->Data().Type()); // spot light auto spotLightEntity = ecm->EntityByComponents( @@ -850,6 +854,7 @@ TEST_F(UserCommandsTest, Light) 0.001, spotLightComp->Data().QuadraticAttenuationFactor(), 0.001); EXPECT_EQ(math::Vector3d(0, 0, -1), spotLightComp->Data().Direction()); EXPECT_FALSE(spotLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::SPOT, spotLightComp->Data().Type()); EXPECT_NEAR(0.1, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); EXPECT_NEAR(0.5, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); EXPECT_NEAR(0.8, spotLightComp->Data().SpotFalloff(), 0.1); @@ -892,6 +897,7 @@ TEST_F(UserCommandsTest, Light) EXPECT_NEAR(1, spotLightComp->Data().QuadraticAttenuationFactor(), 0.1); EXPECT_EQ(math::Vector3d(1, 2, 3), spotLightComp->Data().Direction()); EXPECT_TRUE(spotLightComp->Data().CastShadows()); + EXPECT_EQ(sdf::LightType::SPOT, spotLightComp->Data().Type()); EXPECT_NEAR(1.5, spotLightComp->Data().SpotInnerAngle().Radian(), 0.1); EXPECT_NEAR(0.3, spotLightComp->Data().SpotOuterAngle().Radian(), 0.1); EXPECT_NEAR(0.9, spotLightComp->Data().SpotFalloff(), 0.1); From d4143973d18a7ab759f0a9a79345e35dc9f98dfa Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 28 Dec 2020 17:56:20 +0100 Subject: [PATCH 24/42] Improved GUI Signed-off-by: ahcorde --- src/gui/plugins/component_inspector/Light.qml | 1508 +++++++++-------- src/systems/user_commands/UserCommands.cc | 58 +- 2 files changed, 810 insertions(+), 756 deletions(-) diff --git a/src/gui/plugins/component_inspector/Light.qml b/src/gui/plugins/component_inspector/Light.qml index 17a7374af5..ffaced1293 100644 --- a/src/gui/plugins/component_inspector/Light.qml +++ b/src/gui/plugins/component_inspector/Light.qml @@ -18,6 +18,7 @@ import QtQuick 2.9 import QtQuick.Controls 1.4 import QtQuick.Controls 2.2 import QtQuick.Controls.Material 2.1 +import QtQuick.Dialogs 1.0 import QtQuick.Layouts 1.3 import QtQuick.Controls.Styles 1.4 import "qrc:/ComponentInspector" @@ -111,7 +112,7 @@ Rectangle { attLinearItem.value, attConstantItem.value, attQuadraticItem.value, - castShadowsItem, + castShadowsItem.checked, directionXItem.value, directionYItem.value, directionZItem.value, @@ -131,18 +132,32 @@ Rectangle { * Used to create a spin box */ Component { - id: spinZeroOne - IgnSpinBox { + id: sliderZeroOne + Slider { id: writableSpin value: writableSpin.activeFocus ? writableSpin.value : numberValue - minimumValue: 0 - maximumValue: 1 - decimals: 6 - onEditingFinished: { + from: 0.0 + to: 1.0 + onValueChanged: { + if (hovered){ + sendLight() + } + } + } + } + + Component { + id: ignSwitch + Switch { + id: booleanSwitch + checked: numberValue + enabled: true + onToggled: { sendLight() } } } + Component { id: spinZeroMax IgnSpinBox { @@ -170,6 +185,35 @@ Rectangle { } } + Component { + id: plotIcon + Image { + property string componentInfo: "" + source: "plottable_icon.svg" + anchors.top: parent.top + anchors.left: parent.left + + Drag.mimeData: { "text/plain" : (model === null) ? "" : + "Component," + model.entity + "," + model.typeId + "," + + model.dataType + "," + componentInfo + "," + model.shortName + } + Drag.dragType: Drag.Automatic + Drag.supportedActions : Qt.CopyAction + Drag.active: dragMouse.drag.active + // a point to drag from + Drag.hotSpot.x: 0 + Drag.hotSpot.y: y + MouseArea { + id: dragMouse + anchors.fill: parent + drag.target: (model === null) ? null : parent + onPressed: parent.grabToImage(function(result) {parent.Drag.imageSource = result.url }) + onReleased: parent.Drag.drop(); + cursorShape: Qt.DragCopyCursor + } + } + } + Column { anchors.fill: parent @@ -233,833 +277,819 @@ Rectangle { } } - - GridLayout { + ColumnLayout { id: grid width: parent.width - columns: 6 - - Text { - Layout.columnSpan: 6 - text: " Specular" - color: "dimgrey" - width: margin + indentation - } - - // Left spacer - Item { - Layout.rowSpan: 3 - width: margin + indentation - } - - Component { - id: plotIcon - Image { - property string componentInfo: "" - source: "plottable_icon.svg" - anchors.top: parent.top - anchors.left: parent.left - - Drag.mimeData: { "text/plain" : (model === null) ? "" : - "Component," + model.entity + "," + model.typeId + "," + - model.dataType + "," + componentInfo + "," + model.shortName - } - Drag.dragType: Drag.Automatic - Drag.supportedActions : Qt.CopyAction - Drag.active: dragMouse.drag.active - // a point to drag from - Drag.hotSpot.x: 0 - Drag.hotSpot.y: y - MouseArea { - id: dragMouse - anchors.fill: parent - drag.target: (model === null) ? null : parent - onPressed: parent.grabToImage(function(result) {parent.Drag.imageSource = result.url }) - onReleased: parent.Drag.drop(); - cursorShape: Qt.DragCopyCursor - } - } - } - - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: rSpecularText.width + indentation*3 - Loader { - id: loaderSpecularR - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderSpecularR.item.componentInfo = "specularR" + RowLayout { + Layout.alignment : Qt.AlignLeft Text { - id : rSpecularText - text: ' R' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + text: " Specular" + color: "dimgrey" + width: margin + indentation } } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: rSpecularLoader - anchors.fill: parent - property double numberValue: model.data[0] - sourceComponent: spinZeroOne - onLoaded: { - rSpecularItem = rSpecularLoader.item + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: rSpecularText.width + indentation*3 + Loader { + id: loaderSpecularR + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularR.item.componentInfo = "specularR" + + Text { + id : rSpecularText + text: ' R' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent } } - } - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: gSpecularText.width + indentation*3 - Loader { - id: loaderSpecularG - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: rSpecularLoader + anchors.fill: parent + property double numberValue: model.data[0] + sourceComponent: sliderZeroOne + onLoaded: { + rSpecularItem = rSpecularLoader.item + } + } } - Component.onCompleted: loaderSpecularG.item.componentInfo = "specularG" - - Text { - id : gSpecularText - text: ' G' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: gSpecularText.width + indentation*3 + Loader { + id: loaderSpecularG + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularG.item.componentInfo = "specularG" + + Text { + id : gSpecularText + text: ' G' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - } - - // Right spacer - Item { - Layout.rowSpan: 3 - width: margin + indentation - } - - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: gSpecularLoader - anchors.fill: parent - property double numberValue: model.data[1] - sourceComponent: spinZeroOne - onLoaded: { - gSpecularItem = gSpecularLoader.item + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: gSpecularLoader + anchors.fill: parent + property double numberValue: model.data[1] + sourceComponent: sliderZeroOne + onLoaded: { + gSpecularItem = gSpecularLoader.item + } } } } - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: bSpecularText.width + indentation*3 - Loader { - id: loaderSpecularB - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderSpecularB.item.componentInfo = "specularB" - - Text { - id : bSpecularText - text: ' B' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: bSpecularText.width + indentation*3 + Loader { + id: loaderSpecularB + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularB.item.componentInfo = "specularB" + + Text { + id : bSpecularText + text: ' B' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: bSpecularLoader - anchors.fill: parent - property double numberValue: model.data[2] - sourceComponent: spinZeroOne - onLoaded: { - bSpecularItem = bSpecularLoader.item + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: bSpecularLoader + anchors.fill: parent + property double numberValue: model.data[2] + sourceComponent: sliderZeroOne + onLoaded: { + bSpecularItem = bSpecularLoader.item + } } } - } - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: aSpecularText.width + indentation*3 - Loader { - id: loaderSpecularA - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: aSpecularText.width + indentation*3 + Loader { + id: loaderSpecularA + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderSpecularA.item.componentInfo = "specularA" + + Text { + id : aSpecularText + text: ' A' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - Component.onCompleted: loaderSpecularA.item.componentInfo = "specularA" - - Text { - id : aSpecularText - text: ' A' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: aSpecularLoader + anchors.fill: parent + property double numberValue: model.data[3] + sourceComponent: sliderZeroOne + onLoaded: { + aSpecularItem = aSpecularLoader.item + } + } } } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: aSpecularLoader - anchors.fill: parent - property double numberValue: model.data[3] - sourceComponent: spinZeroOne - onLoaded: { - aSpecularItem = aSpecularLoader.item + RowLayout { + Layout.alignment: Qt.AlignHCenter + Button { + Layout.alignment: Qt.AlignHCenter + id: specularColor + text: qsTr("Specular Color") + onClicked: colorDialog.open() + ColorDialog { + id: colorDialog + title: "Choose a specular color" + visible: false + onAccepted: { + rSpecularLoader.numberValue = colorDialog.color.r + gSpecularLoader.numberValue = colorDialog.color.g + bSpecularLoader.numberValue = colorDialog.color.b + aSpecularLoader.numberValue = colorDialog.color.a + sendLight() + colorDialog.close() + } + onRejected: { + colorDialog.close() + } } } } - // Right spacer - Item { - Layout.rowSpan: 3 - width: margin + indentation - } - - Text { - Layout.columnSpan: 6 - text: " Diffuse" - color: "dimgrey" - width: margin + indentation - } - - // Left spacer - Item { - Layout.rowSpan: 3 - width: margin + indentation - } - - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: rDiffuseText.width + indentation*3 - Loader { - id: loaderDiffuseR - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderDiffuseR.item.componentInfo = "diffuseR" - + RowLayout { Text { - id : rDiffuseText - text: ' R' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Layout.columnSpan: 6 + text: " Diffuse" + color: "dimgrey" + width: margin + indentation } } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: rDiffuseLoader - anchors.fill: parent - property double numberValue: model.data[4] - sourceComponent: spinZeroOne - onLoaded: { - rDiffuseItem = rDiffuseLoader.item + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: rDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseR + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseR.item.componentInfo = "diffuseR" + + Text { + id : rDiffuseText + text: ' R' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent } } - } - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: gDiffuseText.width + indentation*3 - Loader { - id: loaderDiffuseG - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: rDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[4] + sourceComponent: sliderZeroOne + onLoaded: { + rDiffuseItem = rDiffuseLoader.item + } + } } - Component.onCompleted: loaderDiffuseG.item.componentInfo = "diffuseG" - - Text { - id : gDiffuseText - text: ' G' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: gDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseG + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseG.item.componentInfo = "diffuseG" + + Text { + id : gDiffuseText + text: ' G' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - } - - // Right spacer - Item { - Layout.rowSpan: 3 - width: margin + indentation - } - - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: gDiffuseLoader - anchors.fill: parent - property double numberValue: model.data[5] - sourceComponent: spinZeroOne - onLoaded: { - gDiffuseItem = gDiffuseLoader.item + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: gDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[5] + sourceComponent: sliderZeroOne + onLoaded: { + gDiffuseItem = gDiffuseLoader.item + } } } } - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: bDiffuseText.width + indentation*3 - Loader { - id: loaderDiffuseB - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderDiffuseB.item.componentInfo = "diffuseB" - - Text { - id : bDiffuseText - text: ' B' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: bDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseB + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseB.item.componentInfo = "diffuseB" + + Text { + id : bDiffuseText + text: ' B' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: bDiffuseLoader - anchors.fill: parent - property double numberValue: model.data[6] - sourceComponent: spinZeroOne - onLoaded: { - bDiffuseItem = bDiffuseLoader.item + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: bDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[6] + sourceComponent: sliderZeroOne + onLoaded: { + bDiffuseItem = bDiffuseLoader.item + } } } - } - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: aDiffuseText.width + indentation*3 - Loader { - id: loaderDiffuseA - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: aDiffuseText.width + indentation*3 + Loader { + id: loaderDiffuseA + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDiffuseA.item.componentInfo = "diffuseA" + + Text { + id : aDiffuseText + text: ' A' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - Component.onCompleted: loaderDiffuseA.item.componentInfo = "diffuseA" - - Text { - id : aDiffuseText - text: ' A' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: aDiffuseLoader + anchors.fill: parent + property double numberValue: model.data[7] + sourceComponent: sliderZeroOne + onLoaded: { + aDiffuseItem = aDiffuseLoader.item + } + } } } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: aDiffuseLoader - anchors.fill: parent - property double numberValue: model.data[7] - sourceComponent: spinZeroOne - onLoaded: { - aDiffuseItem = aDiffuseLoader.item + RowLayout { + Layout.alignment: Qt.AlignHCenter + Button { + Layout.alignment: Qt.AlignHCenter + id: diffuseColor + text: qsTr("Diffuse Color") + onClicked: colorDialogDiffuse.open() + ColorDialog { + id: colorDialogDiffuse + title: "Choose a diffuse color" + visible: false + onAccepted: { + rDiffuseLoader.numberValue = colorDialogDiffuse.color.r + gDiffuseLoader.numberValue = colorDialogDiffuse.color.g + bDiffuseLoader.numberValue = colorDialogDiffuse.color.b + aDiffuseLoader.numberValue = colorDialogDiffuse.color.a + sendLight() + colorDialogDiffuse.close() + } + onRejected: { + colorDialogDiffuse.close() + } } } } - - Text { - Layout.columnSpan: 6 - text: " Attenuation" - color: "dimgrey" - width: margin + indentation - } - - // Left spacer - Item { - Layout.rowSpan: 3 - width: margin + indentation - } - - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: attRangeText.width + indentation*3 - Loader { - id: loaderAttRange - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderAttRange.item.componentInfo = "attRange" - + RowLayout { Text { - id : attRangeText - text: ' Range' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Layout.columnSpan: 6 + text: " Attenuation" + color: "dimgrey" + width: margin + indentation } } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: attRangeLoader - anchors.fill: parent - property double numberValue: model.data[8] - sourceComponent: spinZeroMax - onLoaded: { - attRangeItem = attRangeLoader.item + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attRangeText.width + indentation*3 + Loader { + id: loaderAttRange + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttRange.item.componentInfo = "attRange" + + Text { + id : attRangeText + text: ' Range' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent } } - } - - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: attLinearText.width + indentation*3 - Loader { - id: loaderAttLinear - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderAttLinear.item.componentInfo = "attLinear" - - Text { - id : attLinearText - text: ' Linear' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent - } - } - - // Right spacer - Item { - Layout.rowSpan: 3 - width: margin + indentation - } - - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: attLinearLoader - anchors.fill: parent - property double numberValue: model.data[9] - sourceComponent: spinZeroOne - onLoaded: { - attLinearItem = attLinearLoader.item + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attRangeLoader + anchors.fill: parent + property double numberValue: model.data[8] + sourceComponent: spinZeroMax + onLoaded: { + attRangeItem = attRangeLoader.item + } } } } - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: attConstantText.width + indentation*3 - Loader { - id: loaderAttConstant - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderAttConstant.item.componentInfo = "attConstant" - - Text { - id : attConstantText - text: ' Constant' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attLinearText.width + indentation*3 + Loader { + id: loaderAttLinear + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttLinear.item.componentInfo = "attLinear" + + Text { + id : attLinearText + text: ' Linear' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: attConstantLoader - anchors.fill: parent - property double numberValue: model.data[10] - sourceComponent: spinZeroOne - onLoaded: { - attConstantItem = attConstantLoader.item + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attLinearLoader + anchors.fill: parent + property double numberValue: model.data[9] + sourceComponent: sliderZeroOne + onLoaded: { + attLinearItem = attLinearLoader.item + } } } } - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: attQuadraticText.width + indentation*3 - Loader { - id: loaderAttQuadratic - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderAttQuadratic.item.componentInfo = "attQuadratic" - - Text { - id : attQuadraticText - text: ' Quadratic' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attConstantText.width + indentation*3 + Loader { + id: loaderAttConstant + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttConstant.item.componentInfo = "attConstant" + + Text { + id : attConstantText + text: ' Constant' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - } - Item { - Layout.fillWidth: true - height: 40 - Loader { - id: attQuadraticLoader - anchors.fill: parent - property double numberValue: model.data[11] - sourceComponent: spinZeroMax - onLoaded: { - attQuadraticItem = attQuadraticLoader.item + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attConstantLoader + anchors.fill: parent + property double numberValue: model.data[10] + sourceComponent: sliderZeroOne + onLoaded: { + attConstantItem = attConstantLoader.item + } } } } - - Rectangle { - color: "transparent" - height: 40 - Layout.preferredWidth: castShadowsText.width + indentation*3 - Loader { - id: loaderCastShadows - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: attQuadraticText.width + indentation*3 + Loader { + id: loaderAttQuadratic + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderAttQuadratic.item.componentInfo = "attQuadratic" + + Text { + id : attQuadraticText + text: ' Quadratic' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - Component.onCompleted: loaderCastShadows.item.componentInfo = "castshadows" - - Text { - id : castShadowsText - text: ' Cast shadows' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Item { + Layout.fillWidth: true + height: 40 + Loader { + id: attQuadraticLoader + anchors.fill: parent + property double numberValue: model.data[11] + sourceComponent: spinZeroMax + onLoaded: { + attQuadraticItem = attQuadraticLoader.item + } + } } } - Item { - Layout.fillWidth: true - height: 40 - - Switch { - id: booleanSwitchCastShadows - checked: model.data[12] - enabled: true - - onToggled: { - castShadowsItem = checked - sendLight() + RowLayout { + Rectangle { + color: "transparent" + height: 40 + Layout.preferredWidth: castShadowsText.width + indentation*3 + Loader { + id: loaderCastShadows + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderCastShadows.item.componentInfo = "castshadows" + + Text { + id : castShadowsText + text: ' Cast shadows' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent } } - } + Item { + Layout.fillWidth: true + height: 40 - Text { - visible: model.data[19] === 1 || model.data[19] === 2 - Layout.columnSpan: 6 - text: " Direction" - color: "dimgrey" - width: margin + indentation - } - - // Left spacer - Item { - visible: model.data[19] === 1 || model.data[19] === 2 - Layout.rowSpan: 3 - width: margin + indentation - } - - Rectangle { - visible: model.data[19] === 1 || model.data[19] === 2 - color: "transparent" - height: 40 - Layout.preferredWidth: xDirectionText.width + indentation*3 - Loader { - id: loaderDirectionX - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + Loader { + id: castShadowLoader + anchors.fill: parent + property double numberValue: model.data[12] + sourceComponent: ignSwitch + onLoaded: { + castShadowsItem = castShadowLoader.item + } + } } - Component.onCompleted: loaderDirectionX.item.componentInfo = "directionX" - + } + RowLayout { Text { visible: model.data[19] === 1 || model.data[19] === 2 - id : xDirectionText - text: ' X:' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Layout.columnSpan: 6 + text: " Direction" + color: "dimgrey" + width: margin + indentation } } - Item { - visible: model.data[19] === 1 || model.data[19] === 2 - Layout.fillWidth: true - height: 40 - Layout.columnSpan: 4 - Loader { - id: xDirectionLoader - anchors.fill: parent - property double numberValue: model.data[13] - sourceComponent: spinNoLimit - onLoaded: { - directionXItem = xDirectionLoader.item + RowLayout { + Rectangle { + visible: model.data[19] === 1 || model.data[19] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: xDirectionText.width + indentation*3 + Loader { + id: loaderDirectionX + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionX.item.componentInfo = "directionX" + + Text { + visible: model.data[19] === 1 || model.data[19] === 2 + id : xDirectionText + text: ' X:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent } } - } - - Rectangle { - visible: model.data[19] === 1 || model.data[19] === 2 - color: "transparent" - height: 40 - Layout.preferredWidth: yDirectionText.width + indentation*3 - Loader { - id: loaderDirectionY - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderDirectionY.item.componentInfo = "directionY" - - Text { + Item { visible: model.data[19] === 1 || model.data[19] === 2 - id : yDirectionText - text: ' Y:' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent - } - } - Item { - visible: model.data[19] === 1 || model.data[19] === 2 - Layout.fillWidth: true - height: 40 - Layout.columnSpan: 4 - Loader { - id: yDirectionLoader - anchors.fill: parent - property double numberValue: model.data[14] - sourceComponent: spinNoLimit - onLoaded: { - directionYItem = yDirectionLoader.item + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: xDirectionLoader + anchors.fill: parent + property double numberValue: model.data[13] + sourceComponent: spinNoLimit + onLoaded: { + directionXItem = xDirectionLoader.item + } } } } - - Rectangle { - visible: model.data[19] === 1 || model.data[19] === 2 - color: "transparent" - height: 40 - Layout.preferredWidth: zDirectionText.width + indentation*3 - Loader { - id: loaderDirectionZ - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + RowLayout { + Rectangle { + visible: model.data[19] === 1 || model.data[19] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: yDirectionText.width + indentation*3 + Loader { + id: loaderDirectionY + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionY.item.componentInfo = "directionY" + + Text { + visible: model.data[19] === 1 || model.data[19] === 2 + id : yDirectionText + text: ' Y:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - Component.onCompleted: loaderDirectionZ.item.componentInfo = "directionZ" - - Text { + Item { visible: model.data[19] === 1 || model.data[19] === 2 - id : zDirectionText - text: ' Z:' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: yDirectionLoader + anchors.fill: parent + property double numberValue: model.data[14] + sourceComponent: spinNoLimit + onLoaded: { + directionYItem = yDirectionLoader.item + } + } } } - Item { - visible: model.data[19] === 1 || model.data[19] === 2 - Layout.fillWidth: true - height: 40 - Layout.columnSpan: 4 - Loader { - id: zDirectionLoader - anchors.fill: parent - property double numberValue: model.data[15] - sourceComponent: spinNoLimit - onLoaded: { - directionZItem = zDirectionLoader.item + RowLayout { + Rectangle { + visible: model.data[19] === 1 || model.data[19] === 2 + color: "transparent" + height: 40 + Layout.preferredWidth: zDirectionText.width + indentation*3 + Loader { + id: loaderDirectionZ + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderDirectionZ.item.componentInfo = "directionZ" + + Text { + visible: model.data[19] === 1 || model.data[19] === 2 + id : zDirectionText + text: ' Z:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent } } - } - - Text { - visible: model.data[19] === 1 - Layout.columnSpan: 6 - text: " Spot features" - color: "dimgrey" - width: margin + indentation - } - - // Left spacer - Item { - visible: model.data[19] === 1 - Layout.rowSpan: 3 - width: margin + indentation - } - - Rectangle { - visible: model.data[19] === 1 - color: "transparent" - height: 40 - Layout.preferredWidth: innerAngleText.width + indentation*3 - Loader { - id: loaderInnerAngle - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + Item { + visible: model.data[19] === 1 || model.data[19] === 2 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: zDirectionLoader + anchors.fill: parent + property double numberValue: model.data[15] + sourceComponent: spinNoLimit + onLoaded: { + directionZItem = zDirectionLoader.item + } + } } - Component.onCompleted: loaderInnerAngle.item.componentInfo = "innerAngle" - + } + RowLayout { Text { visible: model.data[19] === 1 - id : innerAngleText - text: ' Inner Angle:' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Layout.columnSpan: 6 + text: " Spot features" + color: "dimgrey" + width: margin + indentation } } - Item { - visible: model.data[19] === 1 - Layout.fillWidth: true - height: 40 - Layout.columnSpan: 4 - Loader { - id: innerAngleLoader - anchors.fill: parent - property double numberValue: model.data[16] - sourceComponent: spinNoLimit - onLoaded: { - innerAngleItem = innerAngleLoader.item + RowLayout { + Rectangle { + visible: model.data[19] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: innerAngleText.width + indentation*3 + Loader { + id: loaderInnerAngle + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderInnerAngle.item.componentInfo = "innerAngle" + + Text { + visible: model.data[19] === 1 + id : innerAngleText + text: ' Inner Angle:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent } } - } - - Rectangle { - visible: model.data[19] === 1 - color: "transparent" - height: 40 - Layout.preferredWidth: outerAngleText.width + indentation*3 - Loader { - id: loaderOuterAngle - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon - } - Component.onCompleted: loaderOuterAngle.item.componentInfo = "outerAngle" - - Text { + Item { visible: model.data[19] === 1 - id : outerAngleText - text: ' Outer angle:' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent - } - } - Item { - visible: model.data[19] === 1 - Layout.fillWidth: true - height: 40 - Layout.columnSpan: 4 - Loader { - id: outerAngleLoader - anchors.fill: parent - property double numberValue: model.data[17] - sourceComponent: spinNoLimit - onLoaded: { - outerAngleItem = outerAngleLoader.item + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: innerAngleLoader + anchors.fill: parent + property double numberValue: model.data[16] + sourceComponent: spinNoLimit + onLoaded: { + innerAngleItem = innerAngleLoader.item + } } } } - Rectangle { - visible: model.data[19] === 1 - color: "transparent" - height: 40 - Layout.preferredWidth: fallOffText.width + indentation*3 - Loader { - id: loaderFallOff - width: iconWidth - height: iconHeight - y:10 - sourceComponent: plotIcon + RowLayout { + Rectangle { + visible: model.data[19] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: outerAngleText.width + indentation*3 + Loader { + id: loaderOuterAngle + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderOuterAngle.item.componentInfo = "outerAngle" + + Text { + visible: model.data[19] === 1 + id : outerAngleText + text: ' Outer angle:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } } - Component.onCompleted: loaderFallOff.item.componentInfo = "falloff" - - Text { + Item { visible: model.data[19] === 1 - id : fallOffText - text: ' Falloff:' - leftPadding: 5 - color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" - font.pointSize: 12 - anchors.centerIn: parent + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: outerAngleLoader + anchors.fill: parent + property double numberValue: model.data[17] + sourceComponent: spinNoLimit + onLoaded: { + outerAngleItem = outerAngleLoader.item + } + } } } - Item { - visible: model.data[19] === 1 - Layout.fillWidth: true - height: 40 - Layout.columnSpan: 4 - Loader { - id: fallOffLoader - anchors.fill: parent - property double numberValue: model.data[18] - sourceComponent: spinZeroMax - onLoaded: { - falloffItem = fallOffLoader.item + RowLayout { + Rectangle { + visible: model.data[19] === 1 + color: "transparent" + height: 40 + Layout.preferredWidth: fallOffText.width + indentation*3 + Loader { + id: loaderFallOff + width: iconWidth + height: iconHeight + y:10 + sourceComponent: plotIcon + } + Component.onCompleted: loaderFallOff.item.componentInfo = "falloff" + + Text { + visible: model.data[19] === 1 + id : fallOffText + text: ' Falloff:' + leftPadding: 5 + color: Material.theme == Material.Light ? "#444444" : "#bbbbbb" + font.pointSize: 12 + anchors.centerIn: parent + } + } + Item { + visible: model.data[19] === 1 + Layout.fillWidth: true + height: 40 + Layout.columnSpan: 4 + Loader { + id: fallOffLoader + anchors.fill: parent + property double numberValue: model.data[18] + sourceComponent: spinZeroMax + onLoaded: { + falloffItem = fallOffLoader.item + } } } } diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 1d6d6e6ab2..a50c4d6f51 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -733,32 +733,56 @@ bool LightCommand::Execute() return false; } - auto entity = this->iface->ecm->EntityByComponents( - components::Name(lightMsg->name()), - components::ParentEntity(this->iface->worldEntity)); + Entity lightEntity{kNullEntity}; + + if (lightMsg->id() != 0) + { + lightEntity = lightMsg->id(); + } + else if (!lightMsg->name().empty()) + { + if (lightMsg->parent_id() != 0) + { + lightEntity = this->iface->ecm->EntityByComponents( + components::Name(lightMsg->name()), + components::ParentEntity(lightMsg->parent_id())); + } + else + { + lightEntity = this->iface->ecm->EntityByComponents( + components::Name(lightMsg->name())); + } + } + if (kNullEntity == lightEntity) + { + ignerr << "Failed to find light with name [" << lightMsg->name() + << "], ID [" << lightMsg->id() << "] and parent ID [" + << lightMsg->parent_id() << "]." << std::endl; + return false; + } - auto lightComp = this->iface->ecm->Component(entity); + auto lightComp = this->iface->ecm->Component(lightEntity); if (nullptr == lightComp) { - entity = kNullEntity; + lightEntity = kNullEntity; // try to find the light inside a link - auto lightEnt = this->iface->ecm->EntityByComponents( + auto tempLightEnty = this->iface->ecm->EntityByComponents( components::Name(lightMsg->name())); - if (lightEnt != kNullEntity) + if (tempLightEnty != kNullEntity) { // check if light parent is a link auto parentComp = this->iface->ecm->Component( - lightEnt); + tempLightEnty); if (parentComp && this->iface->ecm->Component( parentComp->Data())) { - lightComp = this->iface->ecm->Component(lightEnt); - entity = lightEnt; + lightComp = this->iface->ecm->Component(tempLightEnty); + lightEntity = tempLightEnty; } } } - if (!entity) + if (!lightEntity) { ignmsg << "Failed to find light entity named [" << lightMsg->name() << "]." << std::endl; @@ -768,11 +792,11 @@ bool LightCommand::Execute() sdf::Light lightSDF = convert(*lightMsg); lightComp->Data() = lightSDF; - auto lightPose = this->iface->ecm->Component(entity); + auto lightPose = this->iface->ecm->Component(lightEntity); if (nullptr == lightPose) - entity = kNullEntity; + lightEntity = kNullEntity; - if (!entity) + if (!lightEntity) { ignmsg << "Pose component not available" << std::endl; return false; @@ -784,18 +808,18 @@ bool LightCommand::Execute() } auto lightCmdComp = - this->iface->ecm->Component(entity); + this->iface->ecm->Component(lightEntity); if (!lightCmdComp) { this->iface->ecm->CreateComponent( - entity, components::LightCmd(lightComp->Data())); + lightEntity, components::LightCmd(lightComp->Data())); } else { auto state = lightCmdComp->SetData(lightComp->Data(), this->lightEql) ? ComponentState::OneTimeChange : ComponentState::NoChange; - this->iface->ecm->SetChanged(entity, components::LightCmd::typeId, + this->iface->ecm->SetChanged(lightEntity, components::LightCmd::typeId, state); } From cadc2ba60ea02c9a1a8468a4f9ff9d152a6182f2 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 28 Dec 2020 18:09:39 +0100 Subject: [PATCH 25/42] Fixed tests Signed-off-by: ahcorde --- test/integration/user_commands.cc | 2 ++ 1 file changed, 2 insertions(+) diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 55d05517df..5b108169eb 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -704,6 +704,7 @@ TEST_F(UserCommandsTest, Light) msgs::Light req; req.set_name("point"); + req.set_parent_id(1); msgs::Boolean res; bool result; @@ -739,6 +740,7 @@ TEST_F(UserCommandsTest, Light) ignition::math::Color(0.2, 0.2, 0.2, 0.2)); req.set_range(2.6); req.set_name("point"); + req.set_parent_id(1); req.set_type(ignition::msgs::Light::POINT); req.set_attenuation_linear(0.7); req.set_attenuation_constant(0.6); From 89b603ab98c755cd82d97bc9ef4bd941a948a4a4 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 28 Dec 2020 18:13:09 +0100 Subject: [PATCH 26/42] make linters happy Signed-off-by: ahcorde --- src/systems/user_commands/UserCommands.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index a50c4d6f51..f180385632 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -776,7 +776,8 @@ bool LightCommand::Execute() if (parentComp && this->iface->ecm->Component( parentComp->Data())) { - lightComp = this->iface->ecm->Component(tempLightEnty); + lightComp = + this->iface->ecm->Component(tempLightEnty); lightEntity = tempLightEnty; } } From 57e7ca3630cedcc6a5b0e296b6adef8a17b01528 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 30 Dec 2020 11:04:46 +0100 Subject: [PATCH 27/42] Changed LightCmd to use msgs::Light Signed-off-by: ahcorde --- .../ignition/gazebo/components/LightCmd.hh | 17 +-- .../component_inspector/ComponentInspector.cc | 50 ++++---- .../component_inspector/ComponentInspector.hh | 4 +- src/gui/plugins/plotting/Plotting.cc | 46 ++++---- src/gui/plugins/plotting/Plotting.hh | 4 +- src/rendering/RenderUtil.cc | 107 ++++++++++++++---- src/systems/user_commands/UserCommands.cc | 74 +++++++----- 7 files changed, 186 insertions(+), 116 deletions(-) diff --git a/include/ignition/gazebo/components/LightCmd.hh b/include/ignition/gazebo/components/LightCmd.hh index 20ade522ec..fdba5858fc 100644 --- a/include/ignition/gazebo/components/LightCmd.hh +++ b/include/ignition/gazebo/components/LightCmd.hh @@ -21,29 +21,24 @@ #include #include - #include -#include "ignition/gazebo/components/Component.hh" +#include #include +#include + namespace ignition { namespace gazebo { // Inline bracket to help doxygen filtering. inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace serializers -{ - using LightCmdSerializer = - serializers::ComponentToMsgSerializer; -} - namespace components { /// \brief A component type that contains commanded light of an - /// entity in the world frame represented by sdf::Light. - using LightCmd = - Component; + /// entity in the world frame represented by msgs::Light. + using LightCmd = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LightCmd", LightCmd) } diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index c1ecdc13be..b09d2eeaf8 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -118,18 +118,18 @@ void ignition::gazebo::setData(QStandardItem *_item, const math::Pose3d &_data) ////////////////////////////////////////////////// template<> -void ignition::gazebo::setData(QStandardItem *_item, const sdf::Light &_data) +void ignition::gazebo::setData(QStandardItem *_item, const msgs::Light &_data) { int lightType = -1; - if (_data.Type() == sdf::LightType::POINT) + if (_data.type() == msgs::Light::POINT) { lightType = 0; } - else if (_data.Type() == sdf::LightType::SPOT) + else if (_data.type() == msgs::Light::SPOT) { lightType = 1; } - else if (_data.Type() == sdf::LightType::DIRECTIONAL) + else if (_data.type() == msgs::Light::DIRECTIONAL) { lightType = 2; } @@ -137,25 +137,25 @@ void ignition::gazebo::setData(QStandardItem *_item, const sdf::Light &_data) _item->setData(QString("Light"), ComponentsModel::RoleNames().key("dataType")); _item->setData(QList({ - QVariant(_data.Specular().R()), - QVariant(_data.Specular().G()), - QVariant(_data.Specular().B()), - QVariant(_data.Specular().A()), - QVariant(_data.Diffuse().R()), - QVariant(_data.Diffuse().G()), - QVariant(_data.Diffuse().B()), - QVariant(_data.Diffuse().A()), - QVariant(_data.AttenuationRange()), - QVariant(_data.LinearAttenuationFactor()), - QVariant(_data.ConstantAttenuationFactor()), - QVariant(_data.QuadraticAttenuationFactor()), - QVariant(_data.CastShadows()), - QVariant(_data.Direction().X()), - QVariant(_data.Direction().Y()), - QVariant(_data.Direction().Z()), - QVariant(_data.SpotInnerAngle().Radian()), - QVariant(_data.SpotOuterAngle().Radian()), - QVariant(_data.SpotFalloff()), + QVariant(_data.specular().r()), + QVariant(_data.specular().g()), + QVariant(_data.specular().b()), + QVariant(_data.specular().a()), + QVariant(_data.diffuse().r()), + QVariant(_data.diffuse().g()), + QVariant(_data.diffuse().b()), + QVariant(_data.diffuse().a()), + QVariant(_data.range()), + QVariant(_data.attenuation_linear()), + QVariant(_data.attenuation_constant()), + QVariant(_data.attenuation_quadratic()), + QVariant(_data.cast_shadows()), + QVariant(_data.direction().x()), + QVariant(_data.direction().y()), + QVariant(_data.direction().z()), + QVariant(_data.spot_inner_angle()), + QVariant(_data.spot_outer_angle()), + QVariant(_data.spot_falloff()), QVariant(lightType) }), ComponentsModel::RoleNames().key("data")); } @@ -568,12 +568,14 @@ void ComponentInspector::Update(const UpdateInfo &, { this->SetType("light"); auto comp = _ecm.Component(this->dataPtr->entity); + msgs::Light lightMsgs = convert(comp->Data()); if (comp) - setData(item, comp->Data()); + setData(item, lightMsgs); } else if (typeId == components::LightCmd::typeId) { auto comp = _ecm.Component(this->dataPtr->entity); + msgs::Light lightMsgs = comp->Data(); if (comp) setData(item, comp->Data()); } diff --git a/src/gui/plugins/component_inspector/ComponentInspector.hh b/src/gui/plugins/component_inspector/ComponentInspector.hh index 5a4f5c593b..677423a0db 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.hh +++ b/src/gui/plugins/component_inspector/ComponentInspector.hh @@ -28,7 +28,7 @@ #include #include -#include +#include Q_DECLARE_METATYPE(ignition::gazebo::ComponentTypeId) @@ -75,7 +75,7 @@ namespace gazebo /// \param[in] _item Item whose data will be set. /// \param[in] _data Data to set. template<> - void setData(QStandardItem *_item, const sdf::Light &_data); + void setData(QStandardItem *_item, const msgs::Light &_data); /// \brief Specialized to set vector data. /// \param[in] _item Item whose data will be set. diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index f65a7587c2..f7d5c275be 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -227,46 +227,46 @@ void Plotting::SetData(std::string _Id, const ignition::math::Vector3d &_vector) this->dataPtr->components[_Id]->SetAttributeValue("z", _vector.Z()); } -void Plotting::SetData(std::string _Id, const sdf::Light &_light) +void Plotting::SetData(std::string _Id, const msgs::Light &_light) { this->dataPtr->components[_Id]->SetAttributeValue("specularR", - _light.Specular().R()); + _light.specular().r()); this->dataPtr->components[_Id]->SetAttributeValue("specularG", - _light.Specular().G()); + _light.specular().g()); this->dataPtr->components[_Id]->SetAttributeValue("specularB", - _light.Specular().B()); + _light.specular().b()); this->dataPtr->components[_Id]->SetAttributeValue("specularA", - _light.Specular().A()); + _light.specular().a()); this->dataPtr->components[_Id]->SetAttributeValue("diffuseR", - _light.Diffuse().R()); + _light.diffuse().r()); this->dataPtr->components[_Id]->SetAttributeValue("diffuseG", - _light.Diffuse().G()); + _light.diffuse().g()); this->dataPtr->components[_Id]->SetAttributeValue("diffuseB", - _light.Diffuse().B()); + _light.diffuse().b()); this->dataPtr->components[_Id]->SetAttributeValue("diffuseA", - _light.Diffuse().A()); + _light.diffuse().a()); this->dataPtr->components[_Id]->SetAttributeValue("attRange", - _light.AttenuationRange()); + _light.range()); this->dataPtr->components[_Id]->SetAttributeValue("attLinear", - _light.LinearAttenuationFactor()); + _light.attenuation_linear()); this->dataPtr->components[_Id]->SetAttributeValue("attConstant", - _light.ConstantAttenuationFactor()); + _light.attenuation_constant()); this->dataPtr->components[_Id]->SetAttributeValue("attQuadratic", - _light.QuadraticAttenuationFactor()); + _light.attenuation_quadratic()); this->dataPtr->components[_Id]->SetAttributeValue("castshadows", - _light.CastShadows()); + _light.cast_shadows()); this->dataPtr->components[_Id]->SetAttributeValue("directionX", - _light.Direction().X()); + _light.direction().x()); this->dataPtr->components[_Id]->SetAttributeValue("directionY", - _light.Direction().Y()); + _light.direction().y()); this->dataPtr->components[_Id]->SetAttributeValue("directionZ", - _light.Direction().Z()); + _light.direction().z()); this->dataPtr->components[_Id]->SetAttributeValue("innerAngle", - _light.SpotInnerAngle().Radian()); + _light.spot_inner_angle()); this->dataPtr->components[_Id]->SetAttributeValue("outerAngle", - _light.SpotOuterAngle().Radian()); + _light.spot_outer_angle()); this->dataPtr->components[_Id]->SetAttributeValue("falloff", - _light.SpotFalloff()); + _light.spot_falloff()); } ////////////////////////////////////////////////// @@ -451,8 +451,10 @@ void Plotting ::Update(const ignition::gazebo::UpdateInfo &_info, else if (typeId == components::Light::typeId) { auto comp = _ecm.Component(entity); - if (comp) - this->SetData(component.first, comp->Data()); + if (comp){ + msgs::Light lightMsgs = convert(comp->Data()); + this->SetData(component.first, lightMsgs); + } } else if (typeId == components::LightCmd::typeId) { diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index faab999706..a5d5ced80d 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -24,7 +24,7 @@ #include #include -#include +#include #include #include @@ -119,7 +119,7 @@ class Plotting : public ignition::gazebo::GuiSystem /// \param [in] _Id Component Key of the components map /// \param [in] _light Vector Data to be set to the component public: void SetData(std::string _Id, - const sdf::Light &_light); + const msgs::Light &_light); /// \brief Set the Component data of giving id to the giving pose /// \param [in] _Id Component Key of the components map diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 7640e06668..f3c5fb3a10 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -38,6 +38,8 @@ #include #include +#include + #include #include #include @@ -165,7 +167,7 @@ class ignition::gazebo::RenderUtilPrivate public: std::unordered_map entityPoses; /// \brief A map of entity ids and light updates. - public: std::unordered_map entityLights; + public: std::unordered_map entityLights; /// \brief A map of entity ids and light updates. public: std::vector entityLightsCmdToDelete; @@ -207,6 +209,36 @@ class ignition::gazebo::RenderUtilPrivate public: std::function createSensorCb; + /// \brief Light equality comparison function. + public: std::function + lightEql { [](const sdf::Light &_a, const sdf::Light &_b) + { + return + _a.Type() == _b.Type() && + _a.Name() == _b.Name() && + _a.Diffuse() == _b.Diffuse() && + _a.Specular() == _b.Specular() && + math::equal( + _a.AttenuationRange(), _b.AttenuationRange(), 1e-6) && + math::equal( + _a.LinearAttenuationFactor(), + _b.LinearAttenuationFactor(), + 1e-6) && + math::equal( + _a.ConstantAttenuationFactor(), + _b.ConstantAttenuationFactor(), + 1e-6) && + math::equal( + _a.QuadraticAttenuationFactor(), + _b.QuadraticAttenuationFactor(), + 1e-6) && + _a.CastShadows() == _b.CastShadows() && + _a.Direction() == _b.Direction() && + _a.SpotInnerAngle() == _b.SpotInnerAngle() && + _a.SpotOuterAngle() == _b.SpotOuterAngle() && + math::equal(_a.SpotFalloff(), _b.SpotFalloff(), 1e-6); + }}; + /// \brief Callback function for removing sensors. /// The function arg is the entity id public: std::function removeSensorCb; @@ -258,6 +290,17 @@ void RenderUtil::UpdateECM(const UpdateInfo &, { this->dataPtr->entityLights[_entity] = _lightCmd->Data(); this->dataPtr->entityLightsCmdToDelete.push_back(_entity); + + auto lightComp = _ecm.Component(_entity); + if (lightComp) + { + sdf::Light sdfLight = convert(_lightCmd->Data()); + auto state = lightComp->SetData(sdfLight, + this->dataPtr->lightEql) ? + ComponentState::OneTimeChange : + ComponentState::NoChange; + _ecm.SetChanged(_entity, components::Light::typeId, state); + } return true; }); @@ -470,54 +513,68 @@ void RenderUtil::Update() auto l = std::dynamic_pointer_cast(node); if (l) { - if (l->DiffuseColor() != light.second.Diffuse()) - l->SetDiffuseColor(light.second.Diffuse()); - if (l->SpecularColor() != light.second.Specular()) - l->SetSpecularColor(light.second.Specular()); + if (l->DiffuseColor() != msgs::Convert(light.second.diffuse())) + l->SetDiffuseColor(msgs::Convert(light.second.diffuse())); + if (l->SpecularColor() != msgs::Convert(light.second.specular())) + { + l->SetSpecularColor(msgs::Convert(light.second.specular())); + } if (ignition::math::equal( - l->AttenuationRange(), light.second.AttenuationRange())) + l->AttenuationRange(), + static_cast(light.second.range()))) { - l->SetAttenuationRange(light.second.AttenuationRange()); + l->SetAttenuationRange(light.second.range()); } if (ignition::math::equal( - l->AttenuationLinear(), light.second.LinearAttenuationFactor())) + l->AttenuationLinear(), + static_cast(light.second.attenuation_linear()))) { - l->SetAttenuationLinear(light.second.LinearAttenuationFactor()); + l->SetAttenuationLinear(light.second.attenuation_linear()); } if (ignition::math::equal( - l->AttenuationConstant(), light.second.ConstantAttenuationFactor())) + l->AttenuationConstant(), + static_cast(light.second.attenuation_constant()))) { - l->SetAttenuationConstant(light.second.ConstantAttenuationFactor()); + l->SetAttenuationConstant(light.second.attenuation_constant()); } if (ignition::math::equal( l->AttenuationQuadratic(), - light.second.QuadraticAttenuationFactor())) + static_cast(light.second.attenuation_quadratic()))) { - l->SetAttenuationQuadratic(light.second.QuadraticAttenuationFactor()); + l->SetAttenuationQuadratic(light.second.attenuation_quadratic()); } - if (l->CastShadows() != light.second.CastShadows()) - l->SetCastShadows(light.second.CastShadows()); + if (l->CastShadows() != light.second.cast_shadows()) + l->SetCastShadows(light.second.cast_shadows()); auto lDirectional = std::dynamic_pointer_cast(node); if (lDirectional) { - if (lDirectional->Direction() != light.second.Direction()) - lDirectional->SetDirection(light.second.Direction()); + if (lDirectional->Direction() != + msgs::Convert(light.second.direction())) + { + lDirectional->SetDirection( + msgs::Convert(light.second.direction())); + } } auto lSpotLight = std::dynamic_pointer_cast(node); if (lSpotLight) { - if (lSpotLight->Direction() != light.second.Direction()) - lSpotLight->SetDirection(light.second.Direction()); - if (lSpotLight->InnerAngle() != light.second.SpotInnerAngle()) - lSpotLight->SetInnerAngle(light.second.SpotInnerAngle()); - if (lSpotLight->OuterAngle() != light.second.SpotOuterAngle()) - lSpotLight->SetOuterAngle(light.second.SpotOuterAngle()); + if (lSpotLight->Direction() != + msgs::Convert(light.second.direction())) + { + lSpotLight->SetDirection( + msgs::Convert(light.second.direction())); + } + if (lSpotLight->InnerAngle() != light.second.spot_inner_angle()) + lSpotLight->SetInnerAngle(light.second.spot_inner_angle()); + if (lSpotLight->OuterAngle() != light.second.spot_outer_angle()) + lSpotLight->SetOuterAngle(light.second.spot_outer_angle()); if (ignition::math::equal( - lSpotLight->Falloff(), light.second.SpotFalloff())) + lSpotLight->Falloff(), + static_cast(light.second.spot_falloff()))) { - lSpotLight->SetFalloff(light.second.SpotFalloff()); + lSpotLight->SetFalloff(light.second.spot_falloff()); } } } diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index f180385632..fdddff6e8d 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -140,37 +140,54 @@ class LightCommand : public UserCommandBase public: bool Execute() final; /// \brief Light equality comparison function. - public: std::function - lightEql { [](const sdf::Light &_a, const sdf::Light &_b) + public: std::function + lightEql { [](const msgs::Light &_a, const msgs::Light &_b) { return - _a.Type() == _b.Type() && - _a.Name() == _b.Name() && - _a.Diffuse() == _b.Diffuse() && - _a.Specular() == _b.Specular() && + _a.type() == _b.type() && + _a.name() == _b.name() && math::equal( - _a.AttenuationRange(), _b.AttenuationRange(), 1e-6) && + _a.diffuse().a(), _b.diffuse().a(), 1e-6f) && + math::equal( + _a.diffuse().r(), _b.diffuse().r(), 1e-6f) && + math::equal( + _a.diffuse().g(), _b.diffuse().g(), 1e-6f) && + math::equal( + _a.diffuse().b(), _b.diffuse().b(), 1e-6f) && + math::equal( + _a.specular().a(), _b.specular().a(), 1e-6f) && + math::equal( + _a.specular().r(), _b.specular().r(), 1e-6f) && + math::equal( + _a.specular().g(), _b.specular().g(), 1e-6f) && + math::equal( + _a.specular().b(), _b.specular().b(), 1e-6f) && + math::equal( + _a.range(), _b.range(), 1e-6f) && + math::equal( + _a.attenuation_linear(), + _b.attenuation_linear(), + 1e-6f) && + math::equal( + _a.attenuation_constant(), + _b.attenuation_constant(), + 1e-6f) && + math::equal( + _a.attenuation_quadratic(), + _b.attenuation_quadratic(), + 1e-6f) && + _a.cast_shadows() == _b.cast_shadows() && math::equal( - _a.LinearAttenuationFactor(), - _b.LinearAttenuationFactor(), - 1e-6) && + _a.direction().x(), _b.direction().x(), 1e-6) && math::equal( - _a.ConstantAttenuationFactor(), - _b.ConstantAttenuationFactor(), - 1e-6) && + _a.direction().y(), _b.direction().y(), 1e-6) && math::equal( - _a.ConstantAttenuationFactor(), - _b.ConstantAttenuationFactor(), - 1e-6) && + _a.direction().z(), _b.direction().z(), 1e-6) && math::equal( - _a.QuadraticAttenuationFactor(), - _b.QuadraticAttenuationFactor(), - 1e-6) && - _a.CastShadows() == _b.CastShadows() && - _a.Direction() == _b.Direction() && - _a.SpotInnerAngle() == _b.SpotInnerAngle() && - _a.SpotOuterAngle() == _b.SpotOuterAngle() && - math::equal(_a.SpotFalloff(), _b.SpotFalloff(), 1e-6); + _a.spot_inner_angle(), _b.spot_inner_angle(), 1e-6f) && + math::equal( + _a.spot_outer_angle(), _b.spot_outer_angle(), 1e-6f) && + math::equal(_a.spot_falloff(), _b.spot_falloff(), 1e-6f); }}; }; @@ -790,9 +807,6 @@ bool LightCommand::Execute() return false; } - sdf::Light lightSDF = convert(*lightMsg); - lightComp->Data() = lightSDF; - auto lightPose = this->iface->ecm->Component(lightEntity); if (nullptr == lightPose) lightEntity = kNullEntity; @@ -813,15 +827,15 @@ bool LightCommand::Execute() if (!lightCmdComp) { this->iface->ecm->CreateComponent( - lightEntity, components::LightCmd(lightComp->Data())); + lightEntity, components::LightCmd(*lightMsg)); } else { - auto state = lightCmdComp->SetData(lightComp->Data(), this->lightEql) ? + auto state = lightCmdComp->SetData(*lightMsg, this->lightEql) ? ComponentState::OneTimeChange : ComponentState::NoChange; this->iface->ecm->SetChanged(lightEntity, components::LightCmd::typeId, - state); + state); } return true; From 1b0b091d6b1e81a63665ff7eb082d7e8a4221ef9 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 12 Jan 2021 08:36:54 +0100 Subject: [PATCH 28/42] Removed LightCmd from Plotting class Signed-off-by: ahcorde --- src/gui/plugins/plotting/Plotting.cc | 7 ------- 1 file changed, 7 deletions(-) diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index f7d5c275be..4c4936ae01 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -24,7 +24,6 @@ #include "ignition/gazebo/components/Factory.hh" #include "ignition/gazebo/components/Gravity.hh" #include "ignition/gazebo/components/Light.hh" -#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/LinearAcceleration.hh" #include "ignition/gazebo/components/LinearVelocity.hh" #include "ignition/gazebo/components/LinearVelocitySeed.hh" @@ -456,12 +455,6 @@ void Plotting ::Update(const ignition::gazebo::UpdateInfo &_info, this->SetData(component.first, lightMsgs); } } - else if (typeId == components::LightCmd::typeId) - { - auto comp = _ecm.Component(entity); - if (comp) - this->SetData(component.first, comp->Data()); - } for (auto attribute : component.second->Data()) { From 0c783056974500a28749f81991a9fcfe258e5937 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 12 Jan 2021 08:37:28 +0100 Subject: [PATCH 29/42] Fixed GUI when a color is picked through the color palette Signed-off-by: ahcorde --- src/gui/plugins/component_inspector/Light.qml | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/gui/plugins/component_inspector/Light.qml b/src/gui/plugins/component_inspector/Light.qml index ffaced1293..68314d7053 100644 --- a/src/gui/plugins/component_inspector/Light.qml +++ b/src/gui/plugins/component_inspector/Light.qml @@ -445,10 +445,10 @@ Rectangle { title: "Choose a specular color" visible: false onAccepted: { - rSpecularLoader.numberValue = colorDialog.color.r - gSpecularLoader.numberValue = colorDialog.color.g - bSpecularLoader.numberValue = colorDialog.color.b - aSpecularLoader.numberValue = colorDialog.color.a + rSpecularLoader.item.value = colorDialog.color.r + gSpecularLoader.item.value = colorDialog.color.g + bSpecularLoader.item.value = colorDialog.color.b + aSpecularLoader.item.value = colorDialog.color.a sendLight() colorDialog.close() } @@ -622,10 +622,10 @@ Rectangle { title: "Choose a diffuse color" visible: false onAccepted: { - rDiffuseLoader.numberValue = colorDialogDiffuse.color.r - gDiffuseLoader.numberValue = colorDialogDiffuse.color.g - bDiffuseLoader.numberValue = colorDialogDiffuse.color.b - aDiffuseLoader.numberValue = colorDialogDiffuse.color.a + rDiffuseLoader.item.value = colorDialogDiffuse.color.r + gDiffuseLoader.item.value = colorDialogDiffuse.color.g + bDiffuseLoader.item.value = colorDialogDiffuse.color.b + aDiffuseLoader.item.value = colorDialogDiffuse.color.a sendLight() colorDialogDiffuse.close() } From 69d9d6660d349b91b254f50e78352b7391014480 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 12 Jan 2021 08:57:07 +0100 Subject: [PATCH 30/42] Removed LightCmd form component inspector Signed-off-by: ahcorde --- src/gui/plugins/component_inspector/ComponentInspector.cc | 7 ------- 1 file changed, 7 deletions(-) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index b09d2eeaf8..fb10db6121 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -572,13 +572,6 @@ void ComponentInspector::Update(const UpdateInfo &, if (comp) setData(item, lightMsgs); } - else if (typeId == components::LightCmd::typeId) - { - auto comp = _ecm.Component(this->dataPtr->entity); - msgs::Light lightMsgs = comp->Data(); - if (comp) - setData(item, comp->Data()); - } else if (typeId == components::Pose::typeId) { auto comp = _ecm.Component(this->dataPtr->entity); From e3169263a6a04741890f41bc284c4964a1e2c858 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 26 Jan 2021 21:23:42 +0100 Subject: [PATCH 31/42] Added feedback Signed-off-by: ahcorde --- include/ignition/gazebo/Model.hh | 2 -- src/Model.cc | 1 - src/gui/plugins/component_inspector/ComponentInspector.cc | 6 ++++++ src/gui/plugins/plotting/Plotting.cc | 4 +++- src/gui/plugins/plotting/Plotting.hh | 2 -- 5 files changed, 9 insertions(+), 6 deletions(-) diff --git a/include/ignition/gazebo/Model.hh b/include/ignition/gazebo/Model.hh index 1528cd61e7..89450cb45c 100644 --- a/include/ignition/gazebo/Model.hh +++ b/include/ignition/gazebo/Model.hh @@ -28,8 +28,6 @@ #include #include -#include - namespace ignition { namespace gazebo diff --git a/src/Model.cc b/src/Model.cc index 7c90f06933..9981110f1f 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -16,7 +16,6 @@ */ #include "ignition/gazebo/components/Joint.hh" -#include "ignition/gazebo/components/LightCmd.hh" #include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index fb10db6121..6aa2ddc8f3 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -830,6 +830,12 @@ void ComponentInspector::OnLight( auto lightConfigService = "/world/" + this->dataPtr->worldName + "/light_config"; + lightConfigService = transport::TopicUtils::AsValidTopic(lightConfigService); + if (lightConfigService.empty()) + { + ignerr << "Invalid light command service topic provided" << std::endl; + return; + } this->dataPtr->node.Request(lightConfigService, req, cb); } diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index 4c4936ae01..80bc40d57c 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -35,6 +35,7 @@ #include "ignition/gazebo/components/WindMode.hh" #include "ignition/gazebo/components/World.hh" #include "ignition/gazebo/EntityComponentManager.hh" +#include namespace ignition::gazebo { @@ -450,7 +451,8 @@ void Plotting ::Update(const ignition::gazebo::UpdateInfo &_info, else if (typeId == components::Light::typeId) { auto comp = _ecm.Component(entity); - if (comp){ + if (comp) + { msgs::Light lightMsgs = convert(comp->Data()); this->SetData(component.first, lightMsgs); } diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index a5d5ced80d..ad2d1c3dc1 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -24,8 +24,6 @@ #include #include -#include - #include #include #include From d6f0c5f28a297abf61c89118ba4ebd02012fde1d Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 26 Jan 2021 22:11:43 +0100 Subject: [PATCH 32/42] Added feedback Signed-off-by: ahcorde --- src/gui/plugins/plotting/Plotting.cc | 1 - src/gui/plugins/plotting/Plotting.hh | 2 ++ 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index 80bc40d57c..b58d272950 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -35,7 +35,6 @@ #include "ignition/gazebo/components/WindMode.hh" #include "ignition/gazebo/components/World.hh" #include "ignition/gazebo/EntityComponentManager.hh" -#include namespace ignition::gazebo { diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index ad2d1c3dc1..a5d5ced80d 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -24,6 +24,8 @@ #include #include +#include + #include #include #include From 7b6d922a73777f9ffb4cab09593ca724e3c8234e Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 15:20:33 +0100 Subject: [PATCH 33/42] Added feedback Signed-off-by: ahcorde --- src/gui/plugins/plotting/Plotting.cc | 53 +++++++++++++---------- src/gui/plugins/plotting/Plotting.hh | 3 +- src/rendering/RenderUtil.cc | 46 ++++++++++++-------- src/systems/user_commands/UserCommands.cc | 33 ++++---------- test/integration/model.cc | 4 -- 5 files changed, 70 insertions(+), 69 deletions(-) diff --git a/src/gui/plugins/plotting/Plotting.cc b/src/gui/plugins/plotting/Plotting.cc index b58d272950..e21e0db118 100644 --- a/src/gui/plugins/plotting/Plotting.cc +++ b/src/gui/plugins/plotting/Plotting.cc @@ -228,22 +228,28 @@ void Plotting::SetData(std::string _Id, const ignition::math::Vector3d &_vector) void Plotting::SetData(std::string _Id, const msgs::Light &_light) { - this->dataPtr->components[_Id]->SetAttributeValue("specularR", - _light.specular().r()); - this->dataPtr->components[_Id]->SetAttributeValue("specularG", - _light.specular().g()); - this->dataPtr->components[_Id]->SetAttributeValue("specularB", - _light.specular().b()); - this->dataPtr->components[_Id]->SetAttributeValue("specularA", - _light.specular().a()); - this->dataPtr->components[_Id]->SetAttributeValue("diffuseR", - _light.diffuse().r()); - this->dataPtr->components[_Id]->SetAttributeValue("diffuseG", - _light.diffuse().g()); - this->dataPtr->components[_Id]->SetAttributeValue("diffuseB", - _light.diffuse().b()); - this->dataPtr->components[_Id]->SetAttributeValue("diffuseA", - _light.diffuse().a()); + if (_light.has_specular()) + { + this->dataPtr->components[_Id]->SetAttributeValue("specularR", + _light.specular().r()); + this->dataPtr->components[_Id]->SetAttributeValue("specularG", + _light.specular().g()); + this->dataPtr->components[_Id]->SetAttributeValue("specularB", + _light.specular().b()); + this->dataPtr->components[_Id]->SetAttributeValue("specularA", + _light.specular().a()); + } + if (_light.has_diffuse()) + { + this->dataPtr->components[_Id]->SetAttributeValue("diffuseR", + _light.diffuse().r()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseG", + _light.diffuse().g()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseB", + _light.diffuse().b()); + this->dataPtr->components[_Id]->SetAttributeValue("diffuseA", + _light.diffuse().a()); + } this->dataPtr->components[_Id]->SetAttributeValue("attRange", _light.range()); this->dataPtr->components[_Id]->SetAttributeValue("attLinear", @@ -254,12 +260,15 @@ void Plotting::SetData(std::string _Id, const msgs::Light &_light) _light.attenuation_quadratic()); this->dataPtr->components[_Id]->SetAttributeValue("castshadows", _light.cast_shadows()); - this->dataPtr->components[_Id]->SetAttributeValue("directionX", - _light.direction().x()); - this->dataPtr->components[_Id]->SetAttributeValue("directionY", - _light.direction().y()); - this->dataPtr->components[_Id]->SetAttributeValue("directionZ", - _light.direction().z()); + if (_light.has_direction()) + { + this->dataPtr->components[_Id]->SetAttributeValue("directionX", + _light.direction().x()); + this->dataPtr->components[_Id]->SetAttributeValue("directionY", + _light.direction().y()); + this->dataPtr->components[_Id]->SetAttributeValue("directionZ", + _light.direction().z()); + } this->dataPtr->components[_Id]->SetAttributeValue("innerAngle", _light.spot_inner_angle()); this->dataPtr->components[_Id]->SetAttributeValue("outerAngle", diff --git a/src/gui/plugins/plotting/Plotting.hh b/src/gui/plugins/plotting/Plotting.hh index a5d5ced80d..186ad902b2 100644 --- a/src/gui/plugins/plotting/Plotting.hh +++ b/src/gui/plugins/plotting/Plotting.hh @@ -23,8 +23,7 @@ #include #include #include - -#include +#include #include #include diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 267f9acba0..a40279ba85 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -513,31 +513,37 @@ void RenderUtil::Update() auto l = std::dynamic_pointer_cast(node); if (l) { - if (l->DiffuseColor() != msgs::Convert(light.second.diffuse())) - l->SetDiffuseColor(msgs::Convert(light.second.diffuse())); - if (l->SpecularColor() != msgs::Convert(light.second.specular())) + if (light.second.has_diffuse()) { - l->SetSpecularColor(msgs::Convert(light.second.specular())); + if (l->DiffuseColor() != msgs::Convert(light.second.diffuse())) + l->SetDiffuseColor(msgs::Convert(light.second.diffuse())); } - if (ignition::math::equal( + if (light.second.has_specular()) + { + if (l->SpecularColor() != msgs::Convert(light.second.specular())) + { + l->SetSpecularColor(msgs::Convert(light.second.specular())); + } + } + if (!ignition::math::equal( l->AttenuationRange(), static_cast(light.second.range()))) { l->SetAttenuationRange(light.second.range()); } - if (ignition::math::equal( + if (!ignition::math::equal( l->AttenuationLinear(), static_cast(light.second.attenuation_linear()))) { l->SetAttenuationLinear(light.second.attenuation_linear()); } - if (ignition::math::equal( + if (!ignition::math::equal( l->AttenuationConstant(), static_cast(light.second.attenuation_constant()))) { l->SetAttenuationConstant(light.second.attenuation_constant()); } - if (ignition::math::equal( + if (!ignition::math::equal( l->AttenuationQuadratic(), static_cast(light.second.attenuation_quadratic()))) { @@ -549,28 +555,34 @@ void RenderUtil::Update() std::dynamic_pointer_cast(node); if (lDirectional) { - if (lDirectional->Direction() != - msgs::Convert(light.second.direction())) + if (light.second.has_direction()) { - lDirectional->SetDirection( - msgs::Convert(light.second.direction())); + if (lDirectional->Direction() != + msgs::Convert(light.second.direction())) + { + lDirectional->SetDirection( + msgs::Convert(light.second.direction())); + } } } auto lSpotLight = std::dynamic_pointer_cast(node); if (lSpotLight) { - if (lSpotLight->Direction() != - msgs::Convert(light.second.direction())) + if (light.second.has_direction()) { - lSpotLight->SetDirection( - msgs::Convert(light.second.direction())); + if (lSpotLight->Direction() != + msgs::Convert(light.second.direction())) + { + lSpotLight->SetDirection( + msgs::Convert(light.second.direction())); + } } if (lSpotLight->InnerAngle() != light.second.spot_inner_angle()) lSpotLight->SetInnerAngle(light.second.spot_inner_angle()); if (lSpotLight->OuterAngle() != light.second.spot_outer_angle()) lSpotLight->SetOuterAngle(light.second.spot_outer_angle()); - if (ignition::math::equal( + if (!ignition::math::equal( lSpotLight->Falloff(), static_cast(light.second.spot_falloff()))) { diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index cc007d3131..e84b573115 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -336,6 +336,13 @@ void UserCommands::Configure(const Entity &_entity, // Light service std::string lightService{"/world/" + worldName + "/light_config"}; + lightService = transport::TopicUtils::AsValidTopic(lightService); + if (lightService.empty()) + { + ignerr << "Invalid light config service topic provided" << std::endl; + return; + } + this->dataPtr->node.Advertise(lightService, &UserCommandsPrivate::LightService, this->dataPtr.get()); @@ -779,13 +786,13 @@ bool LightCommand::Execute() Entity lightEntity{kNullEntity}; - if (lightMsg->id() != 0) + if (lightMsg->id() != kNullEntity) { lightEntity = lightMsg->id(); } else if (!lightMsg->name().empty()) { - if (lightMsg->parent_id() != 0) + if (lightMsg->parent_id() != kNullEntity) { lightEntity = this->iface->ecm->EntityByComponents( components::Name(lightMsg->name()), @@ -805,28 +812,6 @@ bool LightCommand::Execute() return false; } - auto lightComp = this->iface->ecm->Component(lightEntity); - if (nullptr == lightComp) - { - lightEntity = kNullEntity; - // try to find the light inside a link - auto tempLightEnty = this->iface->ecm->EntityByComponents( - components::Name(lightMsg->name())); - if (tempLightEnty != kNullEntity) - { - // check if light parent is a link - auto parentComp = this->iface->ecm->Component( - tempLightEnty); - if (parentComp && this->iface->ecm->Component( - parentComp->Data())) - { - lightComp = - this->iface->ecm->Component(tempLightEnty); - lightEntity = tempLightEnty; - } - } - } - if (!lightEntity) { ignmsg << "Failed to find light entity named [" << lightMsg->name() diff --git a/test/integration/model.cc b/test/integration/model.cc index 0fb534a36f..008bd7ddf8 100644 --- a/test/integration/model.cc +++ b/test/integration/model.cc @@ -23,8 +23,6 @@ #include #include #include -#include -#include #include #include #include @@ -35,8 +33,6 @@ #include #include -#include - using namespace ignition; using namespace gazebo; From 5eb2bb1fd95e9a235069b97ea41532eb390ffd6f Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 15:58:28 +0100 Subject: [PATCH 34/42] improved variable name Signed-off-by: ahcorde --- src/rendering/RenderUtil.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index a40279ba85..3d2bf2b37f 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -280,7 +280,7 @@ void RenderUtil::UpdateECM(const UpdateInfo &, { std::lock_guard lock(this->dataPtr->updateMutex); - auto entityLightsCmdToDelete = + auto olderEntitiesLightsCmdToDelete = std::move(this->dataPtr->entityLightsCmdToDelete); this->dataPtr->entityLightsCmdToDelete.clear(); @@ -304,7 +304,7 @@ void RenderUtil::UpdateECM(const UpdateInfo &, return true; }); - for (const auto entity : entityLightsCmdToDelete) + for (const auto entity : olderEntitiesLightsCmdToDelete) { _ecm.RemoveComponent(entity); } From 53f045b9db8da14504f482ae1bc0b1f2ce91cf4d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 2 Feb 2021 23:10:42 +0100 Subject: [PATCH 35/42] Added light tutorial and example (#515) * Added light tutorial and example Signed-off-by: ahcorde * Added some feedback Signed-off-by: ahcorde * Split tutorial in two Signed-off-by: ahcorde * remove ids from tutorial Signed-off-by: ahcorde * Added feedback Signed-off-by: ahcorde * update tutorial Signed-off-by: ahcorde Co-authored-by: Louise Poubel --- .../standalone/light_control/CMakeLists.txt | 12 ++ .../standalone/light_control/light_control.cc | 179 ++++++++++++++++++ tutorials.md.in | 1 + tutorials/light_config.md | 45 +++++ 4 files changed, 237 insertions(+) create mode 100644 examples/standalone/light_control/CMakeLists.txt create mode 100644 examples/standalone/light_control/light_control.cc create mode 100644 tutorials/light_config.md diff --git a/examples/standalone/light_control/CMakeLists.txt b/examples/standalone/light_control/CMakeLists.txt new file mode 100644 index 0000000000..be27581c40 --- /dev/null +++ b/examples/standalone/light_control/CMakeLists.txt @@ -0,0 +1,12 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) + +find_package(ignition-transport9 QUIET REQUIRED OPTIONAL_COMPONENTS log) +set(IGN_TRANSPORT_VER ${ignition-transport9_VERSION_MAJOR}) + +find_package(ignition-gazebo4 REQUIRED) +set(IGN_GAZEBO_VER ${ignition-gazebo4_VERSION_MAJOR}) + +add_executable(light_control light_control.cc) +target_link_libraries(light_control + ignition-transport${IGN_TRANSPORT_VER}::core + ignition-gazebo${IGN_GAZEBO_VER}::ignition-gazebo${IGN_GAZEBO_VER}) diff --git a/examples/standalone/light_control/light_control.cc b/examples/standalone/light_control/light_control.cc new file mode 100644 index 0000000000..4f499787c2 --- /dev/null +++ b/examples/standalone/light_control/light_control.cc @@ -0,0 +1,179 @@ +/* + * Copyright (C) 2020 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 +#include +#include + +using namespace std::chrono_literals; + +// Create a transport node. +ignition::transport::Node node; + +bool result; +// timeout used for services +constexpr unsigned int timeout = 5000; + +std::mt19937 twister(std::time(0)); +std::uniform_real_distribution distr(0, 1000); +constexpr double epsilon = 0.1; + +float directionX = 0.5; +float directionY = 0.2; +float directionZ = -0.9; + +void createLight() +{ + ignition::msgs::Boolean rep; +//! [create light] + ignition::msgs::EntityFactory entityFactoryRequest; + + entityFactoryRequest.mutable_light()->set_name("point"); + entityFactoryRequest.mutable_light()->set_range(4); + entityFactoryRequest.mutable_light()->set_attenuation_linear(0.5); + entityFactoryRequest.mutable_light()->set_attenuation_constant(0.2); + entityFactoryRequest.mutable_light()->set_attenuation_quadratic(0.01); + entityFactoryRequest.mutable_light()->set_cast_shadows(false); + entityFactoryRequest.mutable_light()->set_type(ignition::msgs::Light::POINT); + ignition::msgs::Set( + entityFactoryRequest.mutable_light()->mutable_direction(), + ignition::math::Vector3d(directionX, directionY, directionZ)); + ignition::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(), + ignition::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0)); +//! [create light] + + bool executedEntityFactory = node.Request("/world/empty/create", + entityFactoryRequest, timeout, rep, result); + if (executedEntityFactory) + { + if (result) + std::cout << "Light was created : [" << rep.data() << "]" << std::endl; + else + { + std::cout << "Service call failed" << std::endl; + return; + } + } + else + std::cerr << "Service call timed out" << std::endl; +} + +void createSphere() +{ + auto modelStr = R"( + + + + + 0 0 0.5 0 0 0 + + 1 + + + 1 + + + + )"; + + ignition::msgs::EntityFactory req; + ignition::msgs::Boolean res; + req.set_sdf(modelStr); + + bool executed = node.Request("/world/empty/create", + req, timeout, res, result); + if (executed) + { + if (result) + std::cout << "Sphere was created : [" << res.data() << "]" << std::endl; + else + { + std::cout << "Service call failed" << std::endl; + return; + } + } + else + std::cerr << "Service call timed out" << std::endl; +} + +////////////////////////////////////////////////// +int main(int argc, char **argv) +{ + ignition::msgs::Boolean rep; + ignition::msgs::Light lightRequest; + auto lightConfigService = "/world/empty/light_config"; + + createSphere(); + createLight(); + + while (1) + { + float r, g, b; + double m = 0; +//! [random numbers] + while (m < epsilon) + { + r = distr(twister); + g = distr(twister); + b = distr(twister); + m = std::sqrt(r*r + b*b + g*g); + } + r /= m; + b /= m; + b /= m; +//! [random numbers] + +//! [modify light] + lightRequest.set_name("point"); + lightRequest.set_range(4); + lightRequest.set_attenuation_linear(0.5); + lightRequest.set_attenuation_constant(0.2); + lightRequest.set_attenuation_quadratic(0.01); + lightRequest.set_cast_shadows(false); + lightRequest.set_type(ignition::msgs::Light::POINT); + // direction field only affects spot / directional lights + ignition::msgs::Set(lightRequest.mutable_direction(), + ignition::math::Vector3d(directionX, directionY, directionZ)); + ignition::msgs::Set(lightRequest.mutable_pose(), + ignition::math::Pose3d(0.0, -1.5, 3.0, 0.0, 0.0, 0.0)); + ignition::msgs::Set(lightRequest.mutable_diffuse(), + ignition::math::Color(r, g, b, 1)); + ignition::msgs::Set(lightRequest.mutable_specular(), + ignition::math::Color(r, g, b, 1)); +//! [modify light] + bool executed = node.Request(lightConfigService, lightRequest, timeout, + rep, result); + std::cout << "Service called: [" << r << ", " << g << ", " << b << "]" + << std::endl; + + if (executed) + { + if (result) + std::cout << "Response: [" << rep.data() << "]" << std::endl; + else + std::cout << "Service call failed" << std::endl; + } + else + std::cerr << "Service call timed out" << std::endl; + + std::this_thread::sleep_for(1s); + } +} diff --git a/tutorials.md.in b/tutorials.md.in index bacb32edb2..b3e03e0cc8 100644 --- a/tutorials.md.in +++ b/tutorials.md.in @@ -14,6 +14,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively. * \subpage resources "Finding resources": The different ways in which Ignition looks for files. * \subpage log "Logging": Record and play back time series of world state. * \subpage physics "Physics engines": Loading different physics engines. +* \subpage light_config "Light config": Configure lights in the scene. * \subpage battery "Battery": Keep track of battery charge on robot models. * \subpage gui_config "GUI configuration": Customizing your layout. * \subpage server_config "Server configuration": Customizing what system plugins are loaded. diff --git a/tutorials/light_config.md b/tutorials/light_config.md new file mode 100644 index 0000000000..4cb8ed83a5 --- /dev/null +++ b/tutorials/light_config.md @@ -0,0 +1,45 @@ +\page light_config Light config + +This tutorial gives an introduction to the Ignition Gazebo's service `/world//light_config`. +This service will allow to modify lights in the scene. + +# Modifying lights + +To modify lights inside the scene we need to use the service `/world//light_config` and +fill the message [`ignition::msgs::Light`](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html). +In particular this example modify the point light that we introduced with the function `createLight()`. + +\snippet examples/standalone/light_control/light_control.cc create light + +**NOTE:**: You can check the [model creation](model_creation.html) tutorial to learn how to include models and lights in the scene. + +As you can see in the snippet we modify the specular and diffuse of the light that corresponds to type of light in the scene. + +\snippet examples/standalone/light_control/light_control.cc modify light + +In this case we are creating random numbers to fill the diffuse and specular. + +\snippet examples/standalone/light_control/light_control.cc random numbers + +# Run the example + +To run this example you should `cd` into `examples/standalone/light_control` and build the code: + +```bash +mkdir build +cd build +cmake .. +make +``` + +Then you should open two terminals and run: + + - Terminal one: + ```bash + ign gazebo -r -v 4 empty.world + ``` + + - Terminal two: + ```bash + ./light_control + ``` From a9e2e59c38fdf2848ea21012f5d4e0a0fe46169d Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 3 Feb 2021 17:09:43 +0100 Subject: [PATCH 36/42] Restored some files Signed-off-by: ahcorde --- src/Model.cc | 1 + test/integration/model.cc | 1 + 2 files changed, 2 insertions(+) diff --git a/src/Model.cc b/src/Model.cc index 9981110f1f..d9776b94a3 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -192,3 +192,4 @@ void Model::SetWorldPoseCmd(EntityComponentManager &_ecm, components::WorldPoseCmd::typeId, ComponentState::OneTimeChange); } } + diff --git a/test/integration/model.cc b/test/integration/model.cc index 008bd7ddf8..07c7c2623c 100644 --- a/test/integration/model.cc +++ b/test/integration/model.cc @@ -232,3 +232,4 @@ TEST_F(ModelIntegrationTest, SetWorldPoseCmd) EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), worldPoseCmdComp->Data()); EXPECT_TRUE(ecm.HasOneTimeComponentChanges()); } + From 291b1d5c622b609469d24d5b6509205b8781685c Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 3 Feb 2021 23:47:07 +0100 Subject: [PATCH 37/42] Fixed tests Signed-off-by: ahcorde --- test/integration/user_commands.cc | 8 +++----- test/worlds/lights.sdf | 29 +++++++++++++++++++++++++---- 2 files changed, 28 insertions(+), 9 deletions(-) diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 17051e77d4..3dbdaafe6d 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -725,7 +725,6 @@ TEST_F(UserCommandsTest, Light) msgs::Light req; req.set_name("point"); - req.set_parent_id(1); msgs::Boolean res; bool result; @@ -761,7 +760,6 @@ TEST_F(UserCommandsTest, Light) ignition::math::Color(0.2, 0.2, 0.2, 0.2)); req.set_range(2.6); req.set_name("point"); - req.set_parent_id(1); req.set_type(ignition::msgs::Light::POINT); req.set_attenuation_linear(0.7); req.set_attenuation_constant(0.6); @@ -771,7 +769,7 @@ TEST_F(UserCommandsTest, Light) EXPECT_TRUE(result); EXPECT_TRUE(res.data()); - server.Run(true, 1, false); + server.Run(true, 100, false); // Sleep for a small duration to allow Run thread to start IGN_SLEEP_MS(10); @@ -834,7 +832,7 @@ TEST_F(UserCommandsTest, Light) EXPECT_TRUE(result); EXPECT_TRUE(res.data()); - server.Run(true, 1, false); + server.Run(true, 100, false); // Sleep for a small duration to allow Run thread to start IGN_SLEEP_MS(10); @@ -904,7 +902,7 @@ TEST_F(UserCommandsTest, Light) EXPECT_TRUE(result); EXPECT_TRUE(res.data()); - server.Run(true, 1, false); + server.Run(true, 100, false); // Sleep for a small duration to allow Run thread to start IGN_SLEEP_MS(10); diff --git a/test/worlds/lights.sdf b/test/worlds/lights.sdf index a8aa63006c..7ec98f3515 100644 --- a/test/worlds/lights.sdf +++ b/test/worlds/lights.sdf @@ -17,6 +17,11 @@ filename="ignition-gazebo-user-commands-system" name="ignition::gazebo::systems::UserCommands"> + + ogre + true 0 0 10 0 0 0 @@ -66,7 +71,26 @@ 0 0.0 0.0 0 0 0 - + + + 1 0 1.3 0 0 0 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + camera + + 0.5 @@ -78,7 +102,6 @@ 0.3 0.3 0.3 1 - 0 0 1.0 0 0 0 0 0 1 1 @@ -91,9 +114,7 @@ false - - From 4b322b84846d9ef598c1c808e1ccdf3655a4be35 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 4 Feb 2021 11:14:52 +0100 Subject: [PATCH 38/42] Fixed tests Signed-off-by: ahcorde --- test/integration/user_commands.cc | 2 +- test/worlds/lights.sdf | 24 ------ test/worlds/lights_render.sdf | 120 ++++++++++++++++++++++++++++++ 3 files changed, 121 insertions(+), 25 deletions(-) create mode 100644 test/worlds/lights_render.sdf diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 3dbdaafe6d..8971d8f310 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -700,7 +700,7 @@ TEST_F(UserCommandsTest, Light) // Start server ServerConfig serverConfig; const auto sdfFile = ignition::common::joinPaths( - std::string(PROJECT_SOURCE_PATH), "test", "worlds", "lights.sdf"); + std::string(PROJECT_SOURCE_PATH), "test", "worlds", "lights_render.sdf"); serverConfig.SetSdfFile(sdfFile); Server server(serverConfig); diff --git a/test/worlds/lights.sdf b/test/worlds/lights.sdf index 7ec98f3515..10516237a8 100644 --- a/test/worlds/lights.sdf +++ b/test/worlds/lights.sdf @@ -17,11 +17,6 @@ filename="ignition-gazebo-user-commands-system" name="ignition::gazebo::systems::UserCommands"> - - ogre - true 0 0 10 0 0 0 @@ -71,25 +66,6 @@ 0 0.0 0.0 0 0 0 - - - 1 0 1.3 0 0 0 - - 1.047 - - 320 - 240 - - - 0.1 - 100 - - - 1 - 30 - true - camera - diff --git a/test/worlds/lights_render.sdf b/test/worlds/lights_render.sdf new file mode 100644 index 0000000000..6c4dc6178b --- /dev/null +++ b/test/worlds/lights_render.sdf @@ -0,0 +1,120 @@ + + + + + 0.001 + 1.0 + + + + + + + + + ogre + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 100 + 0.9 + 0.01 + 0.001 + + 0.5 0.2 -0.9 + + + + 0 -1.5 3 0 0 0 + 1 0 0 1 + .1 .1 .1 1 + + 4 + 0.2 + 0.5 + 0.01 + + false + + + + 0 1.5 3 0 0 0 + 0 1 0 1 + .2 .2 .2 1 + + 5 + 0.3 + 0.4 + 0.001 + + 0 0 -1 + + 0.1 + 0.5 + 0.8 + + false + + + + 0 0.0 0.0 0 0 0 + + + + 1 0 1.3 0 0 0 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + false + camera + + + + + 0.5 + + + + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + 0.3 0.3 0.3 1 + + + + 0 0 1.0 0 0 0 + 0 0 1 1 + .1 .1 .1 1 + + 2 + 0.05 + 0.02 + 0.01 + + false + + + + + From 40320e7ea380b36d2045a1ac5f51bb75538e92da Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 5 Feb 2021 11:18:04 +0100 Subject: [PATCH 39/42] Added feedback Signed-off-by: ahcorde --- test/integration/user_commands.cc | 20 ++++++++------------ test/worlds/lights.sdf | 4 ---- test/worlds/lights_render.sdf | 6 +----- tutorials/light_config.md | 8 ++++---- 4 files changed, 13 insertions(+), 25 deletions(-) diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 8971d8f310..381a5a961e 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -724,23 +724,17 @@ TEST_F(UserCommandsTest, Light) EXPECT_NE(nullptr, ecm); msgs::Light req; - req.set_name("point"); - msgs::Boolean res; + transport::Node node; bool result; unsigned int timeout = 1000; - std::string service{"/world/lights/light_config"}; - - transport::Node node; - EXPECT_TRUE(node.Request(service, req, timeout, res, result)); - EXPECT_TRUE(result); - EXPECT_TRUE(res.data()); + std::string service{"/world/lights_command/light_config"}; // Point light auto pointLightEntity = ecm->EntityByComponents(components::Name("point")); EXPECT_NE(kNullEntity, pointLightEntity); - // Check entity has not been edited yet + // Check point light entity has not been edited yet - Initial values auto pointLightComp = ecm->Component(pointLightEntity); ASSERT_NE(nullptr, pointLightComp); EXPECT_EQ( @@ -773,6 +767,7 @@ TEST_F(UserCommandsTest, Light) // Sleep for a small duration to allow Run thread to start IGN_SLEEP_MS(10); + // Check point light entity has been edited using the service pointLightComp = ecm->Component(pointLightEntity); ASSERT_NE(nullptr, pointLightComp); @@ -786,12 +781,11 @@ TEST_F(UserCommandsTest, Light) EXPECT_TRUE(pointLightComp->Data().CastShadows()); EXPECT_EQ(sdf::LightType::POINT, pointLightComp->Data().Type()); - // directional light + // Check directional light entity has not been edited yet - Initial values auto directionalLightEntity = ecm->EntityByComponents( components::Name("directional")); EXPECT_NE(kNullEntity, directionalLightEntity); - // Check entity has not been moved yet auto directionalLightComp = ecm->Component(directionalLightEntity); ASSERT_NE(nullptr, directionalLightComp); @@ -836,6 +830,7 @@ TEST_F(UserCommandsTest, Light) // Sleep for a small duration to allow Run thread to start IGN_SLEEP_MS(10); + // Check directional light entity has been edited using the service directionalLightComp = ecm->Component(directionalLightEntity); ASSERT_NE(nullptr, directionalLightComp); @@ -860,7 +855,7 @@ TEST_F(UserCommandsTest, Light) components::Name("spot")); EXPECT_NE(kNullEntity, spotLightEntity); - // Check entity has not been moved yet + // Check spot light entity has not been edited yet - Initial values auto spotLightComp = ecm->Component(spotLightEntity); ASSERT_NE(nullptr, spotLightComp); @@ -906,6 +901,7 @@ TEST_F(UserCommandsTest, Light) // Sleep for a small duration to allow Run thread to start IGN_SLEEP_MS(10); + // Check spot light entity has been edited using the service spotLightComp = ecm->Component(spotLightEntity); ASSERT_NE(nullptr, spotLightComp); diff --git a/test/worlds/lights.sdf b/test/worlds/lights.sdf index 10516237a8..6f5daa40af 100644 --- a/test/worlds/lights.sdf +++ b/test/worlds/lights.sdf @@ -13,10 +13,6 @@ filename="ignition-gazebo-scene-broadcaster-system" name="ignition::gazebo::systems::SceneBroadcaster"> - - true 0 0 10 0 0 0 diff --git a/test/worlds/lights_render.sdf b/test/worlds/lights_render.sdf index 6c4dc6178b..3f4d677460 100644 --- a/test/worlds/lights_render.sdf +++ b/test/worlds/lights_render.sdf @@ -1,14 +1,10 @@ - + 0.001 1.0 - - diff --git a/tutorials/light_config.md b/tutorials/light_config.md index 4cb8ed83a5..4a84af58f1 100644 --- a/tutorials/light_config.md +++ b/tutorials/light_config.md @@ -1,19 +1,19 @@ \page light_config Light config -This tutorial gives an introduction to the Ignition Gazebo's service `/world//light_config`. +This tutorial gives an introduction to Ignition Gazebo's service `/world//light_config`. This service will allow to modify lights in the scene. # Modifying lights To modify lights inside the scene we need to use the service `/world//light_config` and fill the message [`ignition::msgs::Light`](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html). -In particular this example modify the point light that we introduced with the function `createLight()`. +In particular this example modifies the point light that we introduced with the function `createLight()`. \snippet examples/standalone/light_control/light_control.cc create light -**NOTE:**: You can check the [model creation](model_creation.html) tutorial to learn how to include models and lights in the scene. +**NOTE:**: You can check the [entity creation](entity_creation.html) tutorial to learn how to include models and lights in the scene. -As you can see in the snippet we modify the specular and diffuse of the light that corresponds to type of light in the scene. +As you can see in the snippet we modify the specular and diffuse colors of the light in the scene. \snippet examples/standalone/light_control/light_control.cc modify light From 79779e6875319be744a1a3cff8cb5d4157570af8 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 5 Feb 2021 13:55:23 +0100 Subject: [PATCH 40/42] Fix seg faults Signed-off-by: ahcorde --- src/EntityComponentManager.cc | 3 +++ src/gui/plugins/component_inspector/ComponentInspector.cc | 4 +++- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/EntityComponentManager.cc b/src/EntityComponentManager.cc index 3b2cd2f924..7f6958c80a 100644 --- a/src/EntityComponentManager.cc +++ b/src/EntityComponentManager.cc @@ -809,6 +809,9 @@ void EntityComponentManagerPrivate::SetRemovedComponentsMsgs(Entity &_entity, // Find the entity in the message auto entIter = _msg.mutable_entities()->find(_entity); + if (entIter == _msg.mutable_entities()->end()) + return; + auto it = this->removedComponents.find(_entity); for (uint64_t i = 0; i < nEntityKeys; ++i) { diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 2ef4dea7aa..4d95c66b3e 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -581,9 +581,11 @@ void ComponentInspector::Update(const UpdateInfo &, { this->SetType("light"); auto comp = _ecm.Component(this->dataPtr->entity); - msgs::Light lightMsgs = convert(comp->Data()); if (comp) + { + msgs::Light lightMsgs = convert(comp->Data()); setData(item, lightMsgs); + } } else if (typeId == components::Physics::typeId) { From 0a22adcbfba0c9a7e7aaf4d140a6b88c3b2fc9eb Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 11 Feb 2021 08:41:50 +0100 Subject: [PATCH 41/42] Fixed merge Signed-off-by: ahcorde --- src/rendering/RenderUtil.cc | 10 +++------- src/systems/sensors/Sensors.hh | 5 ----- 2 files changed, 3 insertions(+), 12 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 6ef136af43..ae94373ebd 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -322,12 +322,14 @@ rendering::ScenePtr RenderUtil::Scene() const { return this->dataPtr->scene; } + ////////////////////////////////////////////////// -void RenderUtil::UpdateECM(const UpdateInfo &, +void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/, EntityComponentManager &_ecm) { std::lock_guard lock(this->dataPtr->updateMutex); + // Update lights auto olderEntitiesLightsCmdToDelete = std::move(this->dataPtr->entityLightsCmdToDelete); this->dataPtr->entityLightsCmdToDelete.clear(); @@ -356,13 +358,7 @@ void RenderUtil::UpdateECM(const UpdateInfo &, { _ecm.RemoveComponent(entity); } -} -////////////////////////////////////////////////// -void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/, - EntityComponentManager &_ecm) -{ - std::lock_guard lock(this->dataPtr->updateMutex); // Update thermal cameras _ecm.Each( [&](const Entity &_entity, diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index 83d88a9bef..2dbdf1a01e 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -41,7 +41,6 @@ namespace systems /// sensor / sensor type? class IGNITION_GAZEBO_VISIBLE Sensors: public System, - public ISystemUpdate, public ISystemConfigure, public ISystemUpdate, public ISystemPostUpdate @@ -62,10 +61,6 @@ namespace systems public: void Update(const UpdateInfo &_info, EntityComponentManager &_ecm) final; - // Documentation inherited - public: void Update(const UpdateInfo &_info, - EntityComponentManager &_ecm) final; - // Documentation inherited public: void PostUpdate(const UpdateInfo &_info, const EntityComponentManager &_ecm) final; From b993f9d77e80223588774391eaf79ce14456d064 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 17 Feb 2021 07:55:29 +0100 Subject: [PATCH 42/42] Added feedback Signed-off-by: ahcorde --- src/systems/sensors/Sensors.hh | 6 +++--- tutorials/light_config.md | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index 2dbdf1a01e..3ee5807268 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -57,9 +57,9 @@ namespace systems EntityComponentManager &_ecm, EventManager &_eventMgr) final; - // Documentation inherited - public: void Update(const UpdateInfo &_info, - EntityComponentManager &_ecm) final; + // Documentation inherited + public: void Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) final; // Documentation inherited public: void PostUpdate(const UpdateInfo &_info, diff --git a/tutorials/light_config.md b/tutorials/light_config.md index 4a84af58f1..8a87170faf 100644 --- a/tutorials/light_config.md +++ b/tutorials/light_config.md @@ -36,7 +36,7 @@ Then you should open two terminals and run: - Terminal one: ```bash - ign gazebo -r -v 4 empty.world + ign gazebo -r -v 4 empty.sdf ``` - Terminal two: