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

Panda in Gazebo + MoveIt! motion planning #52

Closed
wants to merge 8 commits into from
Closed
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
42 changes: 28 additions & 14 deletions franka_description/robots/hand.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
<xacro:macro name="hand" params="connected_to:='' ns:='' rpy:='0 0 0' xyz:='0 0 0' ">
<!-- 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:unless value="${connected_to == ''}">
<joint name="${ns}_hand_joint" type="fixed">
<parent link="${connected_to}"/>
Expand All @@ -19,18 +20,29 @@
<mesh filename="package://franka_description/meshes/collision/hand.stl"/>
</geometry>
</collision>

<!-- for simulation -->
<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>
<!-- end for simulation -->
</link>
<link name="${ns}_leftfinger">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://franka_description/meshes/collision/finger.stl"/>
</geometry>
</collision>

<!-- for simulation -->
<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>
<!-- end for simulation -->
</link>
<link name="${ns}_rightfinger">
<visual>
Expand All @@ -39,13 +51,15 @@
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/finger.stl"/>
</geometry>
</collision>
</link>

<!-- for simulation -->
<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>
<!-- end for simulation -->
</link>
<joint name="${ns}_finger_joint1" type="prismatic">
<parent link="${ns}_hand"/>
<child link="${ns}_leftfinger"/>
Expand All @@ -62,4 +76,4 @@
<mimic joint="${ns}_finger_joint1" />
</joint>
</xacro:macro>
</robot>
</robot>
31 changes: 31 additions & 0 deletions franka_description/robots/panda.control.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="panda_control" params="arm_id load_hand">
<xacro:macro name="arm_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:arm_control transmission="${arm_id}_tran_1" joint="${arm_id}_joint1" motor="${arm_id}_motor_1"/>
<xacro:arm_control transmission="${arm_id}_tran_2" joint="${arm_id}_joint2" motor="${arm_id}_motor_2"/>
<xacro:arm_control transmission="${arm_id}_tran_3" joint="${arm_id}_joint3" motor="${arm_id}_motor_3"/>
<xacro:arm_control transmission="${arm_id}_tran_4" joint="${arm_id}_joint4" motor="${arm_id}_motor_4"/>
<xacro:arm_control transmission="${arm_id}_tran_5" joint="${arm_id}_joint5" motor="${arm_id}_motor_5"/>
<xacro:arm_control transmission="${arm_id}_tran_6" joint="${arm_id}_joint6" motor="${arm_id}_motor_6"/>
<xacro:arm_control transmission="${arm_id}_tran_7" joint="${arm_id}_joint7" motor="${arm_id}_motor_7"/>
<xacro:if value="${load_hand}">
<xacro:arm_control transmission="${arm_id}_leftfinger" joint="${arm_id}_finger_joint1" motor="${arm_id}_finger_joint1"/>
<xacro:arm_control transmission="${arm_id}_rightfinger" joint="${arm_id}_finger_joint2" motor="${arm_id}_finger_joint2"/>
</xacro:if>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"/>
</gazebo>
</xacro:macro>
</robot>
31 changes: 31 additions & 0 deletions franka_description/robots/panda.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="panda_gazebo" params="arm_id">
<xacro:macro name="arm_gazebo" params="link">
<gazebo reference="${link}">
<material>Gazebo/White</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
</xacro:macro>
<xacro:macro name="hand_gazebo" params="link">
<gazebo reference="${link}">
<material>Gazebo/Grey</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
</gazebo>
</xacro:macro>
<xacro:arm_gazebo link="${arm_id}_link0"/>
<xacro:arm_gazebo link="${arm_id}_link1"/>
<xacro:arm_gazebo link="${arm_id}_link2"/>
<xacro:arm_gazebo link="${arm_id}_link3"/>
<xacro:arm_gazebo link="${arm_id}_link4"/>
<xacro:arm_gazebo link="${arm_id}_link5"/>
<xacro:arm_gazebo link="${arm_id}_link6"/>
<xacro:hand_gazebo link="${arm_id}_link7"/>
<xacro:hand_gazebo link="${arm_id}_link8"/>
<xacro:hand_gazebo link="${arm_id}_hand"/>
<xacro:hand_gazebo link="${arm_id}_rightfinger"/>
<xacro:hand_gazebo link="${arm_id}_leftfinger"/>
</xacro:macro>
</robot>
4 changes: 2 additions & 2 deletions franka_description/robots/panda_arm.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:include filename="$(find franka_description)/robots/panda_arm.xacro" />
<xacro:panda_arm />
</robot>
<xacro:panda_arm safety_distance="0.03"/>
</robot>
Loading