diff --git a/franka_control/launch/franka_control.launch b/franka_control/launch/franka_control.launch
index 1d308e71854deb203b0b4215966215c89c0d927b..f73f94f2960753bb6a9f9e6296d4fe0fdc7bdeab 100644
--- a/franka_control/launch/franka_control.launch
+++ b/franka_control/launch/franka_control.launch
@@ -2,7 +2,6 @@
 <launch>
   <arg name="robot_ip" />
   <arg name="load_gripper" default="true" />
-  <arg name="publish_desired_values" default="false" />
 
   <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" if="$(arg load_gripper)" />
   <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm.urdf.xacro'" unless="$(arg load_gripper)" />
@@ -16,10 +15,12 @@
   <node name="state_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="franka_state_controller"/>
   <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen"/>
   <node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen">
-    <rosparam if="$(eval load_gripper and publish_desired_values)" param="source_list">[franka_state_controller/joint_states_desired, franka_gripper/joint_states] </rosparam>
-    <rosparam if="$(eval load_gripper and not publish_desired_values)" param="source_list">[franka_state_controller/joint_states, franka_gripper/joint_states] </rosparam>
-    <rosparam if="$(eval not load_gripper and publish_desired_values)" param="source_list">[franka_state_controller/joint_states_desired] </rosparam>
-    <rosparam if="$(eval not load_gripper and not publish_desired_values)" param="source_list">[franka_state_controller/joint_states] </rosparam>
-    <param name="rate" value="30"/>
+    <rosparam if="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states, franka_gripper/joint_states] </rosparam>
+    <rosparam unless="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states] </rosparam>
+  </node>
+  <node name="joint_state_desired_publisher" type="joint_state_publisher" pkg="joint_state_publisher" output="screen">
+    <rosparam if="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states_desired, franka_gripper/joint_states] </rosparam>
+    <rosparam unless="$(arg load_gripper)" param="source_list">[franka_state_controller/joint_states_desired] </rosparam>
+    <remap from="/joint_states" to="/joint_states_desired" />
   </node>
 </launch>
diff --git a/panda_moveit_config/launch/move_group.launch b/panda_moveit_config/launch/move_group.launch
index d5ef479501923c14ce9036c6f3433d6fd07d8844..148a4c87174672291ca8659ae9a126079bad8e98 100644
--- a/panda_moveit_config/launch/move_group.launch
+++ b/panda_moveit_config/launch/move_group.launch
@@ -71,6 +71,8 @@
     <param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
     <param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
     <param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
+
+    <remap from="/joint_states" to="/joint_states_desired" />
   </node>
 
 </launch>