Skip to content

Commit

Permalink
Remove redundant namespace references
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Aug 9, 2022
1 parent 6e0b3ae commit 9a24fac
Show file tree
Hide file tree
Showing 17 changed files with 162 additions and 162 deletions.
6 changes: 3 additions & 3 deletions src/AirPressureSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ bool AirPressureSensor::Load(const sdf::Sensor &_sdf)
this->SetTopic("/air_pressure");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::FluidPressure>(
this->dataPtr->node.Advertise<msgs::FluidPressure>(
this->Topic());

if (!this->dataPtr->pub)
Expand Down Expand Up @@ -145,7 +145,7 @@ bool AirPressureSensor::Load(sdf::ElementPtr _sdf)
}

//////////////////////////////////////////////////
bool AirPressureSensor::Update(const ignition::common::Time &_now)
bool AirPressureSensor::Update(const common::Time &_now)
{
IGN_PROFILE("AirPressureSensor::Update");
if (!this->dataPtr->initialized)
Expand Down Expand Up @@ -193,7 +193,7 @@ bool AirPressureSensor::Update(const ignition::common::Time &_now)
NoiseType::GAUSSIAN)
{
GaussianNoiseModelPtr gaussian =
std::dynamic_pointer_cast<sensors::GaussianNoiseModel>(
std::dynamic_pointer_cast<GaussianNoiseModel>(
this->dataPtr->noises[AIR_PRESSURE_NOISE_PASCALS]);
msg.set_variance(sqrt(gaussian->StdDev()));
}
Expand Down
4 changes: 2 additions & 2 deletions src/AltimeterSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ bool AltimeterSensor::Load(const sdf::Sensor &_sdf)
this->SetTopic("/altimeter");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::Altimeter>(this->Topic());
this->dataPtr->node.Advertise<msgs::Altimeter>(this->Topic());

if (!this->dataPtr->pub)
{
Expand Down Expand Up @@ -133,7 +133,7 @@ bool AltimeterSensor::Load(sdf::ElementPtr _sdf)
}

//////////////////////////////////////////////////
bool AltimeterSensor::Update(const ignition::common::Time &_now)
bool AltimeterSensor::Update(const common::Time &_now)
{
IGN_PROFILE("AltimeterSensor::Update");
if (!this->dataPtr->initialized)
Expand Down
46 changes: 23 additions & 23 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class ignition::sensors::CameraSensorPrivate
/// of the path was not possible.
/// \sa ImageSaver
public: bool SaveImage(const unsigned char *_data, unsigned int _width,
unsigned int _height, ignition::common::Image::PixelFormatType _format);
unsigned int _height, common::Image::PixelFormatType _format);

/// \brief node to create publisher
public: transport::Node node;
Expand All @@ -74,21 +74,21 @@ class ignition::sensors::CameraSensorPrivate
public: bool initialized = false;

/// \brief Rendering camera
public: ignition::rendering::CameraPtr camera;
public: rendering::CameraPtr camera;

/// \brief Pointer to an image to be published
public: ignition::rendering::Image image;
public: rendering::Image image;

/// \brief Noise added to sensor data
public: std::map<SensorNoiseType, NoisePtr> noises;

/// \brief Event that is used to trigger callbacks when a new image
/// is generated
public: ignition::common::EventT<
void(const ignition::msgs::Image &)> imageEvent;
public: common::EventT<
void(const msgs::Image &)> imageEvent;

/// \brief Connection to the Manager's scene change event.
public: ignition::common::ConnectionPtr sceneChangeConnection;
public: common::ConnectionPtr sceneChangeConnection;

/// \brief Just a mutex for thread safety
public: std::mutex mutex;
Expand Down Expand Up @@ -188,7 +188,7 @@ bool CameraSensor::CreateCamera()
switch (pixelFormat)
{
case sdf::PixelFormatType::RGB_INT8:
this->dataPtr->camera->SetImageFormat(ignition::rendering::PF_R8G8B8);
this->dataPtr->camera->SetImageFormat(rendering::PF_R8G8B8);
break;
default:
ignerr << "Unsupported pixel format ["
Expand Down Expand Up @@ -258,7 +258,7 @@ bool CameraSensor::Load(const sdf::Sensor &_sdf)
this->SetTopic("/camera");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::Image>(
this->dataPtr->node.Advertise<msgs::Image>(
this->Topic());
if (!this->dataPtr->pub)
{
Expand Down Expand Up @@ -293,14 +293,14 @@ bool CameraSensor::Load(sdf::ElementPtr _sdf)
}

/////////////////////////////////////////////////
ignition::common::ConnectionPtr CameraSensor::ConnectImageCallback(
std::function<void(const ignition::msgs::Image &)> _callback)
common::ConnectionPtr CameraSensor::ConnectImageCallback(
std::function<void(const msgs::Image &)> _callback)
{
return this->dataPtr->imageEvent.Connect(_callback);
}

/////////////////////////////////////////////////
void CameraSensor::SetScene(ignition::rendering::ScenePtr _scene)
void CameraSensor::SetScene(rendering::ScenePtr _scene)
{
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
// APIs make it possible for the scene pointer to change
Expand All @@ -315,7 +315,7 @@ void CameraSensor::SetScene(ignition::rendering::ScenePtr _scene)
}

//////////////////////////////////////////////////
bool CameraSensor::Update(const ignition::common::Time &_now)
bool CameraSensor::Update(const common::Time &_now)
{
IGN_PROFILE("CameraSensor::Update");
if (!this->dataPtr->initialized)
Expand Down Expand Up @@ -370,15 +370,15 @@ bool CameraSensor::Update(const ignition::common::Time &_now)
unsigned int height = this->dataPtr->camera->ImageHeight();
unsigned char *data = this->dataPtr->image.Data<unsigned char>();

ignition::common::Image::PixelFormatType
common::Image::PixelFormatType
format{common::Image::UNKNOWN_PIXEL_FORMAT};
msgs::PixelFormatType msgsPixelFormat =
msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT;

switch (this->dataPtr->camera->ImageFormat())
{
case ignition::rendering::PF_R8G8B8:
format = ignition::common::Image::RGB_INT8;
case rendering::PF_R8G8B8:
format = common::Image::RGB_INT8;
msgsPixelFormat = msgs::PixelFormatType::RGB_INT8;
break;
default:
Expand All @@ -388,7 +388,7 @@ bool CameraSensor::Update(const ignition::common::Time &_now)
}

// create message
ignition::msgs::Image msg;
msgs::Image msg;
{
IGN_PROFILE("CameraSensor::Update Message");
msg.set_width(width);
Expand Down Expand Up @@ -439,24 +439,24 @@ bool CameraSensor::Update(const ignition::common::Time &_now)
//////////////////////////////////////////////////
bool CameraSensorPrivate::SaveImage(const unsigned char *_data,
unsigned int _width, unsigned int _height,
ignition::common::Image::PixelFormatType _format)
common::Image::PixelFormatType _format)
{
// Attempt to create the directory if it doesn't exist
if (!ignition::common::isDirectory(this->saveImagePath))
if (!common::isDirectory(this->saveImagePath))
{
if (!ignition::common::createDirectories(this->saveImagePath))
if (!common::createDirectories(this->saveImagePath))
return false;
}

std::string filename = this->saveImagePrefix +
std::to_string(this->saveImageCounter) + ".png";
++this->saveImageCounter;

ignition::common::Image localImage;
common::Image localImage;
localImage.SetFromData(_data, _width, _height, _format);

localImage.SavePNG(
ignition::common::joinPaths(this->saveImagePath, filename));
common::joinPaths(this->saveImagePath, filename));
return true;
}

Expand Down Expand Up @@ -512,7 +512,7 @@ bool CameraSensor::AdvertiseInfo(const std::string &_topic)
this->dataPtr->infoTopic = _topic;

this->dataPtr->infoPub =
this->dataPtr->node.Advertise<ignition::msgs::CameraInfo>(
this->dataPtr->node.Advertise<msgs::CameraInfo>(
this->dataPtr->infoTopic);
if (!this->dataPtr->infoPub)
{
Expand All @@ -529,7 +529,7 @@ bool CameraSensor::AdvertiseInfo(const std::string &_topic)
}

//////////////////////////////////////////////////
void CameraSensor::PublishInfo(const ignition::common::Time &_now)
void CameraSensor::PublishInfo(const common::Time &_now)
{
this->dataPtr->infoMsg.mutable_header()->mutable_stamp()->set_sec(_now.sec);
this->dataPtr->infoMsg.mutable_header()->mutable_stamp()->set_nsec(
Expand Down
30 changes: 15 additions & 15 deletions src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -178,19 +178,19 @@ bool DepthCameraSensorPrivate::ConvertDepthToImage(
//////////////////////////////////////////////////
bool DepthCameraSensorPrivate::SaveImage(const float *_data,
unsigned int _width, unsigned int _height,
ignition::common::Image::PixelFormatType /*_format*/)
common::Image::PixelFormatType /*_format*/)
{
// Attempt to create the directory if it doesn't exist
if (!ignition::common::isDirectory(this->saveImagePath))
if (!common::isDirectory(this->saveImagePath))
{
if (!ignition::common::createDirectories(this->saveImagePath))
if (!common::createDirectories(this->saveImagePath))
return false;
}

if (_width == 0 || _height == 0)
return false;

ignition::common::Image localImage;
common::Image localImage;

unsigned int depthSamples = _width * _height;
unsigned int depthBufferSize = depthSamples * 3;
Expand All @@ -206,7 +206,7 @@ bool DepthCameraSensorPrivate::SaveImage(const float *_data,
localImage.SetFromData(imgDepthBuffer, _width, _height,
common::Image::RGB_INT8);
localImage.SavePNG(
ignition::common::joinPaths(this->saveImagePath, filename));
common::joinPaths(this->saveImagePath, filename));

delete[] imgDepthBuffer;
return true;
Expand Down Expand Up @@ -275,7 +275,7 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)
this->SetTopic("/camera/depth");

this->dataPtr->pub =
this->dataPtr->node.Advertise<ignition::msgs::Image>(
this->dataPtr->node.Advertise<msgs::Image>(
this->Topic());
if (!this->dataPtr->pub)
{
Expand All @@ -292,7 +292,7 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)

// Create the point cloud publisher
this->dataPtr->pointPub =
this->dataPtr->node.Advertise<ignition::msgs::PointCloudPacked>(
this->dataPtr->node.Advertise<msgs::PointCloudPacked>(
this->Topic() + "/points");
if (!this->dataPtr->pointPub)
{
Expand Down Expand Up @@ -445,8 +445,8 @@ void DepthCameraSensor::OnNewDepthFrame(const float *_scan,
unsigned int depthSamples = _width * _height;
unsigned int depthBufferSize = depthSamples * sizeof(float);

ignition::common::Image::PixelFormatType format =
ignition::common::Image::ConvertPixelFormat(_format);
common::Image::PixelFormatType format =
common::Image::ConvertPixelFormat(_format);

if (!this->dataPtr->depthBuffer)
this->dataPtr->depthBuffer = new float[depthSamples];
Expand Down Expand Up @@ -480,20 +480,20 @@ void DepthCameraSensor::OnNewRgbPointCloud(const float *_scan,
}

/////////////////////////////////////////////////
ignition::rendering::DepthCameraPtr DepthCameraSensor::DepthCamera()
rendering::DepthCameraPtr DepthCameraSensor::DepthCamera()
{
return this->dataPtr->depthCamera;
}

/////////////////////////////////////////////////
ignition::common::ConnectionPtr DepthCameraSensor::ConnectImageCallback(
std::function<void(const ignition::msgs::Image &)> _callback)
common::ConnectionPtr DepthCameraSensor::ConnectImageCallback(
std::function<void(const msgs::Image &)> _callback)
{
return this->dataPtr->imageEvent.Connect(_callback);
}

/////////////////////////////////////////////////
void DepthCameraSensor::SetScene(ignition::rendering::ScenePtr _scene)
void DepthCameraSensor::SetScene(rendering::ScenePtr _scene)
{
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
// APIs make it possible for the scene pointer to change
Expand All @@ -509,7 +509,7 @@ void DepthCameraSensor::SetScene(ignition::rendering::ScenePtr _scene)
}

//////////////////////////////////////////////////
bool DepthCameraSensor::Update(const ignition::common::Time &_now)
bool DepthCameraSensor::Update(const common::Time &_now)
{
IGN_PROFILE("DepthCameraSensor::Update");
if (!this->dataPtr->initialized)
Expand All @@ -533,7 +533,7 @@ bool DepthCameraSensor::Update(const ignition::common::Time &_now)
auto msgsFormat = msgs::PixelFormatType::R_FLOAT32;

// create message
ignition::msgs::Image msg;
msgs::Image msg;
msg.set_width(width);
msg.set_height(height);
msg.set_step(width * rendering::PixelUtil::BytesPerPixel(
Expand Down
12 changes: 6 additions & 6 deletions src/GaussianNoiseModel.cc
Original file line number Diff line number Diff line change
Expand Up @@ -87,28 +87,28 @@ void GaussianNoiseModel::Load(const sdf::Noise &_sdf)
double biasStdDev = 0;
biasMean = _sdf.BiasMean();
biasStdDev = _sdf.BiasStdDev();
this->dataPtr->bias = ignition::math::Rand::DblNormal(biasMean, biasStdDev);
this->dataPtr->bias = math::Rand::DblNormal(biasMean, biasStdDev);

// With equal probability, we pick a negative bias (by convention,
// rateBiasMean should be positive, though it would work fine if
// negative).
if (ignition::math::Rand::DblUniform() < 0.5)
if (math::Rand::DblUniform() < 0.5)
this->dataPtr->bias = -this->dataPtr->bias;

this->Print(out);

this->dataPtr->precision = _sdf.Precision();
if (this->dataPtr->precision < 0)
ignerr << "Noise precision cannot be less than 0" << std::endl;
else if (!ignition::math::equal(this->dataPtr->precision, 0.0, 1e-6))
else if (!math::equal(this->dataPtr->precision, 0.0, 1e-6))
this->dataPtr->quantized = true;
}

//////////////////////////////////////////////////
double GaussianNoiseModel::ApplyImpl(double _in, double _dt)
{
// Generate independent (uncorrelated) Gaussian noise to each input value.
double whiteNoise = ignition::math::Rand::DblNormal(
double whiteNoise = math::Rand::DblNormal(
this->dataPtr->mean, this->dataPtr->stdDev);

// Generate varying (correlated) bias to each input value.
Expand All @@ -132,15 +132,15 @@ double GaussianNoiseModel::ApplyImpl(double _in, double _dt)
tau / 2 * expm1(-2 * _dt / tau));
double phi_d = exp(-_dt / tau);
this->dataPtr->bias = phi_d * this->dataPtr->bias +
ignition::math::Rand::DblNormal(0, sigma_b_d);
math::Rand::DblNormal(0, sigma_b_d);
}

double output = _in + this->dataPtr->bias + whiteNoise;

if (this->dataPtr->quantized)
{
// Apply this->dataPtr->precision
if (!ignition::math::equal(this->dataPtr->precision, 0.0, 1e-6))
if (!math::equal(this->dataPtr->precision, 0.0, 1e-6))
{
output = std::round(output / this->dataPtr->precision) *
this->dataPtr->precision;
Expand Down
Loading

0 comments on commit 9a24fac

Please sign in to comment.