cnc-graver-assist/urdf/current.urdf
2025-02-06 18:57:25 +03:00

355 lines
13 KiB
XML

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from rbs_arm_modular.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="rbs_arm">
<link name="world"/>
<joint name="base_link_joint" type="fixed">
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
<parent link="world"/>
<child link="base_link"/>
</joint>
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="0.00078073 -0.005657 0.036649"/>
<mass value="0.61398"/>
<inertia ixx="0.0015423" ixy="2.1048E-05" ixz="-2.1541E-06" iyy="0.0014689" iyz="7.0187E-07" izz="0.0015067"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/base_link.stl"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<!-- <xacro:joint_hardware joint_name="${tf_prefix}base_link" hardware="${hardware}" p="100"/> -->
<!-- <xacro:rbs_materials link_name="${tf_prefix}base_link" link_type="base_link"></xacro:rbs_materials> -->
<joint name="fork0_link_joint" type="revolute">
<limit effort="78" lower="-6.14159" upper="6.14159" velocity="0.52"/>
<origin rpy="0.0 0 -3.1416" xyz="0 0 0.11165"/>
<parent link="base_link"/>
<child link="fork0_link"/>
<axis xyz="0 0 1"/>
</joint>
<link name="fork0_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.0050017 0.088736 0.0023758"/>
<mass value="0.49312"/>
<inertia ixx="0.0016921" ixy="-1.8404E-05" ixz="9.951E-07" iyy="0.00087841" iyz="-2.5874E-06" izz="0.0019955"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/axis1_fork.stl"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/axis1_fork.stl"/>
</geometry>
</collision>
</link>
<ros2_control name="fork0_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<joint name="fork0_link_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<!-- WARN When this active a robot falls down -->
<!-- <command_interface name="effort"/> -->
<param name="p">10000</param>
<param name="d">0.2</param>
<!-- <command_interface name="effort"/> -->
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<!-- <state_interface name="acceleration"/> -->
</joint>
</ros2_control>
<!-- <xacro:rbs_materials link_name="${tf_prefix}${name}" link_type="fork" /> -->
<joint name="main0_link_joint" type="revolute">
<limit effort="78" lower="-2.43" upper="2.43" velocity="0.52"/>
<!-- <origin rpy="0.0 0 -3.1416" xyz="0 0 0.11165"></origin> -->
<origin rpy="0.0 0 0" xyz="0 0.0 0.15465"/>
<parent link="fork0_link"/>
<child link="main0_link"/>
<axis xyz="1 0 0"/>
</joint>
<link name="main0_link">
<inertial>
<origin rpy="0 0 0" xyz="0.00027998 -0.045366 0.0068959"/>
<mass value="0.42726"/>
<inertia ixx="0.0013794" ixy="-4.0542E-05" ixz="-8.9181E-06" iyy="0.00047255" iyz="-3.4771E-05" izz="0.001587"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/axis2_main.stl"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/axis2_main.stl"/>
</geometry>
</collision>
</link>
<ros2_control name="main0_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<joint name="main0_link_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<!-- WARN When this active a robot falls down -->
<!-- <command_interface name="effort"/> -->
<param name="p">10000</param>
<param name="d">0.2</param>
<!-- <command_interface name="effort"/> -->
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<!-- <state_interface name="acceleration"/> -->
</joint>
</ros2_control>
<!-- <xacro:rbs_materials link_name="${tf_prefix}${name}" link_type="main_link" /> -->
<joint name="fork1_link_joint" type="revolute">
<limit effort="78" lower="-6.14159" upper="6.14159" velocity="0.52"/>
<origin rpy="0 0 0" xyz="0.0 0.0 0.11995"/>
<parent link="main0_link"/>
<child link="fork1_link"/>
<axis xyz="0 0 1"/>
</joint>
<link name="fork1_link">
<inertial>
<origin rpy="0 0 0" xyz="-0.0050017 0.088736 0.0023758"/>
<mass value="0.49312"/>
<inertia ixx="0.0016921" ixy="-1.8404E-05" ixz="9.951E-07" iyy="0.00087841" iyz="-2.5874E-06" izz="0.0019955"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/axis1_fork.stl"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/axis1_fork.stl"/>
</geometry>
</collision>
</link>
<ros2_control name="fork1_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<joint name="fork1_link_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<!-- WARN When this active a robot falls down -->
<!-- <command_interface name="effort"/> -->
<param name="p">10000</param>
<param name="d">0.2</param>
<!-- <command_interface name="effort"/> -->
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<!-- <state_interface name="acceleration"/> -->
</joint>
</ros2_control>
<!-- <xacro:rbs_materials link_name="${tf_prefix}${name}" link_type="fork" /> -->
<joint name="main1_link_joint" type="revolute">
<limit effort="78" lower="-2.43" upper="2.43" velocity="0.52"/>
<!-- <origin rpy="0.0 0 -3.1416" xyz="0 0 0.11165"></origin> -->
<origin rpy="0.0 0 0" xyz="0 0.0 0.15465"/>
<parent link="fork1_link"/>
<child link="main1_link"/>
<axis xyz="1 0 0"/>
</joint>
<link name="main1_link">
<inertial>
<origin rpy="0 0 0" xyz="0.00027998 -0.045366 0.0068959"/>
<mass value="0.42726"/>
<inertia ixx="0.0013794" ixy="-4.0542E-05" ixz="-8.9181E-06" iyy="0.00047255" iyz="-3.4771E-05" izz="0.001587"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/axis2_main.stl"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/axis2_main.stl"/>
</geometry>
</collision>
</link>
<ros2_control name="main1_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<joint name="main1_link_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<!-- WARN When this active a robot falls down -->
<!-- <command_interface name="effort"/> -->
<param name="p">1000</param>
<param name="d">0.2</param>
<!-- <command_interface name="effort"/> -->
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<!-- <state_interface name="acceleration"/> -->
</joint>
</ros2_control>
<!-- <xacro:rbs_materials link_name="${tf_prefix}${name}" link_type="main_link" /> -->
<joint name="ee_link_joint" type="revolute">
<limit effort="78" lower="-2.43" upper="2.43" velocity="0.52"/>
<origin rpy="0 0 0.0" xyz="0.0 0.0 0.0754"/>
<parent link="main1_link"/>
<child link="ee_link"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="tool0_joint" type="fixed">
<origin rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.14100"/>
<parent link="ee_link"/>
<child link="tool0"/>
</joint>
<link name="tool0"/>
<link name="ee_link">
<inertial>
<origin rpy="0 0 0" xyz="1.594E-06 0.085889 0.0021969"/>
<mass value="0.20976"/>
<inertia ixx="0.00016257" ixy="4.2628E-07" ixz="-3.8857E-07" iyy="0.00022468" iyz="2.1709E-05" izz="0.00023702"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/visual/axis7_tail.stl"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_arm/share/rbs_arm/meshes/collision/axis7_tail.stl"/>
</geometry>
</collision>
</link>
<ros2_control name="ee_link_joint_hardware_interface" type="actuator">
<hardware>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<joint name="ee_link_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<!-- WARN When this active a robot falls down -->
<!-- <command_interface name="effort"/> -->
<param name="p">20</param>
<param name="d">0.2</param>
<!-- <command_interface name="effort"/> -->
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<!-- <state_interface name="acceleration"/> -->
</joint>
</ros2_control>
<!-- <xacro:rbs_materials link_name="${tf_prefix}ee_link" link_type="ee_link" /> -->
<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.000166667" ixy="0.0" ixz="0.0" iyy="0.000166667" iyz="0.0" izz="0.000166667"/>
</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="rgbd_camera_to_parent" type="fixed">
<parent link="ee_link"/>
<child link="rgbd_camera"/>
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
</joint>
<!-- Insert gripper in robot description if exist -->
<!-- <xacro:if value="${gripper_name=='rbs_gripper'}"> -->
<!-- <xacro:include filename="$(find rbs_gripper)/urdf/rbs_gripper_macro.xacro"></xacro:include> -->
<!-- <xacro:rbs_gripper gripper_name="rbs_gripper" hardware="${hardware}"
parent="${tf_prefix}tool0" tf_prefix="${tf_prefix}"> -->
<!-- <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"></origin> -->
<!-- </xacro:rbs_gripper> -->
<!-- </xacro:if> -->
<!-- <xacro:fts link="tool0" name="fts_sensor" tf_prefix="${tf_prefix}"></xacro:fts> -->
<gazebo>
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
<parameters></parameters>
<ros>
<namespace>arm0</namespace>
</ros>
</plugin>
</gazebo>
</robot>