diff --git a/src/gui/plugins/component_inspector/AirPressure.cc b/src/gui/plugins/component_inspector/AirPressure.cc index 2bc3267e4a..e5c0b15753 100644 --- a/src/gui/plugins/component_inspector/AirPressure.cc +++ b/src/gui/plugins/component_inspector/AirPressure.cc @@ -30,7 +30,7 @@ using namespace gazebo; ///////////////////////////////////////////////// AirPressure::AirPressure(ComponentInspector *_inspector) { - _inspector->Context()->setContextProperty("AirPressure", this); + _inspector->Context()->setContextProperty("AirPressureImpl", this); this->inspector = _inspector; ComponentCreator creator = diff --git a/src/gui/plugins/component_inspector/AirPressure.qml b/src/gui/plugins/component_inspector/AirPressure.qml index 23a89b3b60..ea089e1f25 100644 --- a/src/gui/plugins/component_inspector/AirPressure.qml +++ b/src/gui/plugins/component_inspector/AirPressure.qml @@ -30,6 +30,23 @@ Rectangle { width: componentInspector.width color: index % 2 == 0 ? lightGrey : darkGrey + /** + * Forward air pressure noise changes to C++ + */ + function onAirPressureNoise(_mean, _meanBias, _stdDev, _stdDevBias, + _dynamicBiasStdDev, _dynamicBiasCorrelationTime) { + AirPressureImpl.OnAirPressureNoise( + _mean, _meanBias, _stdDev, _stdDevBias, + _dynamicBiasStdDev, _dynamicBiasCorrelationTime); + } + + /** + * Forward air pressure reference altitude changes to C++ + */ + function onAirPressureReferenceAltitude(_referenceAltitude) { + AirPressureImpl.OnAirPressureReferenceAltitude(_referenceAltitude); + } + Column { anchors.fill: parent @@ -41,7 +58,7 @@ Rectangle { // Set the 'expandingHeaderText' value to override the default header // values, which is based on the model. expandingHeaderText: "Air pressure" - expandingHeaderToolTip: "Air pressure properties" + expandingHeaderToolTip: "Air pressure properties" } // This is the content that will be expanded/contracted using the @@ -82,15 +99,15 @@ Rectangle { Layout.fillWidth: true height: 40 property double refAltitude: model.data[0] - value: referenceAltitudeSpin.activeFocus ? referenceAltitudeSpin.value : refAltitude + value: referenceAltitudeSpin.activeFocus ? referenceAltitudeSpin.value : refAltitude - minimumValue: 0 - maximumValue: 100000 - decimals:4 + minimumValue: 0 + maximumValue: 100000 + decimals:4 stepSize: 0.1 onEditingFinished: { refAltitude = referenceAltitudeSpin.value - componentInspector.onAirPressureReferenceAltitude(refAltitude); + onAirPressureReferenceAltitude(refAltitude); } } } @@ -127,7 +144,7 @@ Rectangle { // Connect to the onNoiseUpdate signal in Noise.qml Component.onCompleted: { pressureNoise.onNoiseUpdate.connect( - componentInspector.onAirPressureNoise) + onAirPressureNoise) } } } diff --git a/src/gui/plugins/component_inspector/ComponentInspector.qml b/src/gui/plugins/component_inspector/ComponentInspector.qml index 66cff0065b..86ad73a023 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.qml +++ b/src/gui/plugins/component_inspector/ComponentInspector.qml @@ -87,23 +87,6 @@ Rectangle { return 6; } - /** - * Forward air pressure noise changes to C++ - */ - function onAirPressureNoise(_mean, _meanBias, _stdDev, _stdDevBias, - _dynamicBiasStdDev, _dynamicBiasCorrelationTime) { - AirPressure.OnAirPressureNoise( - _mean, _meanBias, _stdDev, _stdDevBias, - _dynamicBiasStdDev, _dynamicBiasCorrelationTime); - } - - /** - * Forward air pressure reference altitude changes to C++ - */ - function onAirPressureReferenceAltitude(_referenceAltitude) { - AirPressure.OnAirPressureReferenceAltitude(_referenceAltitude); - } - /** * Forward pose changes to C++ */