diff --git a/config/config.yaml b/config/config.yaml
index 765962ee832c2b8d4821cf2f9d8d9f22b8056131..7d0b038db200970d9ec725796a377c5b9d4b4284 100644
--- a/config/config.yaml
+++ b/config/config.yaml
@@ -1,8 +1,8 @@
 panda_mqtt_connector:
   server: "tcp://localhost:1883"
-  robot_speed_factor: .5
+  robot_speed_factor: .7
   robot_planning_mode: "fluid_path" # "fluid_path" or "cartesian_path"
-  default_trajectory: "circle" # "square" or "circle", everything else is ignored
+  default_trajectory: "<none>" # "square" or "circle", everything else is ignored
   topics:
     robotConfig: "robotconfig"
     dataConfig: "dataconfig"
diff --git a/src/MqttToRosNode.cpp b/src/MqttToRosNode.cpp
index 04a5be7cf9e531023119a62c89b0a261ae4c8ec9..d7c08ad69f10e5fa9c2359e604a270f6afbe6d09 100644
--- a/src/MqttToRosNode.cpp
+++ b/src/MqttToRosNode.cpp
@@ -24,7 +24,7 @@ void handleRobotConfig(const config::RobotConfig &robotConfig, const ros::NodeHa
   ROS_INFO_STREAM("Retrieved new loop-mode: " << robotConfig.looptrajectory());
   n.setParam("loop_trajectory", robotConfig.looptrajectory());
 
-  std::cout << "Retrieved new planning-mode: " << std::endl;
+  ROS_INFO_STREAM("Retrieved new planning-mode.");
   switch (robotConfig.planningmode()) {
     case config::RobotConfig_PlanningMode_FLUID:
       n.setParam("robot_planning_mode", "fluid_path");
@@ -34,6 +34,12 @@ void handleRobotConfig(const config::RobotConfig &robotConfig, const ros::NodeHa
       n.setParam("robot_planning_mode", "cartesian_path");
       ROS_INFO_STREAM("Planning-mode: cartesian");
       break;
+    case config::RobotConfig_PlanningMode_RobotConfig_PlanningMode_INT_MIN_SENTINEL_DO_NOT_USE_:
+      ROS_ERROR_STREAM("Planning-mode: INT_MIN_SENTINEL_DO_NOT_USE_");
+      break;
+    case config::RobotConfig_PlanningMode_RobotConfig_PlanningMode_INT_MAX_SENTINEL_DO_NOT_USE_:
+      ROS_ERROR_STREAM("Planning-mode: INT_MAX_SENTINEL_DO_NOT_USE_");
+      break;
   }
 }