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

Franka sim #110

Merged
merged 7 commits into from
Oct 12, 2020
Merged
Show file tree
Hide file tree
Changes from 5 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
280 changes: 280 additions & 0 deletions robots/franka/franka.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,280 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /home/joshua/workspaces/franka_cogimon_ws/src/franka_description/robots/panda_arm.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="franka" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="world"/>
<joint name="panda_joint_world" type="fixed">
<parent link="world"/>
<child link="panda_link0"/>
<origin rpy="0 0 0" xyz="0 0 0.01"/>
</joint>
<link name="panda_link0">
<inertial>
<mass value="1.2"/>
<origin rpy="0 0 0" xyz="0 0 0.055"/>
<inertia ixx="0.00229" ixy="0" ixz="0" iyy="0.00216" iyz="0" izz="0.00229"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/link0.dae"
/>
</geometry>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description/meshes/collision/link0.stl"/>
</geometry>
</collision>
</link>
<link name="panda_link1">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0 0.130"/>
<inertia ixx="0.0136666666667" ixy="0" ixz="0" iyy="0.0118666666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/visual/link1.dae"/>
</geometry>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/collision/link1.stl"/>
</geometry>
</collision>
</link>
<joint name="panda_joint1" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.818745" soft_upper_limit="2.818745"/>
<origin rpy="0 0 0" xyz="0 0 0.333"/>
<parent link="panda_link0"/>
<child link="panda_link1"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.5"/>
</joint>
<link name="panda_link2">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 -0.06 0.07"/>
<inertia ixx="0.0136666666667" ixy="0" ixz="0" iyy="0.0118666666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/visual/link2.dae"/>
</geometry>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/collision/link2.stl"/>
</geometry>
</collision>
</link>
<joint name="panda_joint2" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.74097" soft_upper_limit="1.74097"/>
<origin rpy="-1.570796326794897 0 0" xyz="0 0 0"/>
<parent link="panda_link1"/>
<child link="panda_link2"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-1.8326" upper="1.8326" velocity="2.5"/>
</joint>
<link name="panda_link3">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 -0.06 0.130"/>
<inertia ixx="0.0136666666667" ixy="0" ixz="0" iyy="0.0118666666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/visual/link3.dae"/>
</geometry>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/collision/link3.stl"/>
</geometry>
</collision>
</link>
<joint name="panda_joint3" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.818745" soft_upper_limit="2.818745"/>
<origin rpy="1.570796326794897 0 0" xyz="0 -0.316 0"/>
<parent link="panda_link2"/>
<child link="panda_link3"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-2.9671" upper="2.9671" velocity="2.5"/>
</joint>
<link name="panda_link4">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0.06 0.07"/>
<inertia ixx="0.0136666666667" ixy="0" ixz="0" iyy="0.0118666666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/visual/link4.dae"/>
</geometry>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/collision/link4.stl"/>
</geometry>
</collision>
</link>
<joint name="panda_joint4" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.98452" soft_upper_limit="0.082935"/>
<origin rpy="1.570796326794897 0 0" xyz="0.0825 0 0"/>
<parent link="panda_link3"/>
<child link="panda_link4"/>
<axis xyz="0 0 1"/>
<limit effort="87" lower="-3.1416" upper="0.0873" velocity="2.5"/>
</joint>
<link name="panda_link5">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0 0.124"/>
<inertia ixx="0.0126506666667" ixy="0" ixz="0" iyy="0.0108506666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/visual/link5.dae"/>
</geometry>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/collision/link5.stl"/>
</geometry>
</collision>
</link>
<joint name="panda_joint5" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.818745" soft_upper_limit="2.818745"/>
<origin rpy="-1.570796326794897 0 0" xyz="-0.0825 0.384 0"/>
<parent link="panda_link4"/>
<child link="panda_link5"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.9671" upper="2.9671" velocity="3"/>
</joint>
<link name="panda_link6">
<inertial>
<mass value="1.0"/>
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<inertia ixx="0.00260416666667" ixy="0" ixz="0" iyy="0.00260416666667" iyz="0" izz="0.00260416666667"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/visual/link6.dae"/>
</geometry>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/collision/link6.stl"/>
</geometry>
</collision>
</link>
<joint name="panda_joint6" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.082935" soft_upper_limit="3.631185"/>
<origin rpy="1.570796326794897 0 0" xyz="0 0 0"/>
<parent link="panda_link5"/>
<child link="panda_link6"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-0.0873" upper="3.8223" velocity="3"/>
</joint>
<link name="panda_link7">
<inertial>
<mass value="0.2"/>
<origin xyz="0 0 0"/>
<inertia ixx="6.66666666667e-05" ixy="0" ixz="0" iyy="6.66666666667e-05" iyz="0" izz="0.00012"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/visual/link7.dae"/>
</geometry>
<material name="White">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://franka_description//meshes/collision/link7.stl"/>
</geometry>
</collision>
</link>
<joint name="panda_joint7" type="revolute">
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.818745" soft_upper_limit="2.818745"/>
<origin rpy="1.570796326794897 0 0" xyz="0.088 0 0"/>
<parent link="panda_link6"/>
<child link="panda_link7"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.9671" upper="2.9671" velocity="3"/>
</joint>
<link name="panda_link8">
</link>
<joint name="panda_joint8" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.107"/>
<parent link="panda_link7"/>
<child link="panda_link8"/>
</joint>

<link name="box">
<visual>
<geometry>
<box size="0.02 0.02 0.20"/>
</geometry>
<material name="White"/>
<origin rpy="0 0 0" xyz="0. 0 0.1"/>
<parent link="panda_link8"/>
</visual>
</link>

<joint name="eef_to_box" type="fixed">
<parent link="panda_link8"/>
<child link="box"/>
<origin xyz="0.0 0.0 0.0"/>
</joint>

<gazebo reference="panda_link0"/>
<gazebo reference="panda_link1"/>
<gazebo reference="panda_link2"/>
<gazebo reference="panda_link3"/>
<gazebo reference="panda_link4"/>
<gazebo reference="panda_link5"/>
<gazebo reference="panda_link6"/>
<gazebo reference="panda_link7"/>
<gazebo reference="panda_link8"/>
</robot>
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
176 changes: 176 additions & 0 deletions robots/franka/franka_description/meshes/visual/finger.dae

Large diffs are not rendered by default.

Loading