diff --git a/CHANGELOG.md b/CHANGELOG.md
index 33a71c8c541ede672d1517e6645b251f8705e730..c4cd355b33fbfd11aeef24730a5f066234453f3a 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -17,6 +17,7 @@ Requires `libfranka` >= 0.5.0
   * **BREAKING** Moved `panda_moveit_config` to [`ros-planning`](https://github.com/ros-planning/panda_moveit_config).
   * Added support for ROS Melodic Morenia.
   * Raised minimum CMake version to 3.4 to match `libfranka`.
+  * Add rosparam to choose value of `franka::RealtimeConfig`.
 
 ## 0.6.0 - 2018-08-08
 
diff --git a/franka_control/config/franka_control_node.yaml b/franka_control/config/franka_control_node.yaml
index fd2524afc14bc81163d105843f6eddd57436117a..333c390abb729f53bc337ebe99e4aa3d36a9078e 100644
--- a/franka_control/config/franka_control_node.yaml
+++ b/franka_control/config/franka_control_node.yaml
@@ -13,3 +13,5 @@ rate_limiting: true
 cutoff_frequency: 100
 # Internal controller for motion generators [joint_impedance|cartesian_impedance]
 internal_controller: joint_impedance
+# Used to decide whether to enforce realtime mode [enforce|ignore]
+realtime_config: enforce
diff --git a/franka_control/src/franka_control_node.cpp b/franka_control/src/franka_control_node.cpp
index ce116d5e7983749afe4db99afe3fa052e5e66d8b..f6fbd71140625f2559571b451ba9e86494c8f062 100644
--- a/franka_control/src/franka_control_node.cpp
+++ b/franka_control/src/franka_control_node.cpp
@@ -78,7 +78,18 @@ int main(int argc, char** argv) {
     ROS_ERROR("Invalid or no arm_id parameter provided");
     return 1;
   }
-  franka::Robot robot(robot_ip);
+
+  std::string realtime_config_param = node_handle.param("realtime_config", std::string("enforce"));
+  franka::RealtimeConfig realtime_config;
+  if (realtime_config_param == "enforce") {
+    realtime_config = franka::RealtimeConfig::kEnforce;
+  } else if (realtime_config_param == "ignore") {
+    realtime_config = franka::RealtimeConfig::kIgnore;
+  } else {
+    ROS_ERROR("Invalid realtime_config parameter provided. Valid values are 'enforce', 'ignore'.");
+    return 1;
+  }
+  franka::Robot robot(robot_ip, realtime_config);
 
   // Set default collision behavior
   robot.setCollisionBehavior(
@@ -149,7 +160,9 @@ int main(int argc, char** argv) {
     } else if (internal_controller == "cartesian_impedance") {
       controller_mode = franka::ControllerMode::kCartesianImpedance;
     } else {
-      ROS_WARN("Invalid internal_controller parameter provided, falling back to joint impedance");
+      ROS_WARN(
+          "Invalid internal_controller parameter provided, falling back to joint impedance. Valid "
+          "values are: 'joint_impedance', 'cartesian_impedance'.");
       controller_mode = franka::ControllerMode::kJointImpedance;
     }