Skip to content

Commit

Permalink
Fortress: Removed warnings (#1754)
Browse files Browse the repository at this point in the history
* Fortress: Removed warnings
  • Loading branch information
ahcorde authored Oct 11, 2022
1 parent e502e9f commit f91d031
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 14 deletions.
3 changes: 1 addition & 2 deletions src/systems/optical_tactile_plugin/OpticalTactilePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
6 changes: 2 additions & 4 deletions src/systems/optical_tactile_plugin/Visualization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
}

Expand Down
8 changes: 1 addition & 7 deletions src/systems/optical_tactile_plugin/Visualization.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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};
};
Expand Down
3 changes: 2 additions & 1 deletion test/integration/thruster.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>
#include <ignition/math/Helpers.hh>
#include <ignition/transport/Node.hh>
#include <ignition/utilities/ExtraTestMacros.hh>

Expand Down Expand Up @@ -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));
Expand Down

0 comments on commit f91d031

Please sign in to comment.