From 7e3ccfe52da327e723fab3ebdcd8431c7c2d5773 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 8 Aug 2022 23:01:50 -0700 Subject: [PATCH] Remove redundant namespace references Signed-off-by: methylDragon --- src/Actor.cc | 8 ++++---- src/AirPressure.cc | 6 +++--- src/Altimeter.cc | 8 ++++---- src/Box.cc | 4 ++-- src/Camera.cc | 22 +++++++++++----------- src/Collision.cc | 10 +++++----- src/Console.cc | 14 +++++++------- src/Cylinder.cc | 4 ++-- src/Element.cc | 8 ++++---- src/Error.cc | 4 ++-- src/Exception.cc | 2 +- src/ForceTorque.cc | 10 +++++----- src/Frame.cc | 10 +++++----- src/Geometry.cc | 16 ++++++++-------- src/Gui.cc | 4 ++-- src/Heightmap.cc | 12 ++++++------ src/Imu.cc | 10 +++++----- src/Joint.cc | 8 ++++---- src/JointAxis.cc | 10 +++++----- src/Lidar.cc | 12 ++++++------ src/Light.cc | 12 ++++++------ src/Link.cc | 12 ++++++------ src/Magnetometer.cc | 6 +++--- src/Material.cc | 12 ++++++------ src/Mesh.cc | 6 +++--- src/Model.cc | 16 ++++++++-------- src/NavSat.cc | 16 ++++++++-------- src/Noise.cc | 4 ++-- src/Param.cc | 10 +++++----- src/Pbr.cc | 16 ++++++++-------- src/Physics.cc | 6 +++--- src/Plane.cc | 4 ++-- src/Polyline.cc | 4 ++-- src/Root.cc | 6 +++--- src/Scene.cc | 6 +++--- src/Sensor.cc | 24 ++++++++++++------------ src/Sky.cc | 6 +++--- src/Sphere.cc | 4 ++-- src/Surface.cc | 10 +++++----- src/Visual.cc | 10 +++++----- src/World.cc | 24 ++++++++++++------------ src/parser_urdf.cc | 2 +- 42 files changed, 199 insertions(+), 199 deletions(-) diff --git a/src/Actor.cc b/src/Actor.cc index 1ff483879..39d005aac 100644 --- a/src/Actor.cc +++ b/src/Actor.cc @@ -111,7 +111,7 @@ class sdf::ActorPrivate public: std::vector joints; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; }; ///////////////////////////////////////////////// @@ -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) { @@ -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) { @@ -691,7 +691,7 @@ void Actor::SetPoseRelativeTo(const std::string &_frame) } ///////////////////////////////////////////////// -sdf::ElementPtr Actor::Element() const +ElementPtr Actor::Element() const { return this->dataPtr->sdf; } diff --git a/src/AirPressure.cc b/src/AirPressure.cc index 667fb164f..437536642 100644 --- a/src/AirPressure.cc +++ b/src/AirPressure.cc @@ -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; }; ////////////////////////////////////////////////// @@ -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")); } @@ -105,7 +105,7 @@ Errors AirPressure::Load(ElementPtr _sdf) } ////////////////////////////////////////////////// -sdf::ElementPtr AirPressure::Element() const +ElementPtr AirPressure::Element() const { return this->dataPtr->sdf; } diff --git a/src/Altimeter.cc b/src/Altimeter.cc index 8af404e07..82de9994b 100644 --- a/src/Altimeter.cc +++ b/src/Altimeter.cc @@ -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; }; ////////////////////////////////////////////////// @@ -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")); } @@ -131,7 +131,7 @@ void Altimeter::SetVerticalVelocityNoise(const Noise &_noise) } ////////////////////////////////////////////////// -sdf::ElementPtr Altimeter::Element() const +ElementPtr Altimeter::Element() const { return this->dataPtr->sdf; } diff --git a/src/Box.cc b/src/Box.cc index d16404c59..aa14e8953 100644 --- a/src/Box.cc +++ b/src/Box.cc @@ -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; }; ///////////////////////////////////////////////// @@ -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; } diff --git a/src/Camera.cc b/src/Camera.cc index 7976f6a3c..c3f20f1b1 100644 --- a/src/Camera.cc +++ b/src/Camera.cc @@ -49,7 +49,7 @@ static std::array 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 = ""; @@ -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("k1", this->dataPtr->distortionK1).first; this->dataPtr->distortionK2 = elem->Get("k2", @@ -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("width", this->dataPtr->imageWidth).first; this->dataPtr->imageHeight = elem->Get("height", @@ -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("near")); @@ -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("near", this->dataPtr->nearClip).first; this->dataPtr->farClip = elem->Get("far", @@ -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("enabled", this->dataPtr->save).first; if (this->dataPtr->save) { @@ -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("type", this->dataPtr->lensType).first; @@ -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("c1", this->dataPtr->lensC1).first; this->dataPtr->lensC2 = func->Get("c2", @@ -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("fx", this->dataPtr->lensIntrinsicsFx).first; this->dataPtr->lensIntrinsicsFy = intrinsics->Get("fy", @@ -397,7 +397,7 @@ Errors Camera::Load(ElementPtr _sdf) } ///////////////////////////////////////////////// -sdf::ElementPtr Camera::Element() const +ElementPtr Camera::Element() const { return this->dataPtr->sdf; } diff --git a/src/Collision.cc b/src/Collision.cc index 47f4c33e5..8210a6375 100644 --- a/src/Collision.cc +++ b/src/Collision.cc @@ -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 poseRelativeToGraph; + public: std::weak_ptr poseRelativeToGraph; }; ///////////////////////////////////////////////// @@ -164,7 +164,7 @@ void Collision::SetGeom(const Geometry &_geom) } ///////////////////////////////////////////////// -sdf::Surface *Collision::Surface() const +Surface *Collision::Surface() const { return &this->dataPtr->surface; } @@ -237,7 +237,7 @@ void Collision::SetPoseRelativeToGraph( } ///////////////////////////////////////////////// -sdf::SemanticPose Collision::SemanticPose() const +SemanticPose Collision::SemanticPose() const { return sdf::SemanticPose( this->dataPtr->pose, @@ -247,7 +247,7 @@ sdf::SemanticPose Collision::SemanticPose() const } ///////////////////////////////////////////////// -sdf::ElementPtr Collision::Element() const +ElementPtr Collision::Element() const { return this->dataPtr->sdf; } diff --git a/src/Console.cc b/src/Console.cc index 781491477..2f9d69a81 100644 --- a/src/Console.cc +++ b/src/Console.cc @@ -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); } @@ -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; } diff --git a/src/Cylinder.cc b/src/Cylinder.cc index 0f2fe3cb3..9e584e461 100644 --- a/src/Cylinder.cc +++ b/src/Cylinder.cc @@ -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; }; ///////////////////////////////////////////////// @@ -161,7 +161,7 @@ void Cylinder::SetLength(const double _length) } ///////////////////////////////////////////////// -sdf::ElementPtr Cylinder::Element() const +ElementPtr Cylinder::Element() const { return this->dataPtr->sdf; } diff --git a/src/Element.cc b/src/Element.cc index d30d74572..89ecd1dde 100644 --- a/src/Element.cc +++ b/src/Element.cc @@ -797,7 +797,7 @@ std::map Element::CountNamedElements( { std::map result; - sdf::ElementPtr elem; + ElementPtr elem; if (_type.empty()) { elem = this->GetFirstElement(); @@ -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(); @@ -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(); diff --git a/src/Error.cc b/src/Error.cc index 6bb0de550..e0effb7a0 100644 --- a/src/Error.cc +++ b/src/Error.cc @@ -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::type>(_err.Code()) + << static_cast::type>(_err.Code()) << " Msg: " << _err.Message(); return _out; } diff --git a/src/Exception.cc b/src/Exception.cc index bdc4b47f5..7ad38de1a 100644 --- a/src/Exception.cc +++ b/src/Exception.cc @@ -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(this->dataPtr->line), 31) << *this; } diff --git a/src/ForceTorque.cc b/src/ForceTorque.cc index aab5b9cca..c3bdcefa6 100644 --- a/src/ForceTorque.cc +++ b/src/ForceTorque.cc @@ -54,7 +54,7 @@ class sdf::ForceTorquePrivate ForceTorqueMeasureDirection::CHILD_TO_PARENT; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; }; ////////////////////////////////////////////////// @@ -162,16 +162,16 @@ Errors ForceTorque::Load(ElementPtr _sdf) } } - auto loadAxisNoise = [&errors](sdf::ElementPtr _parent, + auto loadAxisNoise = [&errors](ElementPtr _parent, const std::string _groupLabel, const std::string _axisLabel, - sdf::Noise& _noise) + Noise& _noise) { if (_parent->HasElement(_groupLabel) && _parent->GetElement(_groupLabel)->HasElement(_axisLabel)) { auto axis = _parent->GetElement(_groupLabel)->GetElement(_axisLabel); - sdf::Errors noiseErrors = _noise.Load(axis->GetElement("noise")); + Errors noiseErrors = _noise.Load(axis->GetElement("noise")); errors.insert(errors.end(), noiseErrors.begin(), noiseErrors.end()); return true; } @@ -189,7 +189,7 @@ Errors ForceTorque::Load(ElementPtr _sdf) } ////////////////////////////////////////////////// -sdf::ElementPtr ForceTorque::Element() const +ElementPtr ForceTorque::Element() const { return this->dataPtr->sdf; } diff --git a/src/Frame.cc b/src/Frame.cc index c6a5737df..5c1b932b5 100644 --- a/src/Frame.cc +++ b/src/Frame.cc @@ -39,16 +39,16 @@ class sdf::FramePrivate public: std::string poseRelativeTo = ""; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; /// \brief Name of graph source. std::string graphSourceName = ""; /// \brief Weak pointer to model's or worlds's Frame Attached-To Graph. - public: std::weak_ptr frameAttachedToGraph; + public: std::weak_ptr frameAttachedToGraph; /// \brief Weak pointer to model's or world's Pose Relative-To Graph. - public: std::weak_ptr poseRelativeToGraph; + public: std::weak_ptr poseRelativeToGraph; }; ///////////////////////////////////////////////// @@ -235,7 +235,7 @@ Errors Frame::ResolveAttachedToBody(std::string &_body) const } ///////////////////////////////////////////////// -sdf::SemanticPose Frame::SemanticPose() const +SemanticPose Frame::SemanticPose() const { std::string relativeTo = this->dataPtr->poseRelativeTo; if (relativeTo.empty()) @@ -250,7 +250,7 @@ sdf::SemanticPose Frame::SemanticPose() const } ///////////////////////////////////////////////// -sdf::ElementPtr Frame::Element() const +ElementPtr Frame::Element() const { return this->dataPtr->sdf; } diff --git a/src/Geometry.cc b/src/Geometry.cc index 7c4030262..13b0f37e4 100644 --- a/src/Geometry.cc +++ b/src/Geometry.cc @@ -53,7 +53,7 @@ class sdf::GeometryPrivate public: std::unique_ptr heightmap; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; }; ///////////////////////////////////////////////// @@ -77,18 +77,18 @@ Geometry::Geometry(const Geometry &_geometry) if (_geometry.dataPtr->box) { - this->dataPtr->box = std::make_unique(*_geometry.dataPtr->box); + this->dataPtr->box = std::make_unique(*_geometry.dataPtr->box); } if (_geometry.dataPtr->cylinder) { - this->dataPtr->cylinder = std::make_unique( + this->dataPtr->cylinder = std::make_unique( *_geometry.dataPtr->cylinder); } if (_geometry.dataPtr->plane) { - this->dataPtr->plane = std::make_unique( + this->dataPtr->plane = std::make_unique( *_geometry.dataPtr->plane); } @@ -99,7 +99,7 @@ Geometry::Geometry(const Geometry &_geometry) if (_geometry.dataPtr->sphere) { - this->dataPtr->sphere = std::make_unique( + this->dataPtr->sphere = std::make_unique( *_geometry.dataPtr->sphere); } @@ -111,7 +111,7 @@ Geometry::Geometry(const Geometry &_geometry) if (_geometry.dataPtr->heightmap) { this->dataPtr->heightmap = - std::make_unique(*_geometry.dataPtr->heightmap); + std::make_unique(*_geometry.dataPtr->heightmap); } this->dataPtr->sdf = _geometry.dataPtr->sdf; @@ -212,7 +212,7 @@ Errors Geometry::Load(ElementPtr _sdf) polylineElem != nullptr; polylineElem = polylineElem->GetNextElement("polyline")) { - sdf::Polyline polyline; + Polyline polyline; auto err = polyline.Load(polylineElem); errors.insert(errors.end(), err.begin(), err.end()); this->dataPtr->polylines.push_back(polyline); @@ -319,7 +319,7 @@ void Geometry::SetPolylineShape(const std::vector &_polylines) } ///////////////////////////////////////////////// -sdf::ElementPtr Geometry::Element() const +ElementPtr Geometry::Element() const { return this->dataPtr->sdf; } diff --git a/src/Gui.cc b/src/Gui.cc index 26ac5555a..82c5bafe4 100644 --- a/src/Gui.cc +++ b/src/Gui.cc @@ -26,7 +26,7 @@ class sdf::GuiPrivate public: bool fullscreen = false; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; }; ///////////////////////////////////////////////// @@ -110,7 +110,7 @@ bool Gui::operator==(const Gui &_gui) const } ///////////////////////////////////////////////// -sdf::ElementPtr Gui::Element() const +ElementPtr Gui::Element() const { return this->dataPtr->sdf; } diff --git a/src/Heightmap.cc b/src/Heightmap.cc index 70b161fb7..0e93a7e6a 100644 --- a/src/Heightmap.cc +++ b/src/Heightmap.cc @@ -35,7 +35,7 @@ class sdf::HeightmapTexturePrivate public: double size{10.0}; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf{nullptr}; + public: ElementPtr sdf{nullptr}; }; // Private data class @@ -48,7 +48,7 @@ class sdf::HeightmapBlendPrivate public: double fadeDistance{0.0}; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf{nullptr}; + public: ElementPtr sdf{nullptr}; }; // Private data class @@ -79,7 +79,7 @@ class sdf::HeightmapPrivate public: std::vector blends; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf{nullptr}; + public: ElementPtr sdf{nullptr}; }; ///////////////////////////////////////////////// @@ -182,7 +182,7 @@ Errors HeightmapTexture::Load(ElementPtr _sdf) } ///////////////////////////////////////////////// -sdf::ElementPtr HeightmapTexture::Element() const +ElementPtr HeightmapTexture::Element() const { return this->dataPtr->sdf; } @@ -313,7 +313,7 @@ Errors HeightmapBlend::Load(ElementPtr _sdf) } ///////////////////////////////////////////////// -sdf::ElementPtr HeightmapBlend::Element() const +ElementPtr HeightmapBlend::Element() const { return this->dataPtr->sdf; } @@ -441,7 +441,7 @@ Errors Heightmap::Load(ElementPtr _sdf) } ///////////////////////////////////////////////// -sdf::ElementPtr Heightmap::Element() const +ElementPtr Heightmap::Element() const { return this->dataPtr->sdf; } diff --git a/src/Imu.cc b/src/Imu.cc index 70b33b9e7..0268296f6 100644 --- a/src/Imu.cc +++ b/src/Imu.cc @@ -63,7 +63,7 @@ class sdf::ImuPrivate public: std::string customRpyParentFrame; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; }; ////////////////////////////////////////////////// @@ -124,7 +124,7 @@ Errors Imu::Load(ElementPtr _sdf) // Load the linear acceleration noise values. if (_sdf->HasElement("linear_acceleration")) { - sdf::ElementPtr elem = _sdf->GetElement("linear_acceleration"); + ElementPtr elem = _sdf->GetElement("linear_acceleration"); if (elem->HasElement("x")) { if (elem->GetElement("x")->HasElement("noise")) @@ -156,7 +156,7 @@ Errors Imu::Load(ElementPtr _sdf) // Load the angular velocity noise values. if (_sdf->HasElement("angular_velocity")) { - sdf::ElementPtr elem = _sdf->GetElement("angular_velocity"); + ElementPtr elem = _sdf->GetElement("angular_velocity"); if (elem->HasElement("x")) { if (elem->GetElement("x")->HasElement("noise")) @@ -187,7 +187,7 @@ Errors Imu::Load(ElementPtr _sdf) if (_sdf->HasElement("orientation_reference_frame")) { - sdf::ElementPtr elem = _sdf->GetElement("orientation_reference_frame"); + ElementPtr elem = _sdf->GetElement("orientation_reference_frame"); this->dataPtr->localization = elem->Get("localization", this->dataPtr->localization).first; @@ -214,7 +214,7 @@ Errors Imu::Load(ElementPtr _sdf) } ////////////////////////////////////////////////// -sdf::ElementPtr Imu::Element() const +ElementPtr Imu::Element() const { return this->dataPtr->sdf; } diff --git a/src/Joint.cc b/src/Joint.cc index f33e8e90d..224f126f9 100644 --- a/src/Joint.cc +++ b/src/Joint.cc @@ -71,10 +71,10 @@ class sdf::JointPrivate public: std::array, 2> axis; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; /// \brief Weak pointer to model's Pose Relative-To Graph. - public: std::weak_ptr poseRelativeToGraph; + public: std::weak_ptr poseRelativeToGraph; /// \brief The sensors specified in this joint. public: std::vector sensors; @@ -402,7 +402,7 @@ void Joint::SetPoseRelativeToGraph( } ///////////////////////////////////////////////// -sdf::SemanticPose Joint::SemanticPose() const +SemanticPose Joint::SemanticPose() const { return sdf::SemanticPose( this->dataPtr->pose, @@ -424,7 +424,7 @@ void Joint::SetThreadPitch(double _threadPitch) } ///////////////////////////////////////////////// -sdf::ElementPtr Joint::Element() const +ElementPtr Joint::Element() const { return this->dataPtr->sdf; } diff --git a/src/JointAxis.cc b/src/JointAxis.cc index bedc16b18..375319e8d 100644 --- a/src/JointAxis.cc +++ b/src/JointAxis.cc @@ -75,13 +75,13 @@ class sdf::JointAxisPrivate public: double dissipation = 1.0; /// \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 poseRelativeToGraph; + public: std::weak_ptr poseRelativeToGraph; }; ///////////////////////////////////////////////// @@ -157,7 +157,7 @@ Errors JointAxis::Load(ElementPtr _sdf) // Load dynamic values, if present if (_sdf->HasElement("dynamics")) { - sdf::ElementPtr dynElement = _sdf->GetElement("dynamics"); + ElementPtr dynElement = _sdf->GetElement("dynamics"); this->dataPtr->damping = dynElement->Get("damping", 0.0).first; this->dataPtr->friction = dynElement->Get("friction", 0.0).first; @@ -170,7 +170,7 @@ Errors JointAxis::Load(ElementPtr _sdf) // Load limit values if (_sdf->HasElement("limit")) { - sdf::ElementPtr limitElement = _sdf->GetElement("limit"); + ElementPtr limitElement = _sdf->GetElement("limit"); this->dataPtr->lower = limitElement->Get("lower", -1e16).first; this->dataPtr->upper = limitElement->Get("upper", 1e16).first; @@ -415,7 +415,7 @@ Errors JointAxis::ResolveXyz( } ///////////////////////////////////////////////// -sdf::ElementPtr JointAxis::Element() const +ElementPtr JointAxis::Element() const { return this->dataPtr->sdf; } diff --git a/src/Lidar.cc b/src/Lidar.cc index 103cccdea..7f6e3b0b2 100644 --- a/src/Lidar.cc +++ b/src/Lidar.cc @@ -59,7 +59,7 @@ class sdf::LidarPrivate public: Noise lidarNoise; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf{nullptr}; + public: ElementPtr sdf{nullptr}; }; ////////////////////////////////////////////////// @@ -136,10 +136,10 @@ Errors Lidar::Load(ElementPtr _sdf) // Load lidar sensor properties if (_sdf->HasElement("scan")) { - sdf::ElementPtr elem = _sdf->GetElement("scan"); + ElementPtr elem = _sdf->GetElement("scan"); if (elem->HasElement("horizontal")) { - sdf::ElementPtr subElem = elem->GetElement("horizontal"); + ElementPtr subElem = elem->GetElement("horizontal"); if (subElem->HasElement("samples")) this->dataPtr->horizontalScanSamples = subElem->Get( "samples"); @@ -162,7 +162,7 @@ Errors Lidar::Load(ElementPtr _sdf) if (elem->HasElement("vertical")) { - sdf::ElementPtr subElem = elem->GetElement("vertical"); + ElementPtr subElem = elem->GetElement("vertical"); if (subElem->HasElement("samples")) this->dataPtr->verticalScanSamples = subElem->Get( "samples"); @@ -186,7 +186,7 @@ Errors Lidar::Load(ElementPtr _sdf) if (_sdf->HasElement("range")) { - sdf::ElementPtr elem = _sdf->GetElement("range"); + ElementPtr elem = _sdf->GetElement("range"); if (elem->HasElement("min")) this->dataPtr->minRange = elem->Get("min"); if (elem->HasElement("max")) @@ -208,7 +208,7 @@ Errors Lidar::Load(ElementPtr _sdf) } ////////////////////////////////////////////////// -sdf::ElementPtr Lidar::Element() const +ElementPtr Lidar::Element() const { return this->dataPtr->sdf; } diff --git a/src/Light.cc b/src/Light.cc index f2944d3b4..85024e3a3 100644 --- a/src/Light.cc +++ b/src/Light.cc @@ -38,13 +38,13 @@ class sdf::LightPrivate public: LightType type = LightType::POINT; /// \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 poseRelativeToGraph; + public: std::weak_ptr poseRelativeToGraph; /// \brief True if the light should cast shadows. public: bool castShadows = false; @@ -199,7 +199,7 @@ Errors Light::Load(ElementPtr _sdf) this->dataPtr->specular = _sdf->Get("specular", this->dataPtr->specular).first; - sdf::ElementPtr attenuationElem = _sdf->GetElement("attenuation"); + ElementPtr attenuationElem = _sdf->GetElement("attenuation"); if (attenuationElem) { std::pair doubleValue = attenuationElem->Get( @@ -237,7 +237,7 @@ Errors Light::Load(ElementPtr _sdf) this->dataPtr->direction = dirPair.first; } - sdf::ElementPtr spotElem = _sdf->GetElement("spot"); + ElementPtr spotElem = _sdf->GetElement("spot"); if (this->dataPtr->type == LightType::SPOT && spotElem) { // Check for and set inner_angle @@ -347,7 +347,7 @@ void Light::SetPoseRelativeToGraph( } ///////////////////////////////////////////////// -sdf::SemanticPose Light::SemanticPose() const +SemanticPose Light::SemanticPose() const { return sdf::SemanticPose( this->dataPtr->pose, @@ -357,7 +357,7 @@ sdf::SemanticPose Light::SemanticPose() const } ///////////////////////////////////////////////// -sdf::ElementPtr Light::Element() const +ElementPtr Light::Element() const { return this->dataPtr->sdf; } diff --git a/src/Link.cc b/src/Link.cc index 1a2d965c1..395fa8647 100644 --- a/src/Link.cc +++ b/src/Link.cc @@ -61,13 +61,13 @@ class sdf::LinkPrivate ignition::math::Pose3d::Zero}; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; /// \brief True if this link should be subject to wind, false otherwise. public: bool enableWind = false; /// \brief Weak pointer to model's Pose Relative-To Graph. - public: std::weak_ptr poseRelativeToGraph; + public: std::weak_ptr poseRelativeToGraph; }; ///////////////////////////////////////////////// @@ -171,7 +171,7 @@ Errors Link::Load(ElementPtr _sdf) if (_sdf->HasElement("inertial")) { - sdf::ElementPtr inertialElem = _sdf->GetElement("inertial"); + ElementPtr inertialElem = _sdf->GetElement("inertial"); if (inertialElem->HasElement("pose")) loadPose(inertialElem->GetElement("pose"), inertiaPose, inertiaFrame); @@ -181,7 +181,7 @@ Errors Link::Load(ElementPtr _sdf) if (inertialElem->HasElement("inertia")) { - sdf::ElementPtr inertiaElem = inertialElem->GetElement("inertia"); + ElementPtr inertiaElem = inertialElem->GetElement("inertia"); xxyyzz.X(inertiaElem->Get("ixx", 1.0).first); xxyyzz.Y(inertiaElem->Get("iyy", 1.0).first); @@ -442,7 +442,7 @@ void Link::SetPoseRelativeToGraph( } ///////////////////////////////////////////////// -sdf::SemanticPose Link::SemanticPose() const +SemanticPose Link::SemanticPose() const { return sdf::SemanticPose( this->dataPtr->pose, @@ -491,7 +491,7 @@ const Light *Link::LightByName(const std::string &_name) const } ///////////////////////////////////////////////// -sdf::ElementPtr Link::Element() const +ElementPtr Link::Element() const { return this->dataPtr->sdf; } diff --git a/src/Magnetometer.cc b/src/Magnetometer.cc index 4ecaf8bb0..d65010140 100644 --- a/src/Magnetometer.cc +++ b/src/Magnetometer.cc @@ -27,7 +27,7 @@ class sdf::MagnetometerPrivate public: std::array noise; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; }; ////////////////////////////////////////////////// @@ -92,7 +92,7 @@ Errors Magnetometer::Load(ElementPtr _sdf) { if (_sdf->HasElement(names[i])) { - sdf::ElementPtr elem = _sdf->GetElement(names[i]); + ElementPtr elem = _sdf->GetElement(names[i]); if (elem->HasElement("noise")) this->dataPtr->noise[i].Load(elem->GetElement("noise")); } @@ -138,7 +138,7 @@ void Magnetometer::SetZNoise(const Noise &_noise) } ////////////////////////////////////////////////// -sdf::ElementPtr Magnetometer::Element() const +ElementPtr Magnetometer::Element() const { return this->dataPtr->sdf; } diff --git a/src/Material.cc b/src/Material.cc index 19a0d8db2..904618a04 100644 --- a/src/Material.cc +++ b/src/Material.cc @@ -64,7 +64,7 @@ class sdf::MaterialPrivate public: std::unique_ptr pbr; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; /// \brief The path to the file where this material was defined. public: std::string filePath = ""; @@ -124,7 +124,7 @@ Material &Material::operator=(Material &&_material) } ///////////////////////////////////////////////// -Errors Material::Load(sdf::ElementPtr _sdf) +Errors Material::Load(ElementPtr _sdf) { Errors errors; @@ -145,7 +145,7 @@ Errors Material::Load(sdf::ElementPtr _sdf) // Load the script information if (_sdf->HasElement("script")) { - sdf::ElementPtr elem = _sdf->GetElement("script"); + ElementPtr elem = _sdf->GetElement("script"); std::pair uriPair = elem->Get("uri", ""); if (uriPair.first == "__default__") uriPair.first = ""; @@ -174,7 +174,7 @@ Errors Material::Load(sdf::ElementPtr _sdf) // Load the shader information if (_sdf->HasElement("shader")) { - sdf::ElementPtr elem = _sdf->GetElement("shader"); + ElementPtr elem = _sdf->GetElement("shader"); std::pair typePair = elem->Get("type", "pixel"); @@ -235,7 +235,7 @@ Errors Material::Load(sdf::ElementPtr _sdf) // load pbr param if (_sdf->HasElement("pbr")) { - this->dataPtr->pbr.reset(new sdf::Pbr()); + this->dataPtr->pbr.reset(new Pbr()); Errors pbrErrors = this->dataPtr->pbr->Load(_sdf->GetElement("pbr")); errors.insert(errors.end(), pbrErrors.begin(), pbrErrors.end()); } @@ -328,7 +328,7 @@ void Material::SetDoubleSided(const bool _doubleSided) } ////////////////////////////////////////////////// -sdf::ElementPtr Material::Element() const +ElementPtr Material::Element() const { return this->dataPtr->sdf; } diff --git a/src/Mesh.cc b/src/Mesh.cc index 0e4c6d705..43913a868 100644 --- a/src/Mesh.cc +++ b/src/Mesh.cc @@ -37,7 +37,7 @@ class sdf::MeshPrivate public: bool centerSubmesh = false; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf = nullptr; + public: ElementPtr sdf = nullptr; }; ///////////////////////////////////////////////// @@ -122,7 +122,7 @@ Errors Mesh::Load(ElementPtr _sdf) if (_sdf->HasElement("submesh")) { - sdf::ElementPtr subMesh = _sdf->GetElement("submesh"); + ElementPtr subMesh = _sdf->GetElement("submesh"); std::pair subMeshNamePair = subMesh->Get("name", this->dataPtr->submesh); @@ -150,7 +150,7 @@ Errors Mesh::Load(ElementPtr _sdf) } ///////////////////////////////////////////////// -sdf::ElementPtr Mesh::Element() const +ElementPtr Mesh::Element() const { return this->dataPtr->sdf; } diff --git a/src/Model.cc b/src/Model.cc index 7c88c2094..6c43e74c4 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -72,16 +72,16 @@ class sdf::ModelPrivate public: std::vector models; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; /// \brief Frame Attached-To Graph constructed during Load. - public: std::shared_ptr frameAttachedToGraph; + public: std::shared_ptr frameAttachedToGraph; /// \brief Pose Relative-To Graph constructed during Load. - public: std::shared_ptr poseGraph; + public: std::shared_ptr poseGraph; /// \brief Pose Relative-To Graph in parent (world or __model__) scope. - public: std::weak_ptr parentPoseGraph; + public: std::weak_ptr parentPoseGraph; /// \brief Scope name of parent Pose Relative-To Graph (world or __model__). public: std::string parentPoseGraphScopeName; @@ -107,12 +107,12 @@ Model::Model(const Model &_model) if (_model.dataPtr->frameAttachedToGraph) { this->dataPtr->frameAttachedToGraph = - std::make_shared( + std::make_shared( *_model.dataPtr->frameAttachedToGraph); } if (_model.dataPtr->poseGraph) { - this->dataPtr->poseGraph = std::make_shared( + this->dataPtr->poseGraph = std::make_shared( *_model.dataPtr->poseGraph); } for (auto &link : this->dataPtr->links) @@ -774,7 +774,7 @@ Errors Model::SetPoseRelativeToGraph( } ///////////////////////////////////////////////// -sdf::SemanticPose Model::SemanticPose() const +SemanticPose Model::SemanticPose() const { return sdf::SemanticPose( this->dataPtr->pose, @@ -797,7 +797,7 @@ const Link *Model::LinkByName(const std::string &_name) const } ///////////////////////////////////////////////// -sdf::ElementPtr Model::Element() const +ElementPtr Model::Element() const { return this->dataPtr->sdf; } diff --git a/src/NavSat.cc b/src/NavSat.cc index 088e5d937..0c503637e 100644 --- a/src/NavSat.cc +++ b/src/NavSat.cc @@ -35,7 +35,7 @@ class sdf::NavSatPrivate public: Noise verticalVelocityNoise; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf{nullptr}; + public: ElementPtr sdf{nullptr}; }; ////////////////////////////////////////////////// @@ -105,10 +105,10 @@ Errors NavSat::Load(ElementPtr _sdf) // Load navsat sensor properties if (_sdf->HasElement("position_sensing")) { - sdf::ElementPtr elem = _sdf->GetElement("position_sensing"); + ElementPtr elem = _sdf->GetElement("position_sensing"); if (elem->HasElement("horizontal")) { - sdf::ElementPtr horiz = elem->GetElement("horizontal"); + ElementPtr horiz = elem->GetElement("horizontal"); if (horiz->HasElement("noise")) { this->dataPtr->horizontalPositionNoise.Load(horiz->GetElement("noise")); @@ -116,7 +116,7 @@ Errors NavSat::Load(ElementPtr _sdf) } if (elem->HasElement("vertical")) { - sdf::ElementPtr vert = elem->GetElement("vertical"); + ElementPtr vert = elem->GetElement("vertical"); if (vert->HasElement("noise")) { this->dataPtr->verticalPositionNoise.Load(vert->GetElement("noise")); @@ -125,10 +125,10 @@ Errors NavSat::Load(ElementPtr _sdf) } if (_sdf->HasElement("velocity_sensing")) { - sdf::ElementPtr elem = _sdf->GetElement("velocity_sensing"); + ElementPtr elem = _sdf->GetElement("velocity_sensing"); if (elem->HasElement("horizontal")) { - sdf::ElementPtr horiz = elem->GetElement("horizontal"); + ElementPtr horiz = elem->GetElement("horizontal"); if (horiz->HasElement("noise")) { this->dataPtr->horizontalVelocityNoise.Load(horiz->GetElement("noise")); @@ -136,7 +136,7 @@ Errors NavSat::Load(ElementPtr _sdf) } if (elem->HasElement("vertical")) { - sdf::ElementPtr vert = elem->GetElement("vertical"); + ElementPtr vert = elem->GetElement("vertical"); if (vert->HasElement("noise")) { this->dataPtr->verticalVelocityNoise.Load(vert->GetElement("noise")); @@ -148,7 +148,7 @@ Errors NavSat::Load(ElementPtr _sdf) } ////////////////////////////////////////////////// -sdf::ElementPtr NavSat::Element() const +ElementPtr NavSat::Element() const { return this->dataPtr->sdf; } diff --git a/src/Noise.cc b/src/Noise.cc index d00c1b948..214689393 100644 --- a/src/Noise.cc +++ b/src/Noise.cc @@ -51,7 +51,7 @@ class sdf::NoisePrivate public: double dynamicBiasCorrelationTime = 0.0; /// \brief The SDF element pointer used during load. - public: sdf::ElementPtr sdf; + public: ElementPtr sdf; }; ////////////////////////////////////////////////// @@ -255,7 +255,7 @@ void Noise::SetDynamicBiasCorrelationTime(double _time) } ////////////////////////////////////////////////// -sdf::ElementPtr Noise::Element() const +ElementPtr Noise::Element() const { return this->dataPtr->sdf; } diff --git a/src/Param.cc b/src/Param.cc index c808db885..ec69cce6f 100644 --- a/src/Param.cc +++ b/src/Param.cc @@ -160,10 +160,10 @@ bool Param::GetAny(std::any &_anyVal) const } _anyVal = ret; } - else if (this->IsType()) + else if (this->IsType