Skip to content
Snippets Groups Projects
Unverified Commit e5259bcf authored by Erdal Pekel's avatar Erdal Pekel Committed by GitHub
Browse files

Merge pull request #1 from marcoesposito1988/simulation

Fix Gazebo simulation for panda_arm (without the gripper/hand)
parents 25e274d3 48642d5e
No related branches found
No related tags found
No related merge requests found
<?xml version="1.0"?> <?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="panda_transmission" params="robot_name"> <xacro:macro name="panda_transmission" params="robot_name load_hand">
<!-- Load Gazebo lib and set the robot namespace --> <!-- Load Gazebo lib and set the robot namespace -->
...@@ -87,6 +87,7 @@ ...@@ -87,6 +87,7 @@
</actuator> </actuator>
</transmission> </transmission>
<xacro:if value="${load_hand}">
<transmission name="${robot_name}_leftfinger"> <transmission name="${robot_name}_leftfinger">
<type>transmission_interface/SimpleTransmission</type> <type>transmission_interface/SimpleTransmission</type>
<joint name="${robot_name}_finger_joint1"> <joint name="${robot_name}_finger_joint1">
...@@ -108,5 +109,6 @@ ...@@ -108,5 +109,6 @@
<mechanicalReduction>1</mechanicalReduction> <mechanicalReduction>1</mechanicalReduction>
</actuator> </actuator>
</transmission> </transmission>
</xacro:if>
</xacro:macro> </xacro:macro>
</robot> </robot>
<?xml version='1.0' encoding='utf-8'?> <?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:include filename="$(find franka_description)/robots/panda_arm.xacro" /> <xacro:include filename="$(find franka_description)/robots/panda_arm.xacro" />
<!-- for simulation -->
<xacro:include filename="$(find franka_description)/robots/panda.gazebo.xacro"/>
<xacro:include filename="panda.transmission.xacro"/>
<!-- end for simulation -->
<xacro:panda_arm /> <xacro:panda_arm />
<!-- for simulation -->
<xacro:arg name="robot_name" default="panda"/>
<xacro:panda_gazebo robot_name="$(arg robot_name)" />
<xacro:panda_transmission robot_name="$(arg robot_name)" load_hand="false" />
<!-- end for simulation -->
</robot> </robot>
...@@ -5,7 +5,7 @@ ...@@ -5,7 +5,7 @@
<!-- for simulation --> <!-- for simulation -->
<xacro:include filename="$(find franka_description)/robots/panda.gazebo.xacro"/> <xacro:include filename="$(find franka_description)/robots/panda.gazebo.xacro"/>
<xacro:include filename="$(find franka_description)/robots/panda.transmission.xacro"/> <xacro:include filename="panda.transmission.xacro"/>
<!-- end for simulation --> <!-- end for simulation -->
<xacro:panda_arm /> <xacro:panda_arm />
...@@ -14,6 +14,6 @@ ...@@ -14,6 +14,6 @@
<!-- for simulation --> <!-- for simulation -->
<xacro:arg name="robot_name" default="panda"/> <xacro:arg name="robot_name" default="panda"/>
<xacro:panda_gazebo robot_name="$(arg robot_name)" /> <xacro:panda_gazebo robot_name="$(arg robot_name)" />
<xacro:panda_transmission robot_name="$(arg robot_name)" /> <xacro:panda_transmission robot_name="$(arg robot_name)" load_hand="true" />
<!-- end for simulation --> <!-- end for simulation -->
</robot> </robot>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment