diff --git a/src/TimedPlanner.cpp b/src/TimedPlanner.cpp
index a1d019459df0269320acb37ab72d2d3e64bb0566..7bb35446c5d1f5bf5a827cbf46bbae61a95a2c4f 100644
--- a/src/TimedPlanner.cpp
+++ b/src/TimedPlanner.cpp
@@ -22,7 +22,7 @@ namespace PlannerState {
   TrajectoryUtil traj_util;
 
   const double default_velocity = 1.0;
-  const std::string default_planning_mode = TrajectoryUtil::CARTESIAN_PATH;
+  const std::string default_planning_mode = TrajectoryUtil::FLUID_PATH;
 
   bool isInitialized = false;
   bool isLooping = true;
@@ -184,10 +184,10 @@ void doMotion(const ros::NodeHandle &node_handle, moveit::planning_interface::Mo
       }
     }
 
-    double velocity = 0.0   ;
-    std::string planning_mode;
+    double velocity = 0.0;
+    std::string planning_mode = "";
 
-   if (!node_handle.getParam("robot_speed_factor", velocity)) {
+    if (!node_handle.getParam("robot_speed_factor", velocity)) {
       velocity = PlannerState::default_velocity;
     }