diff --git a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc index 492666b0ec..3fc0458e08 100644 --- a/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc +++ b/src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc @@ -615,8 +615,7 @@ void OpticalTactilePluginPrivate::Load(const EntityComponentManager &_ecm) this->sensorSize, this->forceLength, this->cameraUpdateRate, - this->depthCameraOffset, - this->visualizationResolution); + this->depthCameraOffset); this->initialized = true; } diff --git a/src/systems/optical_tactile_plugin/Visualization.cc b/src/systems/optical_tactile_plugin/Visualization.cc index 22ba842ebb..d330e6a9d4 100644 --- a/src/systems/optical_tactile_plugin/Visualization.cc +++ b/src/systems/optical_tactile_plugin/Visualization.cc @@ -32,14 +32,12 @@ OpticalTactilePluginVisualization::OpticalTactilePluginVisualization( ignition::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, - ignition::math::Pose3f &_depthCameraOffset, - int &_visualizationResolution) : + ignition::math::Pose3f &_depthCameraOffset) : modelName(_modelName), sensorSize(_sensorSize), forceLength(_forceLength), cameraUpdateRate(_cameraUpdateRate), - depthCameraOffset(_depthCameraOffset), - visualizationResolution(_visualizationResolution) + depthCameraOffset(_depthCameraOffset) { } diff --git a/src/systems/optical_tactile_plugin/Visualization.hh b/src/systems/optical_tactile_plugin/Visualization.hh index a5e863e139..96c8b46cc0 100644 --- a/src/systems/optical_tactile_plugin/Visualization.hh +++ b/src/systems/optical_tactile_plugin/Visualization.hh @@ -52,15 +52,12 @@ namespace optical_tactile_sensor /// \param[in] _forceLength Value of the forceLength attribute /// \param[in] _cameraUpdateRate Value of the cameraUpdateRate attribute /// \param[in] _depthCameraOffset Value of the depthCameraOffset attribute - /// \param[in] _visualizationResolution Value of the - /// visualizationResolution attribute public: OpticalTactilePluginVisualization( std::string &_modelName, ignition::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, - ignition::math::Pose3f &_depthCameraOffset, - int &_visualizationResolution); + ignition::math::Pose3f &_depthCameraOffset); /// \brief Initialize the marker message representing the optical tactile /// sensor @@ -153,9 +150,6 @@ namespace optical_tactile_sensor /// \brief Offset between depth camera pose and model pose private: ignition::math::Pose3f depthCameraOffset; - /// \brief Resolution of the sensor in pixels to skip. - private: int visualizationResolution; - /// \brief Whether the normal forces messages are initialized or not private: bool normalForcesMsgsAreInitialized{false}; }; diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index 92c60a7d89..d92b3f15c3 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -21,6 +21,7 @@ #include #include +#include #include #include @@ -244,7 +245,7 @@ void ThrusterTest::TestWorld(const std::string &_world, // linear_velocity) / (angular_velocity * propeller_diameter)) // omega = sqrt(thrust / // (fluid_density * thrust_coefficient * propeller_diameter ^ 4)) - if (_calculateCoefficient && angularVelocity != 0) + if (_calculateCoefficient && gz::math::equal(angularVelocity, 0.0)) { _thrustCoefficient = _alpha1 + _alpha2 * (((1 - _wakeFraction) * propellerLinVels[i].Length()) / (angularVelocity * _diameter));