Skip to content

Commit

Permalink
Adjust to upstream change (frankaemika/franka_ros#216)
Browse files Browse the repository at this point in the history
  • Loading branch information
130s committed Jun 10, 2023
1 parent 1cd754c commit 646722b
Showing 1 changed file with 18 additions and 0 deletions.
18 changes: 18 additions & 0 deletions panda_description/urdf/panda_arm.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:arg name="arm_id" default="panda"/> <!-- Name of this panda -->
<xacro:arg name="hand" default="false"/> <!-- Should a franka_gripper be mounted at the flange?" -->
<xacro:arg name="robot_ip" default=""/> <!-- IP address or hostname of the robot" -->
<xacro:arg name="use_fake_hardware" default="false"/>
<xacro:arg name="fake_sensor_commands" default="false"/>

<xacro:include filename="$(find franka_description)/robots/panda_arm.xacro"/>
<xacro:panda_arm arm_id="$(arg arm_id)" safety_distance="0.03"/>

<xacro:if value="$(arg hand)">
<xacro:include filename="$(find franka_description)/robots/hand.xacro"/>
<xacro:hand ns="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" safety_distance="0.03"/>
</xacro:if>
<xacro:include filename="$(find franka_description)/robots/panda_arm.ros2_control.xacro"/>
<xacro:panda_arm_ros2_control ns="$(arg arm_id)" robot_ip="$(arg robot_ip)" use_fake_hardware="$(arg use_fake_hardware)" fake_sensor_commands="$(arg fake_sensor_commands)"/>
</robot>

0 comments on commit 646722b

Please sign in to comment.