Skip to content

Commit

Permalink
Remove redundant namespace references
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Aug 9, 2022
1 parent 3e76d92 commit 7e3ccfe
Show file tree
Hide file tree
Showing 42 changed files with 199 additions and 199 deletions.
8 changes: 4 additions & 4 deletions src/Actor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ class sdf::ActorPrivate
public: std::vector<Joint> joints;

/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;
public: ElementPtr sdf;
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -565,7 +565,7 @@ Errors Actor::Load(ElementPtr _sdf)

loadPose(_sdf, this->dataPtr->pose, this->dataPtr->poseRelativeTo);

sdf::ElementPtr skinElem = _sdf->GetElement("skin");
ElementPtr skinElem = _sdf->GetElement("skin");

if (skinElem)
{
Expand All @@ -590,7 +590,7 @@ Errors Actor::Load(ElementPtr _sdf)
errors.insert(errors.end(), animationLoadErrors.begin(),
animationLoadErrors.end());

sdf::ElementPtr scriptElem = _sdf->GetElement("script");
ElementPtr scriptElem = _sdf->GetElement("script");

if (!scriptElem)
{
Expand Down Expand Up @@ -691,7 +691,7 @@ void Actor::SetPoseRelativeTo(const std::string &_frame)
}

/////////////////////////////////////////////////
sdf::ElementPtr Actor::Element() const
ElementPtr Actor::Element() const
{
return this->dataPtr->sdf;
}
Expand Down
6 changes: 3 additions & 3 deletions src/AirPressure.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class sdf::AirPressurePrivate
public: double referenceAltitude = 0.0;

/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;
public: ElementPtr sdf;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -93,7 +93,7 @@ Errors AirPressure::Load(ElementPtr _sdf)
// Load the noise values.
if (_sdf->HasElement("pressure"))
{
sdf::ElementPtr elem = _sdf->GetElement("pressure");
ElementPtr elem = _sdf->GetElement("pressure");
if (elem->HasElement("noise"))
this->dataPtr->noise.Load(elem->GetElement("noise"));
}
Expand All @@ -105,7 +105,7 @@ Errors AirPressure::Load(ElementPtr _sdf)
}

//////////////////////////////////////////////////
sdf::ElementPtr AirPressure::Element() const
ElementPtr AirPressure::Element() const
{
return this->dataPtr->sdf;
}
Expand Down
8 changes: 4 additions & 4 deletions src/Altimeter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class sdf::AltimeterPrivate
public: Noise verticalVelocityNoise;

/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;
public: ElementPtr sdf;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -91,14 +91,14 @@ Errors Altimeter::Load(ElementPtr _sdf)
// Load the noise values.
if (_sdf->HasElement("vertical_position"))
{
sdf::ElementPtr elem = _sdf->GetElement("vertical_position");
ElementPtr elem = _sdf->GetElement("vertical_position");
if (elem->HasElement("noise"))
this->dataPtr->verticalPositionNoise.Load(elem->GetElement("noise"));
}

if (_sdf->HasElement("vertical_velocity"))
{
sdf::ElementPtr elem = _sdf->GetElement("vertical_velocity");
ElementPtr elem = _sdf->GetElement("vertical_velocity");
if (elem->HasElement("noise"))
this->dataPtr->verticalVelocityNoise.Load(elem->GetElement("noise"));
}
Expand Down Expand Up @@ -131,7 +131,7 @@ void Altimeter::SetVerticalVelocityNoise(const Noise &_noise)
}

//////////////////////////////////////////////////
sdf::ElementPtr Altimeter::Element() const
ElementPtr Altimeter::Element() const
{
return this->dataPtr->sdf;
}
Expand Down
4 changes: 2 additions & 2 deletions src/Box.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class sdf::BoxPrivate
public: ignition::math::Boxd box{ignition::math::Vector3d::One};

/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;
public: ElementPtr sdf;
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -131,7 +131,7 @@ void Box::SetSize(const ignition::math::Vector3d &_size)
}

/////////////////////////////////////////////////
sdf::ElementPtr Box::Element() const
ElementPtr Box::Element() const
{
return this->dataPtr->sdf;
}
Expand Down
22 changes: 11 additions & 11 deletions src/Camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ static std::array<std::string, 19> kPixelFormatNames =
class sdf::CameraPrivate
{
/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;
public: ElementPtr sdf;

/// \brief Name of the camera.
public: std::string name = "";
Expand Down Expand Up @@ -241,7 +241,7 @@ Errors Camera::Load(ElementPtr _sdf)
// Read the distortion
if (_sdf->HasElement("distortion"))
{
sdf::ElementPtr elem = _sdf->GetElement("distortion");
ElementPtr elem = _sdf->GetElement("distortion");
this->dataPtr->distortionK1 = elem->Get<double>("k1",
this->dataPtr->distortionK1).first;
this->dataPtr->distortionK2 = elem->Get<double>("k2",
Expand All @@ -260,7 +260,7 @@ Errors Camera::Load(ElementPtr _sdf)

if (_sdf->HasElement("image"))
{
sdf::ElementPtr elem = _sdf->GetElement("image");
ElementPtr elem = _sdf->GetElement("image");
this->dataPtr->imageWidth = elem->Get<uint32_t>("width",
this->dataPtr->imageWidth).first;
this->dataPtr->imageHeight = elem->Get<uint32_t>("height",
Expand All @@ -286,11 +286,11 @@ Errors Camera::Load(ElementPtr _sdf)

if (_sdf->HasElement("depth_camera"))
{
sdf::ElementPtr elem = _sdf->GetElement("depth_camera");
ElementPtr elem = _sdf->GetElement("depth_camera");
this->dataPtr->hasDepthCamera = true;
if (elem->HasElement("clip"))
{
sdf::ElementPtr func = elem->GetElement("clip");
ElementPtr func = elem->GetElement("clip");
if (func->HasElement("near"))
{
this->SetDepthNearClip(func->Get<double>("near"));
Expand All @@ -304,7 +304,7 @@ Errors Camera::Load(ElementPtr _sdf)

if (_sdf->HasElement("clip"))
{
sdf::ElementPtr elem = _sdf->GetElement("clip");
ElementPtr elem = _sdf->GetElement("clip");
this->dataPtr->nearClip = elem->Get<double>("near",
this->dataPtr->nearClip).first;
this->dataPtr->farClip = elem->Get<double>("far",
Expand All @@ -318,7 +318,7 @@ Errors Camera::Load(ElementPtr _sdf)

if (_sdf->HasElement("save"))
{
sdf::ElementPtr elem = _sdf->GetElement("save");
ElementPtr elem = _sdf->GetElement("save");
this->dataPtr->save = elem->Get<bool>("enabled", this->dataPtr->save).first;
if (this->dataPtr->save)
{
Expand All @@ -345,7 +345,7 @@ Errors Camera::Load(ElementPtr _sdf)
// Load the lens values.
if (_sdf->HasElement("lens"))
{
sdf::ElementPtr elem = _sdf->GetElement("lens");
ElementPtr elem = _sdf->GetElement("lens");

this->dataPtr->lensType = elem->Get<std::string>("type",
this->dataPtr->lensType).first;
Expand All @@ -358,7 +358,7 @@ Errors Camera::Load(ElementPtr _sdf)

if (elem->HasElement("custom_function"))
{
sdf::ElementPtr func = elem->GetElement("custom_function");
ElementPtr func = elem->GetElement("custom_function");
this->dataPtr->lensC1 = func->Get<double>("c1",
this->dataPtr->lensC1).first;
this->dataPtr->lensC2 = func->Get<double>("c2",
Expand All @@ -373,7 +373,7 @@ Errors Camera::Load(ElementPtr _sdf)

if (elem->HasElement("intrinsics"))
{
sdf::ElementPtr intrinsics = elem->GetElement("intrinsics");
ElementPtr intrinsics = elem->GetElement("intrinsics");
this->dataPtr->lensIntrinsicsFx = intrinsics->Get<double>("fx",
this->dataPtr->lensIntrinsicsFx).first;
this->dataPtr->lensIntrinsicsFy = intrinsics->Get<double>("fy",
Expand All @@ -397,7 +397,7 @@ Errors Camera::Load(ElementPtr _sdf)
}

/////////////////////////////////////////////////
sdf::ElementPtr Camera::Element() const
ElementPtr Camera::Element() const
{
return this->dataPtr->sdf;
}
Expand Down
10 changes: 5 additions & 5 deletions src/Collision.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,13 @@ class sdf::CollisionPrivate
public: Surface surface;

/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;
public: ElementPtr sdf;

/// \brief Name of xml parent object.
public: std::string xmlParentName;

/// \brief Weak pointer to model's Pose Relative-To Graph.
public: std::weak_ptr<const sdf::PoseRelativeToGraph> poseRelativeToGraph;
public: std::weak_ptr<const PoseRelativeToGraph> poseRelativeToGraph;
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -164,7 +164,7 @@ void Collision::SetGeom(const Geometry &_geom)
}

/////////////////////////////////////////////////
sdf::Surface *Collision::Surface() const
Surface *Collision::Surface() const
{
return &this->dataPtr->surface;
}
Expand Down Expand Up @@ -237,7 +237,7 @@ void Collision::SetPoseRelativeToGraph(
}

/////////////////////////////////////////////////
sdf::SemanticPose Collision::SemanticPose() const
SemanticPose Collision::SemanticPose() const
{
return sdf::SemanticPose(
this->dataPtr->pose,
Expand All @@ -247,7 +247,7 @@ sdf::SemanticPose Collision::SemanticPose() const
}

/////////////////////////////////////////////////
sdf::ElementPtr Collision::Element() const
ElementPtr Collision::Element() const
{
return this->dataPtr->sdf;
}
14 changes: 7 additions & 7 deletions src/Console.cc
Original file line number Diff line number Diff line change
Expand Up @@ -59,18 +59,18 @@ Console::Console()
<< std::endl;
return;
}
std::string logDir = sdf::filesystem::append(home, ".sdformat");
if (!sdf::filesystem::exists(logDir))
std::string logDir = filesystem::append(home, ".sdformat");
if (!filesystem::exists(logDir))
{
sdf::filesystem::create_directory(logDir);
filesystem::create_directory(logDir);
}
else if (!sdf::filesystem::is_directory(logDir))
else if (!filesystem::is_directory(logDir))
{
std::cerr << logDir << " exists but is not a directory. Will not log."
<< std::endl;
return;
}
std::string logFile = sdf::filesystem::append(logDir, "sdformat.log");
std::string logFile = filesystem::append(logDir, "sdformat.log");
this->dataPtr->logFileStream.open(logFile.c_str(), std::ios::out);
}

Expand Down Expand Up @@ -106,13 +106,13 @@ void Console::SetQuiet(bool _quiet)
}

//////////////////////////////////////////////////
sdf::Console::ConsoleStream &Console::GetMsgStream()
Console::ConsoleStream &Console::GetMsgStream()
{
return this->dataPtr->msgStream;
}

//////////////////////////////////////////////////
sdf::Console::ConsoleStream &Console::GetLogStream()
Console::ConsoleStream &Console::GetLogStream()
{
return this->dataPtr->logStream;
}
Expand Down
4 changes: 2 additions & 2 deletions src/Cylinder.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ class sdf::CylinderPrivate
public: ignition::math::Cylinderd cylinder{1.0, 1.0};

/// \brief The SDF element pointer used during load.
public: sdf::ElementPtr sdf;
public: ElementPtr sdf;
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -161,7 +161,7 @@ void Cylinder::SetLength(const double _length)
}

/////////////////////////////////////////////////
sdf::ElementPtr Cylinder::Element() const
ElementPtr Cylinder::Element() const
{
return this->dataPtr->sdf;
}
Expand Down
8 changes: 4 additions & 4 deletions src/Element.cc
Original file line number Diff line number Diff line change
Expand Up @@ -797,7 +797,7 @@ std::map<std::string, std::size_t> Element::CountNamedElements(
{
std::map<std::string, std::size_t> result;

sdf::ElementPtr elem;
ElementPtr elem;
if (_type.empty())
{
elem = this->GetFirstElement();
Expand Down Expand Up @@ -926,7 +926,7 @@ void Element::Clear()
/////////////////////////////////////////////////
void Element::ClearElements()
{
for (sdf::ElementPtr_V::iterator iter = this->dataPtr->elements.begin();
for (ElementPtr_V::iterator iter = this->dataPtr->elements.begin();
iter != this->dataPtr->elements.end(); ++iter)
{
(*iter)->ClearElements();
Expand All @@ -938,13 +938,13 @@ void Element::ClearElements()
/////////////////////////////////////////////////
void Element::Update()
{
for (sdf::Param_V::iterator iter = this->dataPtr->attributes.begin();
for (Param_V::iterator iter = this->dataPtr->attributes.begin();
iter != this->dataPtr->attributes.end(); ++iter)
{
(*iter)->Update();
}

for (sdf::ElementPtr_V::iterator iter = this->dataPtr->elements.begin();
for (ElementPtr_V::iterator iter = this->dataPtr->elements.begin();
iter != this->dataPtr->elements.end(); ++iter)
{
(*iter)->Update();
Expand Down
4 changes: 2 additions & 2 deletions src/Error.cc
Original file line number Diff line number Diff line change
Expand Up @@ -57,10 +57,10 @@ namespace sdf
inline namespace SDF_VERSION_NAMESPACE {

/////////////////////////////////////////////////
std::ostream &operator<<(std::ostream &_out, const sdf::Error &_err)
std::ostream &operator<<(std::ostream &_out, const Error &_err)
{
_out << "Error Code "
<< static_cast<std::underlying_type<sdf::ErrorCode>::type>(_err.Code())
<< static_cast<std::underlying_type<ErrorCode>::type>(_err.Code())
<< " Msg: " << _err.Message();
return _out;
}
Expand Down
2 changes: 1 addition & 1 deletion src/Exception.cc
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ Exception &Exception::operator=(Exception &&_exception) = default;
//////////////////////////////////////////////////
void Exception::Print() const
{
sdf::Console::Instance()->ColorMsg("Exception",
Console::Instance()->ColorMsg("Exception",
this->dataPtr->file,
static_cast<unsigned int>(this->dataPtr->line), 31) << *this;
}
Expand Down
Loading

0 comments on commit 7e3ccfe

Please sign in to comment.