diff --git a/config/fake_controllers.yaml b/config/fake_controllers.yaml index d1415c2c36544717f14641bc50f0c13545b196be..619aa5d08f94e9411bcef80f89d6e6a01dae1882 100644 --- a/config/fake_controllers.yaml +++ b/config/fake_controllers.yaml @@ -11,4 +11,7 @@ controller_list: - name: fake_hand_controller joints: - panda_finger_joint1 - - panda_finger_joint2 \ No newline at end of file + - panda_finger_joint2 +initial: + - group: panda_arm_hand + pose: ready diff --git a/config/hand.xacro b/config/hand.xacro new file mode 100644 index 0000000000000000000000000000000000000000..566f1c1b6ddec3569864fd1067f8f7c4e510064b --- /dev/null +++ b/config/hand.xacro @@ -0,0 +1,23 @@ +<?xml version="1.0" ?> +<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda"> + <xacro:macro name="hand"> + <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc--> + <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included--> + <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included--> + <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> + <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> + <group name="hand"> + <link name="panda_hand" /> + <link name="panda_leftfinger" /> + <link name="panda_rightfinger" /> + <joint name="panda_finger_joint1" /> + <passive_joint name="panda_finger_joint2" /> + </group> + <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> + <!--END EFFECTOR: Purpose: Represent information about an end effector.--> + <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> + <disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent" /> + <disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent" /> + <disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default" /> + </xacro:macro> +</robot> diff --git a/config/joint_limits.yaml b/config/joint_limits.yaml index 6b6684fef7ff352fc954da0da2489c910ae8529c..a2f08edd3bace3d4468490b36fb6d4caf00caf3c 100644 --- a/config/joint_limits.yaml +++ b/config/joint_limits.yaml @@ -1,49 +1,55 @@ # joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed # Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] # Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] + +# As MoveIt! does not support jerk limits, the acceleration limits provided here are the highest values that guarantee +# that no jerk limits will be violated. More precisely, applying Euler differentiation in the worst case (from min accel +# to max accel in 1 ms) the acceleration limits are the ones that satisfy +# max_jerk = (max_acceleration - min_acceleration) / 0.001 + joint_limits: - panda_finger_joint1: - has_velocity_limits: true - max_velocity: 0.3 - has_acceleration_limits: false - max_acceleration: 0 - panda_finger_joint2: - has_velocity_limits: true - max_velocity: 0.3 - has_acceleration_limits: false - max_acceleration: 0 panda_joint1: has_velocity_limits: true - max_velocity: 2.5 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 2.1750 + has_acceleration_limits: true + max_acceleration: 3.75 panda_joint2: has_velocity_limits: true - max_velocity: 2.5 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 2.1750 + has_acceleration_limits: true + max_acceleration: 1.875 panda_joint3: has_velocity_limits: true - max_velocity: 2.5 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 2.1750 + has_acceleration_limits: true + max_acceleration: 2.5 panda_joint4: has_velocity_limits: true - max_velocity: 2.5 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 2.1750 + has_acceleration_limits: true + max_acceleration: 3.125 panda_joint5: has_velocity_limits: true - max_velocity: 3 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 2.6100 + has_acceleration_limits: true + max_acceleration: 3.75 panda_joint6: has_velocity_limits: true - max_velocity: 3 + max_velocity: 2.6100 + has_acceleration_limits: true + max_acceleration: 5 + panda_joint7: + has_velocity_limits: true + max_velocity: 2.6100 + has_acceleration_limits: true + max_acceleration: 5 + panda_finger_joint1: + has_velocity_limits: true + max_velocity: 0.1 has_acceleration_limits: false max_acceleration: 0 - panda_joint7: + panda_finger_joint2: has_velocity_limits: true - max_velocity: 3 + max_velocity: 0.1 has_acceleration_limits: false - max_acceleration: 0 \ No newline at end of file + max_acceleration: 0 diff --git a/config/ompl_planning.yaml b/config/ompl_planning.yaml index 73e38ff53f9993895e4e617f2bd3d8b7e2ef3dcc..491e82914e6283b5366cb293ec7bbcd003c1c341 100644 --- a/config/ompl_planning.yaml +++ b/config/ompl_planning.yaml @@ -149,6 +149,32 @@ panda_arm: - SPARSkConfigDefault - SPARStwokConfigDefault - TrajOptDefault +panda_arm_hand: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + - TrajOptDefault hand: planner_configs: - SBLkConfigDefault diff --git a/config/panda_arm.srdf.xacro b/config/panda_arm.srdf.xacro new file mode 100644 index 0000000000000000000000000000000000000000..76b4c9ee266915df3be1c8c4f3fd48a8972b6144 --- /dev/null +++ b/config/panda_arm.srdf.xacro @@ -0,0 +1,9 @@ +<?xml version='1.0' encoding='utf-8'?> +<!--This does not replace URDF, and is not an extension of URDF. + This is a format for representing semantic information about the robot structure. + A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined +--> +<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda"> + <xacro:include filename="$(find panda_moveit_config)/config/panda_arm.xacro" /> + <xacro:panda_arm /> +</robot> diff --git a/config/panda.srdf b/config/panda_arm.xacro similarity index 55% rename from config/panda.srdf rename to config/panda_arm.xacro index d655b90ebc3d86eb20f509a0368695478e4bd6be..9decba818491036a29b8cca2842c1d1c94b64158 100644 --- a/config/panda.srdf +++ b/config/panda_arm.xacro @@ -1,57 +1,46 @@ <?xml version="1.0" ?> -<!--This does not replace URDF, and is not an extension of URDF. - This is a format for representing semantic information about the robot structure. - A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined ---> -<robot name="panda"> +<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda"> + <xacro:macro name="panda_arm"> <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc--> <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included--> <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included--> <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> <group name="panda_arm"> - <joint name="virtual_joint" /> - <joint name="panda_joint1" /> - <joint name="panda_joint2" /> - <joint name="panda_joint3" /> - <joint name="panda_joint4" /> - <joint name="panda_joint5" /> - <joint name="panda_joint6" /> - <joint name="panda_joint7" /> - <joint name="panda_joint8" /> - </group> - <group name="hand"> - <link name="panda_hand" /> - <link name="panda_leftfinger" /> - <link name="panda_rightfinger" /> + <link name="panda_link0" /> + <link name="panda_link1" /> + <link name="panda_link2" /> + <link name="panda_link3" /> + <link name="panda_link4" /> + <link name="panda_link5" /> + <link name="panda_link6" /> + <link name="panda_link7" /> + <link name="panda_link8" /> + <joint name="virtual_joint" /> + <joint name="panda_joint1" /> + <joint name="panda_joint2" /> + <joint name="panda_joint3" /> + <joint name="panda_joint4" /> + <joint name="panda_joint5" /> + <joint name="panda_joint6" /> + <joint name="panda_joint7" /> + <joint name="panda_joint8" /> + <chain base_link="panda_link0" tip_link="panda_link8" /> </group> <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> - <group_state name="home" group="panda_arm"> - <joint name="panda_joint1" value="0" /> - <joint name="panda_joint2" value="0" /> - <joint name="panda_joint3" value="0" /> - <joint name="panda_joint4" value="0" /> - <joint name="panda_joint5" value="0" /> - <joint name="panda_joint6" value="3.1416" /> - <joint name="panda_joint7" value="1.5708" /> + <group_state name="ready" group="panda_arm"> + <joint name="panda_joint1" value="0" /> + <joint name="panda_joint2" value="-0.785" /> + <joint name="panda_joint3" value="0" /> + <joint name="panda_joint4" value="-2.356" /> + <joint name="panda_joint5" value="0" /> + <joint name="panda_joint6" value="1.571" /> + <joint name="panda_joint7" value="0.785" /> </group_state> <!--END EFFECTOR: Purpose: Represent information about an end effector.--> - <end_effector name="eef" parent_link="panda_link8" group="hand" /> <!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)--> <virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="panda_link0" /> <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> - <disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent" /> - <disable_collisions link1="panda_hand" link2="panda_link3" reason="Never" /> - <disable_collisions link1="panda_hand" link2="panda_link4" reason="Never" /> - <disable_collisions link1="panda_hand" link2="panda_link5" reason="Default" /> - <disable_collisions link1="panda_hand" link2="panda_link6" reason="Never" /> - <disable_collisions link1="panda_hand" link2="panda_link7" reason="Adjacent" /> - <disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent" /> - <disable_collisions link1="panda_leftfinger" link2="panda_link3" reason="Never" /> - <disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never" /> - <disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never" /> - <disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never" /> - <disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default" /> <disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent" /> <disable_collisions link1="panda_link0" link2="panda_link2" reason="Never" /> <disable_collisions link1="panda_link0" link2="panda_link3" reason="Never" /> @@ -66,14 +55,11 @@ <disable_collisions link1="panda_link3" link2="panda_link5" reason="Never" /> <disable_collisions link1="panda_link3" link2="panda_link6" reason="Never" /> <disable_collisions link1="panda_link3" link2="panda_link7" reason="Never" /> - <disable_collisions link1="panda_link3" link2="panda_rightfinger" reason="Never" /> <disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent" /> <disable_collisions link1="panda_link4" link2="panda_link6" reason="Never" /> <disable_collisions link1="panda_link4" link2="panda_link7" reason="Never" /> - <disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never" /> <disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent" /> <disable_collisions link1="panda_link5" link2="panda_link7" reason="Default" /> <disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent" /> - <disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never" /> - <disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never" /> + </xacro:macro> </robot> diff --git a/config/panda_arm_hand.srdf.xacro b/config/panda_arm_hand.srdf.xacro new file mode 100644 index 0000000000000000000000000000000000000000..df3985bbd1a3ca0d4aaf23740733123b02188a88 --- /dev/null +++ b/config/panda_arm_hand.srdf.xacro @@ -0,0 +1,46 @@ +<?xml version='1.0' encoding='utf-8'?> +<!--This does not replace URDF, and is not an extension of URDF. + This is a format for representing semantic information about the robot structure. + A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined +--> +<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda"> + <xacro:include filename="$(find panda_moveit_config)/config/panda_arm.xacro" /> + <xacro:include filename="$(find panda_moveit_config)/config/hand.xacro" /> + <xacro:panda_arm /> + <xacro:hand /> + <!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc--> + <!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included--> + <!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included--> + <!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group--> + <!--SUBGROUPS: Groups can also be formed by referencing to already defined group names--> + <group name="panda_arm_hand"> + <group name="panda_arm" /> + <group name="hand" /> + </group> + <!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'--> + <group_state name="ready" group="panda_arm_hand"> + <joint name="panda_joint1" value="0" /> + <joint name="panda_joint2" value="-0.785" /> + <joint name="panda_joint3" value="0" /> + <joint name="panda_joint4" value="-2.356" /> + <joint name="panda_joint5" value="0" /> + <joint name="panda_joint6" value="1.571" /> + <joint name="panda_joint7" value="0.785" /> + </group_state> + <!--END EFFECTOR: Purpose: Represent information about an end effector.--> + <end_effector name="hand" parent_link="panda_hand" group="hand" parent_group="panda_arm_hand" /> + <!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. --> + <disable_collisions link1="panda_hand" link2="panda_link3" reason="Never" /> + <disable_collisions link1="panda_hand" link2="panda_link4" reason="Never" /> + <disable_collisions link1="panda_hand" link2="panda_link5" reason="Default" /> + <disable_collisions link1="panda_hand" link2="panda_link6" reason="Never" /> + <disable_collisions link1="panda_hand" link2="panda_link7" reason="Adjacent" /> + <disable_collisions link1="panda_leftfinger" link2="panda_link3" reason="Never" /> + <disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never" /> + <disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never" /> + <disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never" /> + <disable_collisions link1="panda_link3" link2="panda_rightfinger" reason="Never" /> + <disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never" /> + <disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never" /> + <disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never" /> +</robot> diff --git a/config/panda_controllers.yaml b/config/panda_controllers.yaml new file mode 100644 index 0000000000000000000000000000000000000000..e47d6f20329cffdf9e2b331fe0638f3cfa6c81e3 --- /dev/null +++ b/config/panda_controllers.yaml @@ -0,0 +1,13 @@ + controller_list: + - name: position_joint_trajectory_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: true + joints: + - panda_joint1 + - panda_joint2 + - panda_joint3 + - panda_joint4 + - panda_joint5 + - panda_joint6 + - panda_joint7 diff --git a/config/controllers.yaml b/config/panda_gripper_controllers.yaml similarity index 84% rename from config/controllers.yaml rename to config/panda_gripper_controllers.yaml index 610b0af83a721eaed4afaa59ccc8b175f8313499..76aa3ecd20b53f8a9d43744037edd6db9400eda8 100644 --- a/config/controllers.yaml +++ b/config/panda_gripper_controllers.yaml @@ -1,5 +1,5 @@ controller_list: - - name: panda_arm_controller + - name: position_joint_trajectory_controller action_ns: follow_joint_trajectory type: FollowJointTrajectory default: true @@ -11,7 +11,7 @@ - panda_joint5 - panda_joint6 - panda_joint7 - - name: hand_controller + - name: franka_gripper action_ns: gripper_action type: GripperCommand default: true diff --git a/launch/move_group.launch b/launch/move_group.launch index d2c63b56753c18f2902fe422eb4cf2508aabc434..ccc7150bd534e507a1207d47da61141323fbba0f 100644 --- a/launch/move_group.launch +++ b/launch/move_group.launch @@ -1,6 +1,10 @@ <launch> - <include file="$(find panda_moveit_config)/launch/planning_context.launch" /> + <arg name="load_gripper" default="true" /> + + <include file="$(find panda_moveit_config)/launch/planning_context.launch"> + <arg name="load_gripper" value="$(arg load_gripper)" /> + </include> <arg name="planner" default="ompl" /> @@ -30,7 +34,8 @@ <!-- Trajectory Execution Functionality --> <include ns="move_group" file="$(find panda_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)"> <arg name="moveit_manage_controllers" value="true" /> - <arg name="moveit_controller_manager" value="panda" unless="$(arg fake_execution)"/> + <arg name="moveit_controller_manager" value="panda" if="$(eval not arg('fake_execution') and not arg('load_gripper'))"/> + <arg name="moveit_controller_manager" value="panda_gripper" if="$(eval not arg('fake_execution') and arg('load_gripper'))"/> <arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/> </include> @@ -69,6 +74,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> diff --git a/launch/panda_control_moveit_rviz.launch b/launch/panda_control_moveit_rviz.launch new file mode 100644 index 0000000000000000000000000000000000000000..748f260367162031004d78a3b14e2b57432860dd --- /dev/null +++ b/launch/panda_control_moveit_rviz.launch @@ -0,0 +1,17 @@ +<?xml version="1.0" ?> +<launch> + <arg name="robot_ip" /> + <arg name="load_gripper" default="true" /> + <arg name="launch_rviz" default="true" /> + + <include file="$(find franka_control)/launch/franka_control.launch" > + <arg name="robot_ip" value="$(arg robot_ip)" /> + <arg name="load_gripper" value="$(arg load_gripper)" /> + </include> + + <include file="$(find panda_moveit_config)/launch/panda_moveit.launch"> + <arg name="load_gripper" value="$(arg load_gripper)" /> + </include> + + <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch" if="$(arg launch_rviz)" /> +</launch> diff --git a/launch/panda_gripper_moveit_controller_manager.launch.xml b/launch/panda_gripper_moveit_controller_manager.launch.xml new file mode 100644 index 0000000000000000000000000000000000000000..27ffcea86742d595d36a73aeb7e5ced29be1414b --- /dev/null +++ b/launch/panda_gripper_moveit_controller_manager.launch.xml @@ -0,0 +1,7 @@ + <launch> + <!-- Set the param that trajectory_execution_manager needs to find the controller plugin --> + <arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" /> + <param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/> + <!-- load controller_list --> + <rosparam file="$(find panda_moveit_config)/config/panda_gripper_controllers.yaml"/> + </launch> diff --git a/launch/panda_moveit.launch b/launch/panda_moveit.launch new file mode 100644 index 0000000000000000000000000000000000000000..8559413cc2ad49c7d4deec9f2d219794fdbd3dca --- /dev/null +++ b/launch/panda_moveit.launch @@ -0,0 +1,10 @@ +<?xml version="1.0" ?> +<launch> + <arg name="load_gripper" default="true" /> + + <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="position_joint_trajectory_controller"/> + + <include file="$(find panda_moveit_config)/launch/move_group.launch"> + <arg name="load_gripper" value="$(arg load_gripper)" /> + </include> +</launch> diff --git a/launch/panda_moveit_controller_manager.launch.xml b/launch/panda_moveit_controller_manager.launch.xml index ffbf1a2719911a1f4c8d512437da8c3ce94cb60d..ea4c0ada949cde1cf1f911a2449d4ab0f5955902 100644 --- a/launch/panda_moveit_controller_manager.launch.xml +++ b/launch/panda_moveit_controller_manager.launch.xml @@ -3,5 +3,5 @@ <arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" /> <param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/> <!-- load controller_list --> - <rosparam file="$(find panda_moveit_config)/config/controllers.yaml"/> + <rosparam file="$(find panda_moveit_config)/config/panda_controllers.yaml"/> </launch> diff --git a/launch/planning_context.launch b/launch/planning_context.launch index 29c91204a94a767be469ef06ebf93c84e7a9c88f..e96133948929741d8d126e5942e648f3969029dd 100644 --- a/launch/planning_context.launch +++ b/launch/planning_context.launch @@ -1,4 +1,6 @@ <launch> + <arg name="load_gripper" default="true" /> + <!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior --> <arg name="load_robot_description" default="false"/> @@ -6,10 +8,12 @@ <arg name="robot_description" default="robot_description"/> <!-- Load universal robot description format (URDF) --> - <param if="$(arg load_robot_description)" 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 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'"/> <!-- The semantic description that corresponds to the URDF --> - <param name="$(arg robot_description)_semantic" textfile="$(find panda_moveit_config)/config/panda.srdf" /> + <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)" /> <!-- Load updated joint limits (override information from URDF) --> <group ns="$(arg robot_description)_planning"> diff --git a/package.xml b/package.xml index a364a429fd16995e56c2c238d3c4089368a99b01..4b8056270b73741807d29f269e4ce9b9b0b74036 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ <package> <name>panda_moveit_config</name> - <version>0.3.0</version> + <version>0.7.0</version> <description> An automatically generated package with all the configuration and launch files for using the panda with the MoveIt! Motion Planning Framework </description>