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

Gazebo simulation #60

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
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
369 changes: 369 additions & 0 deletions niryo_one_description/urdf/v2/gazebo_niryo_one.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,369 @@
<?xml version="1.0"?>

<!--
niryo_one.urdf.xacro
Copyright (C) 2019 Niryo
All rights reserved.

This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.

This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.

You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
-->

<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="niryo_one">

<!-- Properties -->

<xacro:property name="distance_origin_shoulder_z" value="0.103" />
<xacro:property name="distance_shoulder_arm_z" value="0.080" />
<xacro:property name="distance_arm_elbow_x" value="0.210" />
<xacro:property name="distance_arm_elbow_y" value="0.0" />
<xacro:property name="distance_elbow_forearm_x" value="0.0415" />
<xacro:property name="distance_elbow_forearm_y" value="0.030" />
<xacro:property name="distance_forearm_wrist_z" value="0.180" />
<xacro:property name="distance_wrist_hand_x" value="0.0164" />
<xacro:property name="distance_wrist_hand_y" value="-0.0055" />
<xacro:property name="distance_hand_tool" value="0.0073" />

<xacro:property name="PI" value="3.14159265359" />

<xacro:property name="limit_low_shoulder_rotation" value="-3.05433" />
<xacro:property name="limit_up_shoulder_rotation" value="3.05433" />
<xacro:property name="limit_low_arm_rotation" value="-1.91986" />
<xacro:property name="limit_up_arm_rotation" value="0.640187" />
<xacro:property name="limit_low_elbow_rotation" value="-1.397485" />
<xacro:property name="limit_up_elbow_rotation" value="${PI/2}" />
<xacro:property name="limit_low_forearm_rotation" value="-3.05433" />
<xacro:property name="limit_up_forearm_rotation" value="3.05433" />
<xacro:property name="limit_low_wrist_rotation" value="-1.74533" />
<xacro:property name="limit_up_wrist_rotation" value="1.91986" />
<xacro:property name="limit_low_hand_rotation" value="-2.57436" />
<xacro:property name="limit_up_hand_rotation" value="2.57436" />

<!-- Links -->

<link name="world" />

<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/collada/base_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/stl/base_link.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${distance_origin_shoulder_z / 2}" rpy="0 0 0" />
<mass value="1.2" />
<inertia ixx="0.0015" ixy="0.0" ixz="0.0" iyy="0.0015" iyz="0.0" izz="0.0015"/>
</inertial>
</link>

<link name="shoulder_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/collada/shoulder_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/stl/shoulder_link.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${distance_shoulder_arm_z / 2}" rpy="0 0 0" />
<mass value="0.8" />
<inertia ixx="0.0015" ixy="0.0" ixz="0.0" iyy="0.0015" iyz="0.0" izz="0.0015"/>
</inertial>
</link>

<link name="arm_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/collada/arm_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/stl/arm_link.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="${distance_arm_elbow_x / 2} -0.1 0" rpy="0 0 0" />
<mass value="0.4" />
<inertia ixx="0.0015" ixy="0.0" ixz="0.0" iyy="0.0015" iyz="0.0" izz="0.0015"/>
</inertial>
</link>

<link name="elbow_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/collada/elbow_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/stl/elbow_link.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="${distance_elbow_forearm_x / 2} ${distance_elbow_forearm_y / 2} 0" rpy="0 0 0" />
<mass value="0.3" />
<inertia ixx="0.0015" ixy="0.0" ixz="0.0" iyy="0.0015" iyz="0.0" izz="0.0015"/>
</inertial>
</link>

<link name="forearm_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/collada/forearm_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/stl/forearm_link.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${distance_forearm_wrist_z / 2}" rpy="0 0 0" />
<mass value="0.3" />
<inertia ixx="0.0015" ixy="0.0" ixz="0.0" iyy="0.0015" iyz="0.0" izz="0.0015"/>
</inertial>
</link>

<link name="wrist_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/collada/wrist_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/stl/wrist_link.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="${distance_wrist_hand_x / 2} ${distance_wrist_hand_y / 2} 0" rpy="0 0 0" />
<mass value="0.15" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
</link>

<link name="hand_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/collada/hand_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://niryo_one_description/meshes/v2/stl/hand_link.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="0 0 ${distance_hand_tool / 2}" rpy="0 0 0" />
<mass value="0.05" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
</link>

<link name="tool_link">
</link>

<!--Joints -->

<joint name="joint_world" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>

<joint name="joint_1" type="revolute">
<parent link="base_link" />
<child link="shoulder_link" />
<origin xyz="0 0 ${distance_origin_shoulder_z}" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit effort="100.0" velocity="3.0" lower="${limit_low_shoulder_rotation}" upper="${limit_up_shoulder_rotation}" />
<dynamics damping="0.1" friction="0.0" />
</joint>

<joint name="joint_2" type="revolute">
<parent link="shoulder_link" />
<child link="arm_link" />
<origin xyz="0 0 ${distance_shoulder_arm_z}" rpy="${PI/2} ${-PI/2} 0" />
<limit effort="100.0" velocity="3.0" lower="${limit_low_arm_rotation}" upper="${limit_up_arm_rotation}" />
<axis xyz="0 0 1" />
<dynamics damping="0.1" friction="0.0" />
</joint>

<joint name="joint_3" type="revolute">
<parent link="arm_link" />
<child link="elbow_link" />
<origin xyz="${distance_arm_elbow_x} ${distance_arm_elbow_y} 0" rpy="0 0 ${-PI/2}" />
<limit effort="100.0" velocity="3.0" lower="${limit_low_elbow_rotation}" upper="${limit_up_elbow_rotation}" />
<axis xyz="0 0 1" />
<dynamics damping="0.1" friction="0.0" />
</joint>

<joint name="joint_4" type="revolute">
<parent link="elbow_link" />
<child link="forearm_link" />
<origin xyz="${distance_elbow_forearm_x} ${distance_elbow_forearm_y} 0" rpy="0 ${PI/2} 0" />
<limit effort="100.0" velocity="3.0" lower="${limit_low_forearm_rotation}" upper="${limit_up_forearm_rotation}" />
<axis xyz="0 0 1" />
<dynamics damping="0.1" friction="0.0" />
</joint>

<joint name="joint_5" type="revolute">
<parent link="forearm_link" />
<child link="wrist_link" />
<origin xyz="0 0 ${distance_forearm_wrist_z}" rpy="0 ${-PI/2} 0" />
<limit effort="100.0" velocity="3.0" lower="${limit_low_wrist_rotation}" upper="${limit_up_wrist_rotation}" />
<axis xyz="0 0 1" />
<dynamics damping="0.1" friction="0.0" />
</joint>

<joint name="joint_6" type="revolute">
<parent link="wrist_link" />
<child link="hand_link" />
<origin xyz="${distance_wrist_hand_x} ${distance_wrist_hand_y} 0" rpy="0 ${PI/2} 0" />
<limit effort="100.0" velocity="3.0" lower="${limit_low_hand_rotation}" upper="${limit_up_hand_rotation}" />
<axis xyz="0 0 1" />
<dynamics damping="0.1" friction="0.0" />
</joint>

<joint name="hand_tool_joint" type="fixed">
<parent link="hand_link" />
<child link="tool_link" />
<origin xyz="0 0 ${distance_hand_tool}" rpy="${-PI/2} ${-PI/2} 0" />
</joint>

<transmission name="transmission_1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<transmission name="transmission_2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_2">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_2">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<transmission name="transmission_3">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_3">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_3">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<transmission name="transmission_4">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_4">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_4">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<transmission name="transmission_5">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_5">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_5">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<transmission name="transmission_6">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_6">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor_6">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
</plugin>
</gazebo>

<gazebo reference="base_link">
<selfCollide>true</selfCollide>
</gazebo>

<gazebo reference="shoulder_link">
<selfCollide>true</selfCollide>
</gazebo>

<gazebo reference="arm_link">
<selfCollide>true</selfCollide>
</gazebo>

<gazebo reference="elbow_link">
<selfCollide>true</selfCollide>
</gazebo>

<gazebo reference="forearm_link">
<selfCollide>true</selfCollide>
</gazebo>

<gazebo reference="wrist_link">
<selfCollide>true</selfCollide>
</gazebo>

<gazebo reference="hand_link">
<selfCollide>true</selfCollide>
</gazebo>

<gazebo reference="tool_link">
</gazebo>

</robot>
6 changes: 6 additions & 0 deletions niryo_one_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(niryo_one_gazebo)

find_package(catkin REQUIRED)

catkin_package()
Loading