diff --git a/CHANGELOG.md b/CHANGELOG.md
index 5e5933c507e254af54200994be02649d0357b2b0..6383a9ff5c435c22cbf4ed30370f96a2b5cbb3a2 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -2,15 +2,24 @@
 
 ## 0.7.0 - UNRELEASED
 
-Requires `libfranka` >= 0.5.0
-
-  * `franka_combined_example_controllers` : Added this package with an example for dual-arm control based on franka_combinable_hw
+Requires `libfranka` >= 0.7.0
+  * **Breaking** moved services and action from `franka_control` to `franka_msgs`.
+  * **Breaking** moved Service container from `franka_control` to `franka_hw`.
+  * `franka_example_controllers` : Added example for dual-arm control based on franka_combinable_hw.
   * `franka_description` : Added an example urdf with two panda arms.
-  * `franka_combinable_hw`: Added this package to support torque-controlling multiple robots from one controller.
-  * `franka_combined_control`: Added this package which contains a control node that can run multiple instances of `FrankaCombinableHW`.
+  * `franka_hw`:
+    - Added hardware classes to support torque-controlling multiple robots from one controller.
+    - Refactored FrankaHW class to serve as base class (e.g. for FrankaCombinableHW).
+    - Added joint limits checking to FrankaHW which means parameterized warning prints when approaching limits.
+    - Made initial collision behavior a parameter.
+    - Added default constructor and init method to FrankaHW.
+    - **Breaking** moved parsing of parameters from control node to FrankaHW::init.
+    - **Breaking** made libfranka robot a member of FrankaHW.
+  * `franka_control` :
+    - Added control node that can runs a `FrankaCombinedHW` to control mulitple Pandas.
   * `franka_control`:
     - Publish whole `libfranka` `franka::RobotState` in `franka_state_controller`.
-  * `franka_description`
+  * `franka_description` :
     - **BREAKING** Updated collision volumes.
     - Removed invalid `axis` for `joint8`.
   * `franka_example_controllers`:
@@ -124,4 +133,3 @@ Requires `libfranka` >= 0.2.0
 ## 0.1.0 - 2017-09-15
 
   * Initial release
-
diff --git a/franka_control/src/franka_combined_control_node.cpp b/franka_control/src/franka_combined_control_node.cpp
index a5211c767131a3a795039df672adf4229d559220..dfcb9ba4f6839b8fb0e37dc27b9bcf9693c28e98 100644
--- a/franka_control/src/franka_combined_control_node.cpp
+++ b/franka_control/src/franka_combined_control_node.cpp
@@ -5,6 +5,7 @@
 #include <franka_hw/franka_combined_hw.h>
 #include <ros/ros.h>
 
+#include <franka/control_tools.h>
 #include <sched.h>
 #include <string>
 
@@ -21,18 +22,11 @@ int main(int argc, char** argv) {
     return 1;
   }
 
-  // set current control_loop thread to real-time
-  const int kThreadPriority = sched_get_priority_max(SCHED_FIFO);
-  if (kThreadPriority == -1) {
-    ROS_ERROR("franka_combined_control_node: unable to get maximum possible thread priority: %s",
-              std::strerror(errno));
-    return 1;
-  }
-  sched_param thread_param{};
-  thread_param.sched_priority = kThreadPriority;
-  if (pthread_setschedparam(pthread_self(), SCHED_FIFO, &thread_param) != 0) {
-    ROS_ERROR("franka_combined_control_node: unable to set realtime scheduling: %s",
-              std::strerror(errno));
+  // set current thread to real-time priority
+  std::string error_message;
+  if (!franka::setCurrentThreadToHighestSchedulerPriority(&error_message)) {
+    ROS_ERROR("franka_combined_control_node: Failed to set thread priority to real-time. Error: %s",
+              error_message.c_str());
     return 1;
   }
 
diff --git a/franka_example_controllers/launch/joint_impedance_example_controller.launch b/franka_example_controllers/launch/joint_impedance_example_controller.launch
index 326617e1532ef9fd200f688321096e8b6f3afdb4..380c5e1f83553942c7426c0c8586e5aa0400940b 100644
--- a/franka_example_controllers/launch/joint_impedance_example_controller.launch
+++ b/franka_example_controllers/launch/joint_impedance_example_controller.launch
@@ -9,4 +9,5 @@
 
   <rosparam command="load" file="$(find franka_example_controllers)/config/franka_example_controllers.yaml" />
   <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen"  args="joint_impedance_example_controller"/>
+  <node pkg="rviz" type="rviz" output="screen" name="rviz" args="-d $(find franka_example_controllers)/launch/robot.rviz"/>
 </launch>