diff --git a/src/IntroPackage.cpp b/src/IntroPackage.cpp
index e88544d012da7a86f54daa01b443ff5b11579717..fe622aa3398f268e49c85f6c6cf92e7e492c0f28 100644
--- a/src/IntroPackage.cpp
+++ b/src/IntroPackage.cpp
@@ -32,7 +32,7 @@ void move_toCallback(const std_msgs::String::ConstPtr& msg)
     target_pose_2.orientation.x = 0;
     target_pose_2.orientation.y = 0;
     target_pose_2.orientation.z = 0;
-    target_pose_2.orientation.w = 0;
+    target_pose_2.orientation.w = 1;
 
     std::vector<geometry_msgs::Pose> waypoints;
     std::string strA ("A");
@@ -60,7 +60,7 @@ int main(int argc, char** argv)
 {
     ros::init(argc, argv, "intro_package");
     ros::NodeHandle node_handle;
-    ros::AsyncSpinner spinner(1);
+    ros::AsyncSpinner spinner(2);
 
     spinner.start();