runtime/rbs_simulation/mujoco_model/current.urdf
2023-07-17 16:41:31 +03:00

517 lines
20 KiB
XML

<?xml version="1.0" encoding="UTF-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from /home/bill-finger/rasms_ws/install/ur_description/share/ur_description/urdf/ur.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="ur">
<!--
Base UR robot series xacro macro.
NOTE this is NOT a URDF. It cannot directly be loaded by consumers
expecting a flattened '.urdf' file. See the top-level '.xacro' for that
(but note that .xacro must still be processed by the xacro command).
This file models the base kinematic chain of a UR robot, which then gets
parameterised by various configuration files to convert it into a UR3(e),
UR5(e), UR10(e) or UR16e.
NOTE the default kinematic parameters (i.e., link lengths, frame locations,
offsets, etc) do not correspond to any particular robot. They are defaults
only. There WILL be non-zero offsets between the Forward Kinematics results
in TF (i.e., robot_state_publisher) and the values reported by the Teach
Pendant.
For accurate (and robot-specific) transforms, the 'kinematics_parameters_file'
parameter MUST point to a .yaml file containing the appropriate values for
the targeted robot.
If using the UniversalRobots/Universal_Robots_ROS_Driver, follow the steps
described in the readme of that repository to extract the kinematic
calibration from the controller and generate the required .yaml file.
Main author of the migration to yaml configs Ludovic Delval.
Contributors to previous versions (in no particular order)
- Denis Stogl
- Lovro Ivanov
- Felix Messmer
- Kelsey Hawkins
- Wim Meeussen
- Shaun Edwards
- Nadia Hammoudeh Garcia
- Dave Hershberger
- G. vd. Hoorn
- Philip Long
- Dave Coleman
- Miguel Prada
- Mathias Luedtke
- Marcel Schnirring
- Felix von Drigalski
- Felix Exner
- Jimmy Da Silva
- Ajit Krisshna N L
- Muhammad Asif Rana
-->
<!--
NOTE the macro defined in this file is NOT part of the public API of this
package. Users CANNOT rely on this file being available, or stored in
this location. Nor can they rely on the existence of the macro.
-->
<mujoco>
<compiler
meshdir="meshes"
balanceinertia="true"
discardvisual="false" />
</mujoco>
<link name="box1_place"/>
<joint name="box1_place_joint" type="fixed">
<parent link="world"/>
<child link="box1_place"/>
<origin rpy="-3.1415927 0.0 0.0" xyz="-0.45 -0.055 0.46"/>
</joint>
<link name="box2_place"/>
<joint name="box2_place_joint" type="fixed">
<parent link="world"/>
<child link="box2_place"/>
<origin rpy="-3.1415927 0.0 0.0" xyz="-0.45 0.0 0.46"/>
</joint>
<link name="box3_place"/>
<joint name="box3_place_joint" type="fixed">
<parent link="world"/>
<child link="box3_place"/>
<origin rpy="-3.1415927 0.0 0.0" xyz="-0.45 0.055 0.46"/>
</joint>
<link name="box4_place"/>
<joint name="box4_place_joint" type="fixed">
<parent link="world"/>
<child link="box4_place"/>
<origin rpy="-3.1415927 0.0 0.0" xyz="-0.45 0.0275 0.49"/>
</joint>
<link name="box5_place"/>
<joint name="box5_place_joint" type="fixed">
<parent link="world"/>
<child link="box5_place"/>
<origin rpy="-3.1415927 0.0 0.0" xyz="-0.45 -0.0275 0.49"/>
</joint>
<link name="box6_place"/>
<joint name="box6_place_joint" type="fixed">
<parent link="world"/>
<child link="box6_place"/>
<origin rpy="-3.1415927 0.0 0.0" xyz="-0.45 0 0.56"/>
</joint>
<!-- create link fixed to the "world" -->
<link name="world"/>
<ros2_control name="ur" type="system">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="shoulder_pan_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="shoulder_lift_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="elbow_joint">
<command_interface name="position">
<param name="min">{-pi}</param>
<param name="max">{pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_1_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_2_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_3_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
<!-- Placeholder for ros2_control transmission which don't yet exist -->
<!-- links - main serial chain -->
<link name="base_link"/>
<link name="base_link_inertia">
<visual>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/base.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/base.stl"/>
</geometry>
</collision>
<inertial>
<mass value="4.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072"/>
</inertial>
</link>
<link name="shoulder_link">
<visual>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/shoulder.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/shoulder.stl"/>
</geometry>
</collision>
<inertial>
<mass value="3.7"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.010267495893" ixy="0.0" ixz="0.0" iyy="0.010267495893" iyz="0.0" izz="0.00666"/>
</inertial>
</link>
<link name="upper_arm_link">
<visual>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.138"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/upperarm.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.138"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/upperarm.stl"/>
</geometry>
</collision>
<inertial>
<mass value="8.393"/>
<origin rpy="0 1.5707963267948966 0" xyz="-0.2125 0.0 0.138"/>
<inertia ixx="0.1338857818623325" ixy="0.0" ixz="0.0" iyy="0.1338857818623325" iyz="0.0" izz="0.0151074"/>
</inertial>
</link>
<link name="forearm_link">
<visual>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.007"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/forearm.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.007"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/forearm.stl"/>
</geometry>
</collision>
<inertial>
<mass value="2.275"/>
<origin rpy="0 1.5707963267948966 0" xyz="-0.1961 0.0 0.007"/>
<inertia ixx="0.031209355099586295" ixy="0.0" ixz="0.0" iyy="0.031209355099586295" iyz="0.0" izz="0.004095"/>
</inertial>
</link>
<link name="wrist_1_link">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.127"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/wrist1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.127"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/wrist1.stl"/>
</geometry>
</collision>
<inertial>
<mass value="1.219"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0025598989760400002" ixy="0.0" ixz="0.0" iyy="0.0025598989760400002" iyz="0.0" izz="0.0021942"/>
</inertial>
</link>
<link name="wrist_2_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.0997"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/wrist2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.0997"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/wrist2.stl"/>
</geometry>
</collision>
<inertial>
<mass value="1.219"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0025598989760400002" ixy="0.0" ixz="0.0" iyy="0.0025598989760400002" iyz="0.0" izz="0.0021942"/>
</inertial>
</link>
<link name="wrist_3_link">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.0989"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/visual/wrist3.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.0989"/>
<geometry>
<mesh filename="file:///home/bill-finger/rasms_ws/install/ur_description/share/ur_description/meshes/ur5e/collision/wrist3.stl"/>
</geometry>
</collision>
<inertial>
<mass value="0.1879"/>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.0229"/>
<inertia ixx="9.890410052167731e-05" ixy="0.0" ixz="0.0" iyy="9.890410052167731e-05" iyz="0.0" izz="0.0001321171875"/>
</inertial>
</link>
<!-- base_joint fixes base_link to the environment -->
<joint name="base_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base_link"/>
</joint>
<!-- joints - main serial chain -->
<joint name="base_link-base_link_inertia" type="fixed">
<parent link="base_link"/>
<child link="base_link_inertia"/>
<!-- 'base_link' is REP-103 aligned (so X+ forward), while the internal
frames of the robot/controller have X+ pointing backwards.
Use the joint between 'base_link' and 'base_link_inertia' (a dummy
link/frame) to introduce the necessary rotation over Z (of pi rad).
-->
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
</joint>
<joint name="shoulder_pan_joint" type="revolute">
<parent link="base_link_inertia"/>
<child link="shoulder_link"/>
<origin rpy="0 0 0" xyz="0 0 0.1625"/>
<axis xyz="0 0 1"/>
<limit effort="150.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="shoulder_lift_joint" type="revolute">
<parent link="shoulder_link"/>
<child link="upper_arm_link"/>
<origin rpy="1.570796327 1.570796327 0" xyz="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="150.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-1.4207963267948966" soft_upper_limit="1.4207963267948966"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="elbow_joint" type="revolute">
<parent link="upper_arm_link"/>
<child link="forearm_link"/>
<origin rpy="0 0 0" xyz="-0.425 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="150.0" lower="-2.7576202181510405" upper="2.7576202181510405" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-2.6076202181510406" soft_upper_limit="2.6076202181510406"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_1_joint" type="revolute">
<parent link="forearm_link"/>
<child link="wrist_1_link"/>
<origin rpy="0 0 -1.570796327" xyz="-0.3922 0 0.1333"/>
<axis xyz="0 0 1"/>
<limit effort="28.0" lower="-2.2689280275926285" upper="2.2689280275926285" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-2.1189280275926285" soft_upper_limit="2.1189280275926285"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_2_joint" type="revolute">
<parent link="wrist_1_link"/>
<child link="wrist_2_link"/>
<origin rpy="1.570796327 0 0" xyz="0 -0.0997 -2.044881182297852e-11"/>
<axis xyz="0 0 1"/>
<limit effort="28.0" lower="-2.530727415391778" upper="2.530727415391778" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-2.380727415391778" soft_upper_limit="2.380727415391778"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_3_joint" type="revolute">
<parent link="wrist_2_link"/>
<child link="wrist_3_link"/>
<origin rpy="1.570796326589793 3.141592653589793 3.141592653589793" xyz="0 0.0996 -2.042830148012698e-11"/>
<axis xyz="0 0 1"/>
<limit effort="28.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
<safety_controller k_position="20" k_velocity="0.0" soft_lower_limit="-6.133185307179586" soft_upper_limit="6.133185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<link name="ft_frame"/>
<joint name="wrist_3_link-ft_frame" type="fixed">
<parent link="wrist_3_link"/>
<child link="ft_frame"/>
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
</joint>
<!-- ROS-Industrial 'base' frame - base_link to UR 'Base' Coordinates transform -->
<link name="base"/>
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- Note the rotation over Z of pi radians - as base_link is REP-103
aligned (i.e., has X+ forward, Y+ left and Z+ up), this is needed
to correctly align 'base' with the 'Base' coordinate system of
the UR controller.
-->
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="base"/>
</joint>
<!-- ROS-Industrial 'flange' frame - attachment point for EEF models -->
<link name="flange"/>
<joint name="wrist_3-flange" type="fixed">
<parent link="wrist_3_link"/>
<child link="flange"/>
<origin rpy="0 -1.5707963267948966 -1.5707963267948966" xyz="0 0 0"/>
</joint>
<!-- ROS-Industrial 'tool0' frame - all-zeros tool frame -->
<link name="tool0"/>
<joint name="flange-tool0" type="fixed">
<!-- default toolframe - X+ left, Y+ up, Z+ front -->
<origin rpy="1.5707963267948966 0 1.5707963267948966" xyz="0 0 0"/>
<parent link="flange"/>
<child link="tool0"/>
</joint>
<!-- <xacro:plane parent="world">
<origin xyz="0 0 -0.001" rpy="0 0 0"/>
</xacro:plane>
<xacro:rack parent="world">
<origin xyz="0.0 0.7 0.0" rpy="0.0 0.0 0.0"/>
</xacro:rack>
<xacro:table parent="world">
<origin xyz="-0.75 0.0 0.2" rpy="0.0 0.0 0.0"/>
</xacro:table> -->
<link name="rgbd_camera">
<inertial>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<mass value="0.1"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
<visual name="">
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
<material name="">
<color rgba="0.0 0.0 0.0 1.0"/>
<texture filename=""/>
</material>
</visual>
<collision>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
</collision>
</link>
<gazebo reference="rgbd_camera">
<sensor name="rgbd_camera" type="rgbd_camera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>rgbd_camera</topic>
<enable_metrics>true</enable_metrics>
</sensor>
</gazebo>
<joint name="plane_base_joint" type="fixed">
<parent link="tool0"/>
<child link="rgbd_camera"/>
<origin rpy="1.57 -1.57 0" xyz="0 -0.05 0.07"/>
</joint>
<gazebo reference="world">
</gazebo>
<gazebo>
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<parameters>/home/bill-finger/rasms_ws/install/ur_moveit_config/share/ur_moveit_config/config/ur_controllers.yaml</parameters>
<controller_manager_node_name>controller_manager</controller_manager_node_name>
</plugin>
</gazebo>
</robot>