Skip to content

Commit

Permalink
Formatting updates
Browse files Browse the repository at this point in the history
Signed-off-by: henrykotze <henry@flycloudline.com>
  • Loading branch information
henrykotze committed Nov 29, 2023
1 parent a4c1a64 commit e067253
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 14 deletions.
4 changes: 3 additions & 1 deletion include/gz/sensors/AirFlowSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -69,9 +69,11 @@ namespace gz
public: gz::math::Vector3d Velocity() const;

/// \brief Update the velocity of the sensor
/// \param[in] _vel The velocity of the sensor [m/s]
public: void SetVelocity(const gz::math::Vector3d &_vel);

/// \brief Update the wind velocity in which the sensor is
/// \brief Update the wind velocity
/// \param[in] _vel The wind velocity [m/s]
public: void SetWindVelocity(const gz::math::Vector3d &_vel);

using Sensor::Update;
Expand Down
13 changes: 2 additions & 11 deletions src/AirFlowSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,24 +50,15 @@ class gz::sensors::AirFlowSensorPrivate
/// \brief true if Load() has been called and was successful
public: bool initialized = false;

/// \brief Pressure in pascals.
public: double pressure = 0.0;

/// \brief Resolution of: [deg]
public: double direction_resolution = 0.0;

/// \brief Pressure in pascals.
public: double speed_resolution = 0.0;

/// \brief Velocity of the air coming from the sensor
/// \brief Velocity of the sensor
public: gz::math::Vector3d vel;

/// \brief Velocity of the wind
public: gz::math::Vector3d wind_vel;

/// \brief Noise added to speed measurement
public: std::map<SensorNoiseType, NoisePtr> speed_noises;

/// \brief Noise added to directional measurement
public: std::map<SensorNoiseType, NoisePtr> dir_noises;
};
Expand Down
4 changes: 2 additions & 2 deletions test/integration/air_flow.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ sdf::ElementPtr AirFlowToSdf(const std::string &_name,
std::ostringstream stream;
stream
<< "<?xml version='1.0'?>"
<< "<sdf version='1.6'>"
<< "<sdf version='1.10'>"
<< " <model name='m1'>"
<< " <link name='link1'>"
<< " <sensor name='" << _name << "' type='air_flow'>"
Expand Down Expand Up @@ -67,7 +67,7 @@ sdf::ElementPtr AirFlowToSdfWithNoise(const std::string &_name,
std::ostringstream stream;
stream
<< "<?xml version='1.0'?>"
<< "<sdf version='1.6'>"
<< "<sdf version='1.10'>"
<< " <model name='m1'>"
<< " <link name='link1'>"
<< " <sensor name='" << _name << "' type='air_flow'>"
Expand Down

0 comments on commit e067253

Please sign in to comment.