diff --git a/youbot_drivers/youbot_oodl/launch/youbot_joint_state_publisher.launch b/youbot_drivers/youbot_oodl/launch/youbot_joint_state_publisher.launch
index 987a968..e629379 100644
--- a/youbot_drivers/youbot_oodl/launch/youbot_joint_state_publisher.launch
+++ b/youbot_drivers/youbot_oodl/launch/youbot_joint_state_publisher.launch
@@ -6,7 +6,7 @@
-
+
-
\ No newline at end of file
+
diff --git a/youbot_manipulation/simple_trajectory_controller/src/youbot_trajectory_controller.cpp b/youbot_manipulation/simple_trajectory_controller/src/youbot_trajectory_controller.cpp
index e2c8982..a20cea9 100644
--- a/youbot_manipulation/simple_trajectory_controller/src/youbot_trajectory_controller.cpp
+++ b/youbot_manipulation/simple_trajectory_controller/src/youbot_trajectory_controller.cpp
@@ -116,13 +116,11 @@ int main(int argc, char **argv) {
command.positions = armJointPositions;
armPositionsPublisher = n.advertise ("arm_1/arm_controller/position_command", 1);
- ros::spinOnce();
ros::Subscriber armTrajectory;
armTrajectory = n.subscribe("/arm_controller/follow_joint_trajectory/goal", 1, trajectoryCallback);
ros::Duration(1).sleep();
- ros::spinOnce();
moveToInitPos(command);
//ros::Duration(10).sleep();