diff --git a/launch/planning_context.launch b/launch/planning_context.launch
index d32922f6c70862fd5f837028cc2cc2cefb031ed1..d94e6fed91de2ba4c70ce2d86c97c4a416f3e93a 100644
--- a/launch/planning_context.launch
+++ b/launch/planning_context.launch
@@ -8,10 +8,10 @@
   <arg name="robot_description" default="robot_description"/>
 
   <!-- Load universal robot description format (URDF) -->
-  <param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro hand:=$(arg load_gripper) '$(find franka_description)/robots/panda_arm.urdf.xacro' arm_id:=$(arg arm_id)"/>
+  <param name="$(arg robot_description)" command="xacro '$(find franka_description)/robots/panda_arm.urdf.xacro' hand:=$(arg load_gripper) arm_id:=$(arg arm_id)" if="$(arg load_robot_description)" />
 
   <!-- The semantic description that corresponds to the URDF -->
-  <param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro '$(find panda_moveit_config)/config/panda.srdf.xacro' hand:=$(arg load_gripper) arm_id:=$(arg arm_id)"/>
+  <param name="$(arg robot_description)_semantic" command="xacro '$(find panda_moveit_config)/config/panda.srdf.xacro' hand:=$(arg load_gripper) arm_id:=$(arg arm_id)" />
 
   <!-- Load updated joint limits (override information from URDF) -->
   <group ns="$(arg robot_description)_planning">