Skip to content

Commit

Permalink
Migrate namespace usage
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Sep 5, 2022
1 parent 089aa03 commit e40e5af
Show file tree
Hide file tree
Showing 121 changed files with 1,359 additions and 1,359 deletions.
18 changes: 9 additions & 9 deletions include/sdf/Actor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <memory>
#include <string>

#include <ignition/math/Pose3.hh>
#include <gz/math/Pose3.hh>

#include "sdf/Element.hh"
#include "sdf/Types.hh"
Expand Down Expand Up @@ -175,11 +175,11 @@ namespace sdf

/// \brief Get the pose to be reached.
/// \return Pose to be reached.
public: ignition::math::Pose3d Pose() const;
public: gz::math::Pose3d Pose() const;

/// \brief Set the pose to be reached.
/// \param[in] _pose Pose to be reached.
public: void SetPose(const ignition::math::Pose3d &_pose);
public: void SetPose(const gz::math::Pose3d &_pose);

/// \brief Copy waypoint from an Waypoint instance.
/// \param[in] _waypoint The waypoint to set values from.
Expand Down Expand Up @@ -326,27 +326,27 @@ namespace sdf
/// global coordinate frame.
/// \return The pose of the actor.
/// \deprecated See RawPose.
public: const ignition::math::Pose3d &Pose() const
public: const gz::math::Pose3d &Pose() const
SDF_DEPRECATED(9.0);

/// \brief Set the pose of the actor.
/// \sa const ignition::math::Pose3d &Pose() const
/// \sa const gz::math::Pose3d &Pose() const
/// \param[in] _pose The new actor pose.
/// \deprecated See SetRawPose.
public: void SetPose(const ignition::math::Pose3d &_pose)
public: void SetPose(const gz::math::Pose3d &_pose)
SDF_DEPRECATED(9.0);

/// \brief Get the pose of the actor. This is the pose of the actor
/// as specified in SDF (<actor> <pose> ... </pose></actor>), and is
/// typically used to express the position and rotation of an actor in a
/// global coordinate frame.
/// \return The pose of the actor.
public: const ignition::math::Pose3d &RawPose() const;
public: const gz::math::Pose3d &RawPose() const;

/// \brief Set the pose of the actor.
/// \sa const ignition::math::Pose3d &RawPose() const
/// \sa const gz::math::Pose3d &RawPose() const
/// \param[in] _pose The new actor pose.
public: void SetRawPose(const ignition::math::Pose3d &_pose);
public: void SetRawPose(const gz::math::Pose3d &_pose);

/// \brief Get the name of the coordinate frame relative to which this
/// object's pose is expressed. An empty value indicates that the frame is
Expand Down
6 changes: 3 additions & 3 deletions include/sdf/Atmosphere.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#ifndef SDF_ATMOSPHERE_HH_
#define SDF_ATMOSPHERE_HH_

#include <ignition/math/Temperature.hh>
#include <gz/math/Temperature.hh>
#include "sdf/Element.hh"
#include "sdf/Types.hh"
#include "sdf/sdf_config.h"
Expand Down Expand Up @@ -87,11 +87,11 @@ namespace sdf

/// \brief Get the temperature at sea level.
/// \return The temperature at sea level.
public: ignition::math::Temperature Temperature() const;
public: gz::math::Temperature Temperature() const;

/// \brief Set the temperature at sea level.
/// \param[in] _temp The temperature at sea level.
public: void SetTemperature(const ignition::math::Temperature &_temp);
public: void SetTemperature(const gz::math::Temperature &_temp);

/// \brief Get the temperature gradient with respect to increasing
/// altitude in units of K/m.
Expand Down
16 changes: 8 additions & 8 deletions include/sdf/Box.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@
#ifndef SDF_BOX_HH_
#define SDF_BOX_HH_

#include <ignition/math/Box.hh>
#include <ignition/math/Vector3.hh>
#include <gz/math/Box.hh>
#include <gz/math/Vector3.hh>
#include <sdf/Error.hh>
#include <sdf/Element.hh>
#include <sdf/sdf_config.h>
Expand Down Expand Up @@ -69,11 +69,11 @@ namespace sdf

/// \brief Get the box size in meters.
/// \return Size of the box in meters.
public: ignition::math::Vector3d Size() const;
public: gz::math::Vector3d Size() const;

/// \brief Set the box size in meters.
/// \param[in] _size Size of the box in meters.
public: void SetSize(const ignition::math::Vector3d &_size);
public: void SetSize(const gz::math::Vector3d &_size);

/// \brief Get a pointer to the SDF element that was used during
/// load.
Expand All @@ -82,12 +82,12 @@ namespace sdf
public: sdf::ElementPtr Element() const;

/// \brief Get the Ignition Math representation of this Box.
/// \return A const reference to an ignition::math::Boxd object.
public: const ignition::math::Boxd &Shape() const;
/// \return A const reference to an gz::math::Boxd object.
public: const gz::math::Boxd &Shape() const;

/// \brief Get a mutable Ignition Math representation of this Box.
/// \return A reference to an ignition::math::Boxd object.
public: ignition::math::Boxd &Shape();
/// \return A reference to an gz::math::Boxd object.
public: gz::math::Boxd &Shape();

/// \brief Private data pointer.
private: BoxPrivate *dataPtr;
Expand Down
28 changes: 14 additions & 14 deletions include/sdf/Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#define SDF_CAMERA_HH_

#include <string>
#include <ignition/math/Pose3.hh>
#include <gz/math/Pose3.hh>

#include <sdf/Error.hh>
#include <sdf/Element.hh>
Expand All @@ -35,7 +35,7 @@ namespace sdf

/// \enum PixelFormatType
/// \brief The set of pixel formats. This list should match
/// ignition::common::Image::PixelFormatType.
/// gz::common::Image::PixelFormatType.
enum class PixelFormatType
{
UNKNOWN_PIXEL_FORMAT = 0,
Expand Down Expand Up @@ -121,11 +121,11 @@ namespace sdf

/// \brief Get the horizontal field of view in radians.
/// \return The horizontal field of view in radians.
public: ignition::math::Angle HorizontalFov() const;
public: gz::math::Angle HorizontalFov() const;

/// \brief Set the horizontal field of view in radians.
/// \param[in] _hfov The horizontal field of view in radians.
public: void SetHorizontalFov(const ignition::math::Angle &_hfov);
public: void SetHorizontalFov(const gz::math::Angle &_hfov);

/// \brief Get the image width in pixels.
/// \return The image width in pixels.
Expand Down Expand Up @@ -294,36 +294,36 @@ namespace sdf

/// \brief Get the distortion center or principal point.
/// \return Distortion center or principal point.
public: const ignition::math::Vector2d &DistortionCenter() const;
public: const gz::math::Vector2d &DistortionCenter() const;

/// \brief Set the distortion center or principal point.
/// \param[in] _center Distortion center or principal point.
public: void SetDistortionCenter(
const ignition::math::Vector2d &_center) const;
const gz::math::Vector2d &_center) const;

/// \brief Get the pose of the camer. This is the pose of the camera
/// as specified in SDF (<camera> <pose> ... </pose></camera>).
/// \return The pose of the link.
/// \deprecated See RawPose.
public: const ignition::math::Pose3d &Pose() const
public: const gz::math::Pose3d &Pose() const
SDF_DEPRECATED(9.0);

/// \brief Set the pose of the camera.
/// \sa const ignition::math::Pose3d &Pose() const
/// \sa const gz::math::Pose3d &Pose() const
/// \param[in] _pose The new camera pose.
/// \deprecated See SetRawPose.
public: void SetPose(const ignition::math::Pose3d &_pose)
public: void SetPose(const gz::math::Pose3d &_pose)
SDF_DEPRECATED(9.0);

/// \brief Get the pose of the camer. This is the pose of the camera
/// as specified in SDF (<camera> <pose> ... </pose></camera>).
/// \return The pose of the link.
public: const ignition::math::Pose3d &RawPose() const;
public: const gz::math::Pose3d &RawPose() const;

/// \brief Set the pose of the camera.
/// \sa const ignition::math::Pose3d &RawPose() const
/// \sa const gz::math::Pose3d &RawPose() const
/// \param[in] _pose The new camera pose.
public: void SetRawPose(const ignition::math::Pose3d &_pose);
public: void SetRawPose(const gz::math::Pose3d &_pose);

/// \brief Get the name of the coordinate frame relative to which this
/// object's pose is expressed. An empty value indicates that the frame is
Expand Down Expand Up @@ -421,12 +421,12 @@ namespace sdf
/// \brief Get lens cutoff angle. Everything outside of the specified
/// angle will be hidden.
/// \return The lens cutoff angle.
public: ignition::math::Angle LensCutoffAngle() const;
public: gz::math::Angle LensCutoffAngle() const;

/// \brief Set lens cutoff angle. Everything outside of the specified
/// angle will be hidden.
/// \param[in] _angle The lens cutoff angle.
public: void SetLensCutoffAngle(const ignition::math::Angle &_angle);
public: void SetLensCutoffAngle(const gz::math::Angle &_angle);

/// \brief Get environment texture size. This is the resolution of the
/// environment cube map used to draw the world.
Expand Down
14 changes: 7 additions & 7 deletions include/sdf/Collision.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <memory>
#include <string>
#include <ignition/math/Pose3.hh>
#include <gz/math/Pose3.hh>
#include "sdf/Element.hh"
#include "sdf/SemanticPose.hh"
#include "sdf/Types.hh"
Expand Down Expand Up @@ -106,26 +106,26 @@ namespace sdf
/// (<collision><pose> ... </pose></collision>).
/// \return The pose of the collision object.
/// \deprecated See RawPose.
public: const ignition::math::Pose3d &Pose() const
public: const gz::math::Pose3d &Pose() const
SDF_DEPRECATED(9.0);

/// \brief Set the pose of the collision object.
/// \sa const ignition::math::Pose3d &Pose() const
/// \sa const gz::math::Pose3d &Pose() const
/// \param[in] _pose The pose of the collision object.
/// \deprecated See SetRawPose.
public: void SetPose(const ignition::math::Pose3d &_pose)
public: void SetPose(const gz::math::Pose3d &_pose)
SDF_DEPRECATED(9.0);

/// \brief Get the pose of the collision object. This is the pose of the
/// collison as specified in SDF
/// (<collision><pose> ... </pose></collision>).
/// \return The pose of the collision object.
public: const ignition::math::Pose3d &RawPose() const;
public: const gz::math::Pose3d &RawPose() const;

/// \brief Set the pose of the collision object.
/// \sa const ignition::math::Pose3d &RawPose() const
/// \sa const gz::math::Pose3d &RawPose() const
/// \param[in] _pose The pose of the collision object.
public: void SetRawPose(const ignition::math::Pose3d &_pose);
public: void SetRawPose(const gz::math::Pose3d &_pose);

/// \brief Get the name of the coordinate frame relative to which this
/// object's pose is expressed. An empty value indicates that the frame is
Expand Down
10 changes: 5 additions & 5 deletions include/sdf/Cylinder.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#ifndef SDF_CYLINDER_HH_
#define SDF_CYLINDER_HH_

#include <ignition/math/Cylinder.hh>
#include <gz/math/Cylinder.hh>
#include <sdf/Error.hh>
#include <sdf/Element.hh>
#include <sdf/sdf_config.h>
Expand Down Expand Up @@ -90,12 +90,12 @@ namespace sdf
public: sdf::ElementPtr Element() const;

/// \brief Get the Ignition Math representation of this Cylinder.
/// \return A const reference to an ignition::math::Cylinderd object.
public: const ignition::math::Cylinderd &Shape() const;
/// \return A const reference to an gz::math::Cylinderd object.
public: const gz::math::Cylinderd &Shape() const;

/// \brief Get a mutable Ignition Math representation of this Cylinder.
/// \return A reference to an ignition::math::Cylinderd object.
public: ignition::math::Cylinderd &Shape();
/// \return A reference to an gz::math::Cylinderd object.
public: gz::math::Cylinderd &Shape();

/// \brief Private data pointer.
private: CylinderPrivate *dataPtr;
Expand Down
8 changes: 4 additions & 4 deletions include/sdf/Frame.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <memory>
#include <string>
#include <ignition/math/Pose3.hh>
#include <gz/math/Pose3.hh>
#include "sdf/Element.hh"
#include "sdf/SemanticPose.hh"
#include "sdf/Types.hh"
Expand Down Expand Up @@ -107,13 +107,13 @@ namespace sdf
/// (<frame><pose> ... </pose></frame>).
/// Use SemanticPose to compute the pose relative to a specific frame.
/// \return The pose of the frame object.
public: const ignition::math::Pose3d &RawPose() const;
public: const gz::math::Pose3d &RawPose() const;

/// \brief Set the raw pose of the frame object. This is interpreted
/// relative to the frame named in the //pose/@relative_to attribute.
/// \sa const ignition::math::Pose3d &RawPose() const
/// \sa const gz::math::Pose3d &RawPose() const
/// \param[in] _pose The pose of the frame object.
public: void SetRawPose(const ignition::math::Pose3d &_pose);
public: void SetRawPose(const gz::math::Pose3d &_pose);

/// \brief Get the name of the coordinate frame relative to which this
/// frame's pose is expressed. An empty value indicates that the frame is
Expand Down
10 changes: 5 additions & 5 deletions include/sdf/Heightmap.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#define SDF_HEIGHTMAP_HH_

#include <string>
#include <ignition/math/Vector3.hh>
#include <gz/math/Vector3.hh>
#include <sdf/Element.hh>
#include <sdf/Error.hh>
#include <sdf/sdf_config.h>
Expand Down Expand Up @@ -216,19 +216,19 @@ namespace sdf

/// \brief Get the heightmap's scaling factor.
/// \return The heightmap's size.
public: ignition::math::Vector3d Size() const;
public: gz::math::Vector3d Size() const;

/// \brief Set the heightmap's scaling factor. Defaults to 1x1x1.
/// \return The heightmap's size factor.
public: void SetSize(const ignition::math::Vector3d &_size);
public: void SetSize(const gz::math::Vector3d &_size);

/// \brief Get the heightmap's position offset.
/// \return The heightmap's position offset.
public: ignition::math::Vector3d Position() const;
public: gz::math::Vector3d Position() const;

/// \brief Set the heightmap's position offset.
/// \return The heightmap's position offset.
public: void SetPosition(const ignition::math::Vector3d &_position);
public: void SetPosition(const gz::math::Vector3d &_position);

/// \brief Get whether the heightmap uses terrain paging.
/// \return True if the heightmap uses terrain paging.
Expand Down
8 changes: 4 additions & 4 deletions include/sdf/Imu.hh
Original file line number Diff line number Diff line change
Expand Up @@ -138,15 +138,15 @@ namespace sdf
/// X-axis. grav_dir_x is defined in the coordinate frame as defined by
/// the parent_frame element.
/// \return The gravity direction.
public: ignition::math::Vector3d &GravityDirX() const;
public: gz::math::Vector3d &GravityDirX() const;

/// \brief Used when localization is set to GRAV_UP or GRAV_DOWN, a
/// projection of this vector into a plane that is orthogonal to the
/// gravity vector defines the direction of the IMU reference frame's
/// X-axis. grav_dir_x is defined in the coordinate frame as defined by
/// the parent_frame element.
/// \param[in] _grav The gravity direction.
public: void SetGravityDirX(const ignition::math::Vector3d &_grav) const;
public: void SetGravityDirX(const gz::math::Vector3d &_grav) const;

/// \brief Get the name of parent frame which the GravityDirX vector is
/// defined relative to. It can be any valid fully scoped link name or the
Expand Down Expand Up @@ -235,11 +235,11 @@ namespace sdf
/// +z:up).
/// Example sdf: parent_frame="local", custom_rpy="-0.5*M_PI 0 -0.5*M_PI"
/// \return Custom RPY vectory
public: const ignition::math::Vector3d &CustomRpy() const;
public: const gz::math::Vector3d &CustomRpy() const;

/// \brief See CustomRpy() const.
/// \param[in] Custom RPY vectory
public: void SetCustomRpy(const ignition::math::Vector3d &_rpy) const;
public: void SetCustomRpy(const gz::math::Vector3d &_rpy) const;

/// \brief Get the name of parent frame which the custom_rpy transform is
/// defined relative to. It can be any valid fully scoped link name or the
Expand Down
Loading

0 comments on commit e40e5af

Please sign in to comment.