diff --git a/include/ignition/math/Pose3.hh b/include/ignition/math/Pose3.hh
index bb0bd655b..01707f0e6 100644
--- a/include/ignition/math/Pose3.hh
+++ b/include/ignition/math/Pose3.hh
@@ -377,13 +377,10 @@ namespace ignition
         return this->p.X();
       }
 
-      /// \brief Get the mutable X value of the position.
-      /// \return Value X of the origin of the pose.
-      /// \note The return is made by value since
-      /// Vector3<T>.X() is already a reference.
-      public: inline T &X()
+      /// \brief Set X value of the position.
+      public: inline void SetX(T x)
       {
-        return this->p.X();
+       this->p.X() = x;
       }
 
       /// \brief Get the Y value of the position.
@@ -395,13 +392,10 @@ namespace ignition
         return this->p.Y();
       }
 
-      /// \brief Get the mutable Y value of the position.
-      /// \return Value Y of the origin of the pose.
-      /// \note The return is made by value since
-      /// Vector3<T>.Y() is already a reference.
-      public: inline T &Y()
+      /// \brief Set the Y value of the position.
+      public: inline void SetY(T y)
       {
-        return this->p.Y();
+        this->p.Y() = y;
       }
 
       /// \brief Get the Z value of the position.
@@ -413,13 +407,10 @@ namespace ignition
         return this->p.Z();
       }
 
-      /// \brief Get the mutable Z value of the position.
-      /// \return Value Z of the origin of the pose.
-      /// \note The return is made by value since
-      /// Vector3<T>.Z() is already a reference.
-      public: inline T &Z()
+      /// \brief Set the Z value of the position.
+      public: inline void SetZ(T z)
       {
-        return this->p.Z();
+        this->p.Z() = z;
       }
 
       /// \brief Get the rotation.
@@ -450,7 +441,7 @@ namespace ignition
       /// \note The return is made by value since
       ///  Quaternion<T>.Roll() is already a reference.
       public: inline T &Roll()
-      { 
+      {
         return this->q.Roll();
       }
 
diff --git a/src/Pose_TEST.cc b/src/Pose_TEST.cc
index 78ccd0552..ad7b361ed 100644
--- a/src/Pose_TEST.cc
+++ b/src/Pose_TEST.cc
@@ -141,7 +141,7 @@ TEST(PoseTest, Pose)
 TEST(PoseTest, ConstPose)
 {
   const math::Pose3d pose(0, 1, 2, 1, 0, 0);
-  
+
   EXPECT_TRUE(pose.Pos() == math::Vector3d(0, 1, 2));
   EXPECT_TRUE(pose.Rot() == math::Quaterniond(1, 0, 0));
 }
@@ -168,13 +168,12 @@ TEST(PoseTest, MutablePose)
 
   EXPECT_TRUE(pose.Pos() == math::Vector3d(10, 20, 30));
   EXPECT_TRUE(pose.Rot() == math::Quaterniond(1, 2, 1));
- }
+}
 
 /////////////////////////////////////////////////
 TEST(PoseTest, ConstPoseElements)
 {
   const math::Pose3d pose(0, 1, 2, 1, 1, 2);
- 
   EXPECT_DOUBLE_EQ(pose.X(), 0);
   EXPECT_DOUBLE_EQ(pose.Y(), 1);
   EXPECT_DOUBLE_EQ(pose.Z(), 2);
@@ -187,25 +186,15 @@ TEST(PoseTest, ConstPoseElements)
 TEST(PoseTest, MutablePoseElements)
 {
   math::Pose3d pose(1, 2, 3, 1.57, 1, 2);
-
   EXPECT_DOUBLE_EQ(pose.X(), 1);
   EXPECT_DOUBLE_EQ(pose.Y(), 2);
   EXPECT_DOUBLE_EQ(pose.Z(), 3);
-  EXPECT_DOUBLE_EQ(pose.Rot().Roll(), 1.57);
-  EXPECT_DOUBLE_EQ(pose.Rot().Pitch(), 1);
-  EXPECT_DOUBLE_EQ(pose.Rot().Yaw(), 2);
 
-  pose.X() = 10;
-  pose.Y() = 12;
-  pose.Z() = 13;
-  // pose.Roll() = 14; 
-  // pose.Pitch() = 15;
-  // pose.Yaw() = 16;
+  pose.SetX(10);
+  pose.SetY(12);
+  pose.SetZ(13);
 
   EXPECT_DOUBLE_EQ(pose.X(), 10);
   EXPECT_DOUBLE_EQ(pose.Y(), 12);
   EXPECT_DOUBLE_EQ(pose.Z(), 13);
-  // EXPECT_EQ(pose.Roll(), 14);
-  // EXPECT_EQ(pose.Pitch(), 15);
-  // EXPECT_EQ(pose.Yaw(), 16);
 }