Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Make Panda robot Gazebo compatible #126

Closed
wants to merge 13 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
40 changes: 40 additions & 0 deletions franka_control/config/panda_gazebo_control.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50

position_joint_trajectory_controller:
type: effort_controllers/JointTrajectoryController
joints:
- panda_joint1
- panda_joint2
- panda_joint3
- panda_joint4
- panda_joint5
- panda_joint6
- panda_joint7

gains:
panda_joint1: { p: 12000, d: 50, i: 0.0, i_clamp: 10000 }
panda_joint2: { p: 30000, d: 100, i: 0.02, i_clamp: 10000 }
panda_joint3: { p: 18000, d: 50, i: 0.01, i_clamp: 1 }
panda_joint4: { p: 18000, d: 70, i: 0.01, i_clamp: 10000 }
panda_joint5: { p: 12000, d: 70, i: 0.01, i_clamp: 1 }
panda_joint6: { p: 7000, d: 50, i: 0.01, i_clamp: 1 }
panda_joint7: { p: 2000, d: 20, i: 0.0, i_clamp: 1 }

constraints:
goal_time: 2.0

state_publish_rate: 25

franka_gripper:
type: effort_controllers/JointTrajectoryController
joints:
- panda_finger_joint1
- panda_finger_joint2

gains:
panda_finger_joint1: { p: 5, d: 3.0, i: 0, i_clamp: 1 }
panda_finger_joint2: { p: 5, d: 1.0, i: 0, i_clamp: 1 }

state_publish_rate: 25
Binary file added franka_description/meshes/collision/finger.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/hand.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/link0.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/link1.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/link2.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/link3.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/link4.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/link5.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/link6.stl
Binary file not shown.
Binary file added franka_description/meshes/collision/link7.stl
Binary file not shown.
16 changes: 15 additions & 1 deletion franka_description/robots/hand.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,19 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
<xacro:arg name="use_cylinder_collision_model" default="true"/>
<xacro:arg name="use_gazebo_sim" default="false"/>

<xacro:include filename="hand.xacro"/>
<xacro:hand ns="panda" safety_distance="0.03"/>

<xacro:if value="$(arg use_gazebo_sim)">
<xacro:include filename="$(find franka_description)/robots/panda.gazebo.xacro"/>
<xacro:include filename="$(find franka_description)/robots/panda.control.xacro"/>
</xacro:if>
<xacro:hand ns="panda" rpy="0 0 ${-pi/4}" connected_to="panda_link8" safety_distance="0.03"
use_cylinder_collision_model="$(arg use_cylinder_collision_model)"/>

<xacro:if value="$(arg use_gazebo_sim)">
<xacro:hand_gazebo arm_id="$(arg arm_id)"/>
<xacro:hand_control arm_id="$(arg arm_id)"/>
</xacro:if>
</robot>
125 changes: 87 additions & 38 deletions franka_description/robots/hand.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
<xacro:arg name="use_gazebo_sim" default="false"/>
<!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
<xacro:macro name="hand" params="connected_to:='' ns:='' rpy:='0 0 0' xyz:='0 0 0' safety_distance:=0">
<xacro:macro name="hand" params="connected_to:='' ns:='' rpy:='0 0 0' xyz:='0 0 0' safety_distance:=0
use_cylinder_collision_model:='true'">
<xacro:unless value="${connected_to == ''}">
<joint name="${ns}_hand_joint" type="fixed">
<parent link="${connected_to}"/>
Expand All @@ -15,49 +17,79 @@
<mesh filename="package://franka_description/meshes/visual/hand.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.04" rpy="0 ${pi/2} ${pi/2}"/>
<geometry>
<cylinder radius="${0.04+safety_distance}" length="0.1" />
</geometry>
</collision>
<collision>
<origin xyz="0 -0.05 0.04" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.04+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0.05 0.04" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.04+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0 0.1" rpy="0 ${pi/2} ${pi/2}"/>
<geometry>
<cylinder radius="${0.02+safety_distance}" length="0.1" />
</geometry>
</collision>
<collision>
<origin xyz="0 -0.05 0.1" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0.05 0.1" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
</geometry>
</collision>
<xacro:if value="${use_cylinder_collision_model}">
<collision>
<origin xyz="0 0 0.04" rpy="0 ${pi/2} ${pi/2}"/>
<geometry>
<cylinder radius="${0.04+safety_distance}" length="0.1" />
</geometry>
</collision>
<collision>
<origin xyz="0 -0.05 0.04" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.04+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0.05 0.04" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.04+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0 0.1" rpy="0 ${pi/2} ${pi/2}"/>
<geometry>
<cylinder radius="${0.02+safety_distance}" length="0.1" />
</geometry>
</collision>
<collision>
<origin xyz="0 -0.05 0.1" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0.05 0.1" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
</geometry>
</collision>
</xacro:if>
<xacro:unless value="${use_cylinder_collision_model}">
<collision>
<geometry>
<mesh filename="package://franka_description/meshes/collision/hand.stl"/>
</geometry>
</collision>
</xacro:unless>
<xacro:if value="$(arg use_gazebo_sim)">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.68" />
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
</xacro:if>
</link>
<link name="${ns}_leftfinger">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<xacro:unless value="${use_cylinder_collision_model}">
<collision>
<geometry>
<mesh filename="package://franka_description/meshes/collision/finger.stl"/>
</geometry>
</collision>
</xacro:unless>
<xacro:if value="$(arg use_gazebo_sim)">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="0.01" />
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
</xacro:if>
</link>
<link name="${ns}_rightfinger">
<visual>
Expand All @@ -66,6 +98,21 @@
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<xacro:unless value="${use_cylinder_collision_model}">
<collision>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/finger.stl"/>
</geometry>
</collision>
</xacro:unless>
<xacro:if value="$(arg use_gazebo_sim)">
<inertial>
<origin xyz="0 0 0" rpy="0 0 ${pi}" />
<mass value="0.01" />
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
</inertial>
</xacro:if>
</link>
<joint name="${ns}_finger_joint1" type="prismatic">
<parent link="${ns}_hand"/>
Expand All @@ -80,7 +127,9 @@
<origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 -1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
<mimic joint="${ns}_finger_joint1" />
<xacro:unless value="$(arg use_gazebo_sim)">
<mimic joint="${ns}_finger_joint1" />
</xacro:unless>
</joint>
</xacro:macro>
</robot>
28 changes: 28 additions & 0 deletions franka_description/robots/panda.control.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="joint_control" params="transmission joint motor">
<transmission name="${transmission}">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint}">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="${motor}">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<xacro:macro name="arm_control" params="arm_id">
<xacro:joint_control transmission="${arm_id}_tran_1" joint="${arm_id}_joint1" motor="${arm_id}_motor_1"/>
<xacro:joint_control transmission="${arm_id}_tran_2" joint="${arm_id}_joint2" motor="${arm_id}_motor_2"/>
<xacro:joint_control transmission="${arm_id}_tran_3" joint="${arm_id}_joint3" motor="${arm_id}_motor_3"/>
<xacro:joint_control transmission="${arm_id}_tran_4" joint="${arm_id}_joint4" motor="${arm_id}_motor_4"/>
<xacro:joint_control transmission="${arm_id}_tran_5" joint="${arm_id}_joint5" motor="${arm_id}_motor_5"/>
<xacro:joint_control transmission="${arm_id}_tran_6" joint="${arm_id}_joint6" motor="${arm_id}_motor_6"/>
<xacro:joint_control transmission="${arm_id}_tran_7" joint="${arm_id}_joint7" motor="${arm_id}_motor_7"/>
</xacro:macro>
<xacro:macro name="hand_control" params="arm_id">
<xacro:joint_control transmission="${arm_id}_leftfinger" joint="${arm_id}_finger_joint1" motor="${arm_id}_finger_joint1"/>
<xacro:joint_control transmission="${arm_id}_rightfinger" joint="${arm_id}_finger_joint2" motor="${arm_id}_finger_joint2"/>
</xacro:macro>
</robot>
33 changes: 33 additions & 0 deletions franka_description/robots/panda.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="arm_gazebo" params="arm_id">
<xacro:macro name="arm_material" params="link">
<gazebo reference="${link}">
<material>Gazebo/White</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
</xacro:macro>
<xacro:arm_material link="${arm_id}_link0"/>
<xacro:arm_material link="${arm_id}_link1"/>
<xacro:arm_material link="${arm_id}_link2"/>
<xacro:arm_material link="${arm_id}_link3"/>
<xacro:arm_material link="${arm_id}_link4"/>
<xacro:arm_material link="${arm_id}_link5"/>
<xacro:arm_material link="${arm_id}_link6"/>
<xacro:arm_material link="${arm_id}_link7"/>
<xacro:arm_material link="${arm_id}_link8"/>
</xacro:macro>
<xacro:macro name="hand_gazebo" params="arm_id">
<xacro:macro name="hand_material" params="link">
<gazebo reference="${link}">
<material>Gazebo/Grey</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
</xacro:macro>
<xacro:hand_material link="${arm_id}_hand"/>
<xacro:hand_material link="${arm_id}_rightfinger"/>
<xacro:hand_material link="${arm_id}_leftfinger"/>
</xacro:macro>
</robot>
21 changes: 20 additions & 1 deletion franka_description/robots/panda_arm.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,24 @@
<?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"/>
<xacro:arg name="use_cylinder_collision_model" default="true"/>
<xacro:arg name="use_gazebo_sim" default="false"/>

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

<xacro:if value="$(arg use_gazebo_sim)">
<xacro:include filename="$(find franka_description)/robots/panda.gazebo.xacro"/>
<xacro:include filename="$(find franka_description)/robots/panda.control.xacro"/>
</xacro:if>
<link name="world"/>
<xacro:panda_arm xyz="0 0 0" rpy="0 0 0" connected_to="world" arm_id="$(arg arm_id)"
safety_distance="0.03" use_cylinder_collision_model="$(arg use_cylinder_collision_model)"/>

<xacro:if value="$(arg use_gazebo_sim)">
<xacro:arm_gazebo arm_id="$(arg arm_id)"/>
<xacro:arm_control arm_id="$(arg arm_id)"/>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"/>
</gazebo>
</xacro:if>
</robot>
Loading