diff --git a/qr_global_loc/include/qr_global_loc_alg_node.h b/qr_global_loc/include/qr_global_loc_alg_node.h
index 8857bb41475fdde97dd90b67119182e1d3112d1c..da8fd76d964f2657ffd7b60e1618206c58e09b4d 100644
--- a/qr_global_loc/include/qr_global_loc_alg_node.h
+++ b/qr_global_loc/include/qr_global_loc_alg_node.h
@@ -93,6 +93,7 @@ class QrGlobalLocAlgNode : public algorithm_base::IriBaseAlgorithm<QrGlobalLocAl
     Eigen::Matrix4d robot_transform;
     Eigen::Vector3d robot_position,robot_rotation;
   public:
+   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
    /**
     * \brief Constructor
     * 
diff --git a/qr_global_loc/src/qr_global_loc_alg_node.cpp b/qr_global_loc/src/qr_global_loc_alg_node.cpp
index aae0b2907fde4c8934e60e3fa34a1a9924171801..05a861021d81742ba571ba052f65bffe4b7cacd1 100644
--- a/qr_global_loc/src/qr_global_loc_alg_node.cpp
+++ b/qr_global_loc/src/qr_global_loc_alg_node.cpp
@@ -121,7 +121,7 @@ void QrGlobalLocAlgNode::qr_pose_callback(const humanoid_common_msgs::tag_pose_a
   tf::Matrix3x3 tf_rotation;
   tf::Vector3 tf_position;
   Eigen::Matrix4d body_transform,qr_transform,cam1_transform,cam2_transform,map_transform;
-  std::vector<Eigen::Matrix4d> total_transforms;
+  std::vector< Eigen::Matrix4d,Eigen::aligned_allocator<Eigen::Matrix4d> > total_transforms;
   Eigen::Vector3d position,rotation;
   std::string odom_frame;
   unsigned int i=0,j=0;
@@ -145,8 +145,8 @@ void QrGlobalLocAlgNode::qr_pose_callback(const humanoid_common_msgs::tag_pose_a
     body_transform=this->alg_.generate_transform(position,rotation);
     // QR detection library transfrom
     position << 0.0,0.0,0.0;
-    rotation << -1.5707 , 0.0 , -1.5707;
-    //rotation << 0.0 , 0.0 , 0.0;
+    //rotation << -1.5707 , 0.0 , -1.5707;
+    rotation << 0.0 , 0.0 , 0.0;
     cam1_transform=this->alg_.generate_transform(position,rotation);
     position << 0.0,0.0,0.0;
     rotation << 0.0 , 0.0 , 3.14159;