From 710ca8b6f712d3465d389f5e2b794ae29390e5d2 Mon Sep 17 00:00:00 2001 From: Dave Coleman <dave@picknik.ai> Date: Wed, 14 Aug 2019 00:46:09 -0600 Subject: [PATCH] Remove deprecated inorder tag to fix warning (#36) --- launch/planning_context.launch | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/launch/planning_context.launch b/launch/planning_context.launch index e961339..f0ec470 100644 --- a/launch/planning_context.launch +++ b/launch/planning_context.launch @@ -8,13 +8,13 @@ <arg name="robot_description" default="robot_description"/> <!-- Load universal robot description format (URDF) --> - <param if="$(eval arg('load_robot_description') and arg('load_gripper'))" name="$(arg robot_description)" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'"/> - <param if="$(eval arg('load_robot_description') and not arg('load_gripper'))" name="$(arg robot_description)" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm.urdf.xacro'"/> + <param if="$(eval arg('load_robot_description') and arg('load_gripper'))" name="$(arg robot_description)" command="$(find xacro)/xacro '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'"/> + <param if="$(eval arg('load_robot_description') and not arg('load_gripper'))" name="$(arg robot_description)" command="$(find xacro)/xacro '$(find franka_description)/robots/panda_arm.urdf.xacro'"/> <!-- The semantic description that corresponds to the URDF --> - <param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro --inorder '$(find panda_moveit_config)/config/panda_arm_hand.srdf.xacro'" if="$(arg load_gripper)" /> - <param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro --inorder '$(find panda_moveit_config)/config/panda_arm.srdf.xacro'" unless="$(arg load_gripper)" /> - + <param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro '$(find panda_moveit_config)/config/panda_arm_hand.srdf.xacro'" if="$(arg load_gripper)" /> + <param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro '$(find panda_moveit_config)/config/panda_arm.srdf.xacro'" unless="$(arg load_gripper)" /> + <!-- Load updated joint limits (override information from URDF) --> <group ns="$(arg robot_description)_planning"> <rosparam command="load" file="$(find panda_moveit_config)/config/joint_limits.yaml"/> @@ -24,5 +24,5 @@ <group ns="$(arg robot_description)_kinematics"> <rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/> </group> - + </launch> -- GitLab