new 6dof robot model
This commit is contained in:
parent
db2e145f2d
commit
82ec9f2dde
17 changed files with 854 additions and 222 deletions
|
@ -48,7 +48,7 @@ install(
|
|||
DESTINATION lib/${PROJECT_NAME}
|
||||
)
|
||||
|
||||
install(DIRECTORY launch urdf config world assets
|
||||
install(DIRECTORY launch urdf config world assets meshes
|
||||
DESTINATION share/${PROJECT_NAME})
|
||||
|
||||
if(BUILD_TESTING)
|
||||
|
|
|
@ -206,7 +206,7 @@ def generate_launch_description():
|
|||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"description_file",
|
||||
default_value="rbs_arm_modular.xacro",
|
||||
default_value="rbs_arm.xacro",
|
||||
description="URDF/XACRO description file with the robot.",
|
||||
)
|
||||
)
|
||||
|
@ -272,7 +272,7 @@ def generate_launch_description():
|
|||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"ee_link_name",
|
||||
default_value="tool0",
|
||||
default_value="Link6",
|
||||
description="End effector name of robot arm",
|
||||
)
|
||||
)
|
||||
|
|
BIN
meshes/Link1.STL
Normal file
BIN
meshes/Link1.STL
Normal file
Binary file not shown.
BIN
meshes/Link2.STL
Normal file
BIN
meshes/Link2.STL
Normal file
Binary file not shown.
BIN
meshes/Link3.STL
Normal file
BIN
meshes/Link3.STL
Normal file
Binary file not shown.
BIN
meshes/Link4.STL
Normal file
BIN
meshes/Link4.STL
Normal file
Binary file not shown.
BIN
meshes/Link5.STL
Normal file
BIN
meshes/Link5.STL
Normal file
Binary file not shown.
BIN
meshes/Link6.STL
Normal file
BIN
meshes/Link6.STL
Normal file
Binary file not shown.
BIN
meshes/Link7.STL
Normal file
BIN
meshes/Link7.STL
Normal file
Binary file not shown.
BIN
meshes/Link8.STL
Normal file
BIN
meshes/Link8.STL
Normal file
Binary file not shown.
BIN
meshes/base_link.STL
Normal file
BIN
meshes/base_link.STL
Normal file
Binary file not shown.
|
@ -1,25 +1,49 @@
|
|||
<?xml version="1.0" ?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from rbs_arm_modular.xacro | -->
|
||||
<!-- | This document was autogenerated by xacro from rbs_arm.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"/>
|
||||
<link name="machine_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.4 0.5 0.115"/>
|
||||
</geometry>
|
||||
<material name="gray">
|
||||
<color rgba="0 1 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.4 0.5 0.115"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="40.0"/>
|
||||
<inertia ixx="0.6580625" ixy="0" ixz="0" iyy="0.4330625" iyz="0" izz="1.0250000000000001"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="machine_joint" type="fixed">
|
||||
<parent link="world"/>
|
||||
<child link="machine_link"/>
|
||||
<origin rpy="0 0 0" xyz="0.25 0 0.0575"/>
|
||||
</joint>
|
||||
<joint name="parent_connection" type="fixed">
|
||||
<origin rpy="0.0 0.0 0.0" xyz="-0.10 0.0 0.03"/>
|
||||
<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"/>
|
||||
<origin rpy="0 0 0" xyz="0.00017379 -0.0030159 0.045999"/>
|
||||
<mass value="0.72132"/>
|
||||
<inertia ixx="0.0013803" ixy="-8.9867E-06" ixz="-8.5813E-06" iyy="0.0018444" iyz="-5.4408E-05" izz="0.0023998"/>
|
||||
</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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/base_link.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
|
@ -28,29 +52,49 @@
|
|||
<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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/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"/>
|
||||
<link name="Link1">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0045937 0.0021781 0.088722"/>
|
||||
<mass value="0.48715"/>
|
||||
<inertia ixx="0.0016524" ixy="9.9556E-07" ixz="2.6451E-05" iyy="0.0019476" iyz="-5.7271E-06" izz="0.0008719"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link1.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_mill_assist/share/rbs_mill_assist/meshes/Link1.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="ax1" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 -0.0002 0.13115"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="fork0_link"/>
|
||||
<child link="Link1"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" lower="-3.14159" upper="3.14159" velocity="10"/>
|
||||
</joint>
|
||||
<link name="fork0_link">
|
||||
<link name="Link2">
|
||||
<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"/>
|
||||
<origin rpy="0 0 0" xyz="3.2673E-06 -0.004271 0.045945"/>
|
||||
<mass value="0.38011"/>
|
||||
<inertia ixx="0.0013451" ixy="-1.3296E-08" ixz="-4.8961E-05" iyy="0.0014979" iyz="4.3965E-07" izz="0.00041688"/>
|
||||
</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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link2.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
|
@ -59,48 +103,56 @@
|
|||
<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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link2.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"/>
|
||||
<joint name="ax2" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 0.15465"/>
|
||||
<parent link="Link1"/>
|
||||
<child link="Link2"/>
|
||||
<axis xyz="-1 0 0"/>
|
||||
<limit effort="30" lower="-1.57" upper="1.57" velocity="10"/>
|
||||
</joint>
|
||||
<link name="Link3">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.0044385 0.00040477 0.0403"/>
|
||||
<mass value="0.39622"/>
|
||||
<inertia ixx="0.00082818" ixy="-3.1574E-06" ixz="1.2935E-05" iyy="0.0010343" iyz="1.9002E-06" izz="0.0006516"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link3.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_mill_assist/share/rbs_mill_assist/meshes/Link3.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="ax3" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 0.092"/>
|
||||
<parent link="Link2"/>
|
||||
<child link="Link3"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="30" lower="-1.57" upper="1.57" velocity="10"/>
|
||||
</joint>
|
||||
<link name="main0_link">
|
||||
<link name="Link4">
|
||||
<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"/>
|
||||
<origin rpy="0 0 0" xyz="0.0012006 -0.0085317 0.066006"/>
|
||||
<mass value="0.22302"/>
|
||||
<inertia ixx="0.0004366" ixy="4.6943E-06" ixz="-1.1269E-05" iyy="0.00049426" iyz="-5.7406E-07" izz="0.00018045"/>
|
||||
</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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link4.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
|
@ -109,47 +161,27 @@
|
|||
<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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link4.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 name="ax4" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 0.098"/>
|
||||
<parent link="Link3"/>
|
||||
<child link="Link4"/>
|
||||
<axis xyz="0 0 -1"/>
|
||||
<limit effort="30" lower="-3.14159" upper="3.14159" velocity="10"/>
|
||||
</joint>
|
||||
<link name="fork1_link">
|
||||
<link name="Link5">
|
||||
<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"/>
|
||||
<origin rpy="0 0 0" xyz="-0.00084186 1.3844E-05 0.068718"/>
|
||||
<mass value="0.55235"/>
|
||||
<inertia ixx="0.00048011" ixy="5.3951E-07" ixz="-4.1834E-06" iyy="0.00074778" iyz="5.6449E-06" izz="0.00070916"/>
|
||||
</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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link5.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
|
@ -158,48 +190,27 @@
|
|||
<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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link5.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"/>
|
||||
<joint name="ax5" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0 0 0.0949"/>
|
||||
<parent link="Link4"/>
|
||||
<child link="Link5"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="30" lower="-1.57" upper="1.57" velocity="10"/>
|
||||
</joint>
|
||||
<link name="main1_link">
|
||||
<link name="Link6">
|
||||
<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"/>
|
||||
<origin rpy="0 0 0" xyz="2.3821E-11 -0.054292 0.018171"/>
|
||||
<mass value="0.41222"/>
|
||||
<inertia ixx="0.00057892" ixy="-5.0591E-13" ixz="1.1462E-13" iyy="8.7903E-05" iyz="5.3383E-05" izz="0.00063814"/>
|
||||
</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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link6.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
|
@ -208,76 +219,179 @@
|
|||
<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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link6.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"/>
|
||||
<joint name="ax6" type="revolute">
|
||||
<origin rpy="0 0 0" xyz="0.0012 0 0.10155"/>
|
||||
<parent link="Link5"/>
|
||||
<child link="Link6"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="30" lower="-3.14159" upper="3.14159" velocity="10"/>
|
||||
</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">
|
||||
<link name="Link7">
|
||||
<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"/>
|
||||
<origin rpy="0 0 0" xyz="3.46944695195361E-18 -5.55111512312578E-17 -0.00360613836994461"/>
|
||||
<mass value="0.0198935071603267"/>
|
||||
<inertia ixx="1.01905343575873E-06" ixy="3.76158192263132E-37" ixz="-3.1449831265618E-23" iyy="1.01905343575873E-06" iyz="6.29843212132371E-23" izz="1.43041044988815E-06"/>
|
||||
</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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link7.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="0.75294 0.75294 0.75294 1"/>
|
||||
<color rgba="1 1 1 0.4"/>
|
||||
</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"/>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link7.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<ros2_control name="ee_link_joint_hardware_interface" type="actuator">
|
||||
<joint name="Right_point" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0.015 -0.095 0.05"/>
|
||||
<parent link="Link6"/>
|
||||
<child link="Link7"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint>
|
||||
<link name="Link8">
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 -2.77555756156289E-17 -0.00360613836994461"/>
|
||||
<mass value="0.0198935071603267"/>
|
||||
<inertia ixx="1.01905343575873E-06" ixy="0" ixz="-2.89418945570099E-23" iyy="1.01905343575872E-06" iyz="-1.78775100697742E-23" izz="1.43041044988815E-06"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link8.STL"/>
|
||||
</geometry>
|
||||
<material name="">
|
||||
<color rgba="1 1 1 0.4"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file:///home/narenmak/rbs_ws/install/rbs_mill_assist/share/rbs_mill_assist/meshes/Link8.STL"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="Left_point" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="-0.015 -0.095 0.05"/>
|
||||
<parent link="Link6"/>
|
||||
<child link="Link8"/>
|
||||
<axis xyz="0 0 0"/>
|
||||
</joint>
|
||||
<ros2_control name="ax1_hardware_interface" type="actuator">
|
||||
<hardware>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="ee_link_joint">
|
||||
<joint name="ax1">
|
||||
<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>
|
||||
<!-- <param name="p">${p}</param> -->
|
||||
<!-- <param name="d">${d}</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>
|
||||
<ros2_control name="ax2_hardware_interface" type="actuator">
|
||||
<hardware>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="ax2">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<!-- WARN When this active a robot falls down -->
|
||||
<!-- <command_interface name="effort"/> -->
|
||||
<!-- <param name="p">${p}</param> -->
|
||||
<!-- <param name="d">${d}</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>
|
||||
<ros2_control name="ax3_hardware_interface" type="actuator">
|
||||
<hardware>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="ax3">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<!-- WARN When this active a robot falls down -->
|
||||
<!-- <command_interface name="effort"/> -->
|
||||
<!-- <param name="p">${p}</param> -->
|
||||
<!-- <param name="d">${d}</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>
|
||||
<ros2_control name="ax4_hardware_interface" type="actuator">
|
||||
<hardware>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="ax4">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<!-- WARN When this active a robot falls down -->
|
||||
<!-- <command_interface name="effort"/> -->
|
||||
<!-- <param name="p">${p}</param> -->
|
||||
<!-- <param name="d">${d}</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>
|
||||
<ros2_control name="ax5_hardware_interface" type="actuator">
|
||||
<hardware>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="ax5">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<!-- WARN When this active a robot falls down -->
|
||||
<!-- <command_interface name="effort"/> -->
|
||||
<!-- <param name="p">${p}</param> -->
|
||||
<!-- <param name="d">${d}</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>
|
||||
<ros2_control name="ax6_hardware_interface" type="actuator">
|
||||
<hardware>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="ax6">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<!-- WARN When this active a robot falls down -->
|
||||
<!-- <command_interface name="effort"/> -->
|
||||
<!-- <param name="p">${p}</param> -->
|
||||
<!-- <param name="d">${d}</param> -->
|
||||
<!-- <command_interface name="effort"/> -->
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">0.0</param>
|
||||
|
@ -286,63 +400,6 @@
|
|||
<!-- <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">
|
||||
|
@ -351,5 +408,15 @@
|
|||
<namespace>arm0</namespace>
|
||||
</ros>
|
||||
</plugin>
|
||||
<plugin filename="VacuumGripper" name="rbs_mill_assist::VacuumGripper">
|
||||
<link_name>Link6</link_name>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<gazebo reference="Link6">
|
||||
<sensor name="sensor_contact" type="contact">
|
||||
<contact>
|
||||
<collision>Link6_collision</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
</robot>
|
||||
|
|
0
urdf/gazebo_reference_macro.xacro
Normal file
0
urdf/gazebo_reference_macro.xacro
Normal file
25
urdf/rbs_arm.xacro
Normal file
25
urdf/rbs_arm.xacro
Normal file
|
@ -0,0 +1,25 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="rbs_arm">
|
||||
<xacro:arg name="gripper_name" default="" />
|
||||
<xacro:arg name="hardware" default="gazebo" />
|
||||
<xacro:arg name="simulation_controllers" default="" />
|
||||
<xacro:arg name="tf_prefix" default="" />
|
||||
<xacro:arg name="namespace" default="arm0"/>
|
||||
|
||||
<xacro:arg name="x" default="-0.10" />
|
||||
<xacro:arg name="y" default="0.0" />
|
||||
<xacro:arg name="z" default="0.03" />
|
||||
|
||||
<xacro:arg name="roll" default="0.0" />
|
||||
<xacro:arg name="pitch" default="0.0" />
|
||||
<xacro:arg name="yaw" default="0.0" />
|
||||
|
||||
<xacro:include filename="$(find rbs_mill_assist)/urdf/rbs_arm_macro.xacro" />
|
||||
<link name="world" />
|
||||
|
||||
<!-- Arm-->
|
||||
<xacro:rbs_arm_vacuum namespace="$(arg namespace)" parent="world" tf_prefix="$(arg tf_prefix)" hardware="$(arg hardware)"
|
||||
gripper_name="$(arg gripper_name)" controllers="$(arg simulation_controllers)">
|
||||
<origin xyz="$(arg x) $(arg y) $(arg z)" rpy="$(arg roll) $(arg pitch) $(arg yaw)" />
|
||||
</xacro:rbs_arm_vacuum>
|
||||
</robot>
|
540
urdf/rbs_arm_macro.xacro
Normal file
540
urdf/rbs_arm_macro.xacro
Normal file
|
@ -0,0 +1,540 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:macro name="rbs_arm_vacuum"
|
||||
params="namespace parent *origin tf_prefix hardware gripper_name controllers">
|
||||
|
||||
<xacro:include filename="$(find rbs_mill_assist)/urdf/sensors.xacro"></xacro:include>
|
||||
<xacro:include filename="$(find rbs_arm)/urdf/inc/joint_hardware.xacro" />
|
||||
|
||||
<joint name="${tf_prefix}parent_connection" type="fixed">
|
||||
<xacro:insert_block name="origin" />
|
||||
<parent link="${parent}" />
|
||||
<child link="base_link" />
|
||||
</joint>
|
||||
|
||||
<link
|
||||
name="base_link">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.00017379 -0.0030159 0.045999"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.72132" />
|
||||
<inertia
|
||||
ixx="0.0013803"
|
||||
ixy="-8.9867E-06"
|
||||
ixz="-8.5813E-06"
|
||||
iyy="0.0018444"
|
||||
iyz="-5.4408E-05"
|
||||
izz="0.0023998" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="file://$(find rbs_mill_assist)/meshes/base_link.STL"></mesh>
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0.75294 0.75294 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/base_link.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link
|
||||
name="Link1">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0045937 0.0021781 0.088722"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.48715" />
|
||||
<inertia
|
||||
ixx="0.0016524"
|
||||
ixy="9.9556E-07"
|
||||
ixz="2.6451E-05"
|
||||
iyy="0.0019476"
|
||||
iyz="-5.7271E-06"
|
||||
izz="0.0008719" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link1.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0.75294 0.75294 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link1.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="ax1"
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 -0.0002 0.13115"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="base_link" />
|
||||
<child
|
||||
link="Link1" />
|
||||
<axis
|
||||
xyz="0 0 1" />
|
||||
<limit
|
||||
lower="-6.2832"
|
||||
upper="6.2832"
|
||||
effort="30"
|
||||
velocity="10" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link2">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="3.2673E-06 -0.004271 0.045945"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.38011" />
|
||||
<inertia
|
||||
ixx="0.0013451"
|
||||
ixy="-1.3296E-08"
|
||||
ixz="-4.8961E-05"
|
||||
iyy="0.0014979"
|
||||
iyz="4.3965E-07"
|
||||
izz="0.00041688" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link2.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0.75294 0.75294 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link2.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="ax2"
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0.15465"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link1" />
|
||||
<child
|
||||
link="Link2" />
|
||||
<axis
|
||||
xyz="-1 0 0" />
|
||||
<limit
|
||||
lower="-2.2689"
|
||||
upper="1.7453"
|
||||
effort="30"
|
||||
velocity="10" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link3">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.0044385 0.00040477 0.0403"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.39622" />
|
||||
<inertia
|
||||
ixx="0.00082818"
|
||||
ixy="-3.1574E-06"
|
||||
ixz="1.2935E-05"
|
||||
iyy="0.0010343"
|
||||
iyz="1.9002E-06"
|
||||
izz="0.0006516" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link3.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0.75294 0.75294 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link3.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="ax3"
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0.092"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link2" />
|
||||
<child
|
||||
link="Link3" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
<limit
|
||||
lower="-2.2689"
|
||||
upper="1.7453"
|
||||
effort="30"
|
||||
velocity="10" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link4">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0.0012006 -0.0085317 0.066006"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.22302" />
|
||||
<inertia
|
||||
ixx="0.0004366"
|
||||
ixy="4.6943E-06"
|
||||
ixz="-1.1269E-05"
|
||||
iyy="0.00049426"
|
||||
iyz="-5.7406E-07"
|
||||
izz="0.00018045" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link4.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0.75294 0.75294 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link4.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="ax4"
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0.098"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link3" />
|
||||
<child
|
||||
link="Link4" />
|
||||
<axis
|
||||
xyz="0 0 -1" />
|
||||
<limit
|
||||
lower="-6.2832"
|
||||
upper="6.2832"
|
||||
effort="30"
|
||||
velocity="10" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link5">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="-0.00084186 1.3844E-05 0.068718"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.55235" />
|
||||
<inertia
|
||||
ixx="0.00048011"
|
||||
ixy="5.3951E-07"
|
||||
ixz="-4.1834E-06"
|
||||
iyy="0.00074778"
|
||||
iyz="5.6449E-06"
|
||||
izz="0.00070916" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link5.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0.75294 0.75294 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link5.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="ax5"
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0 0 0.0949"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link4" />
|
||||
<child
|
||||
link="Link5" />
|
||||
<axis
|
||||
xyz="1 0 0" />
|
||||
<limit
|
||||
lower="-1.7453"
|
||||
upper="2.0944"
|
||||
effort="30"
|
||||
velocity="10" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link6">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="2.3821E-11 -0.054292 0.018171"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.41222" />
|
||||
<inertia
|
||||
ixx="0.00057892"
|
||||
ixy="-5.0591E-13"
|
||||
ixz="1.1462E-13"
|
||||
iyy="8.7903E-05"
|
||||
iyz="5.3383E-05"
|
||||
izz="0.00063814" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link6.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="0.75294 0.75294 0.75294 1" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link6.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="ax6"
|
||||
type="revolute">
|
||||
<origin
|
||||
xyz="0.0012 0 0.10155"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link5" />
|
||||
<child
|
||||
link="Link6" />
|
||||
<axis
|
||||
xyz="0 0 1" />
|
||||
<limit
|
||||
lower="-6.2832"
|
||||
upper="6.2832"
|
||||
effort="30"
|
||||
velocity="10" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link7">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="3.46944695195361E-18 -5.55111512312578E-17 -0.00360613836994461"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.0198935071603267" />
|
||||
<inertia
|
||||
ixx="1.01905343575873E-06"
|
||||
ixy="3.76158192263132E-37"
|
||||
ixz="-3.1449831265618E-23"
|
||||
iyy="1.01905343575873E-06"
|
||||
iyz="6.29843212132371E-23"
|
||||
izz="1.43041044988815E-06" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link7.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 1 0.4" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link7.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="Right_point"
|
||||
type="fixed">
|
||||
<origin
|
||||
xyz="0.015 -0.095 0.05"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link6" />
|
||||
<child
|
||||
link="Link7" />
|
||||
<axis
|
||||
xyz="0 0 0" />
|
||||
</joint>
|
||||
<link
|
||||
name="Link8">
|
||||
<inertial>
|
||||
<origin
|
||||
xyz="0 -2.77555756156289E-17 -0.00360613836994461"
|
||||
rpy="0 0 0" />
|
||||
<mass
|
||||
value="0.0198935071603267" />
|
||||
<inertia
|
||||
ixx="1.01905343575873E-06"
|
||||
ixy="0"
|
||||
ixz="-2.89418945570099E-23"
|
||||
iyy="1.01905343575872E-06"
|
||||
iyz="-1.78775100697742E-23"
|
||||
izz="1.43041044988815E-06" />
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link8.STL" />
|
||||
</geometry>
|
||||
<material
|
||||
name="">
|
||||
<color
|
||||
rgba="1 1 1 0.4" />
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin
|
||||
xyz="0 0 0"
|
||||
rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find rbs_mill_assist)/meshes/Link8.STL" />
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint
|
||||
name="Left_point"
|
||||
type="fixed">
|
||||
<origin
|
||||
xyz="-0.015 -0.095 0.05"
|
||||
rpy="0 0 0" />
|
||||
<parent
|
||||
link="Link6" />
|
||||
<child
|
||||
link="Link8" />
|
||||
<axis
|
||||
xyz="0 0 0" />
|
||||
</joint>
|
||||
|
||||
|
||||
<xacro:joint_hardware joint_name="ax1" hardware="${hardware}" initial_joint_position="0.0" />
|
||||
<xacro:joint_hardware joint_name="ax2" hardware="${hardware}" initial_joint_position="0.0" />
|
||||
<xacro:joint_hardware joint_name="ax3" hardware="${hardware}" initial_joint_position="0.0" />
|
||||
<xacro:joint_hardware joint_name="ax4" hardware="${hardware}" initial_joint_position="0.0" />
|
||||
<xacro:joint_hardware joint_name="ax5" hardware="${hardware}" initial_joint_position="0.0" />
|
||||
<xacro:joint_hardware joint_name="ax6" hardware="${hardware}" initial_joint_position="0.0" />
|
||||
|
||||
<xacro:if value="${hardware=='gazebo'}">
|
||||
<!-- <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>$(arg simulation_controllers)</parameters>
|
||||
<ros>
|
||||
<namespace>${namespace}</namespace>
|
||||
</ros>
|
||||
</plugin>
|
||||
<plugin filename="VacuumGripper" name="rbs_mill_assist::VacuumGripper">
|
||||
<link_name>Link6</link_name>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
</xacro:if>
|
||||
<gazebo reference="Link6">
|
||||
<sensor name='sensor_contact' type='contact'>
|
||||
<contact>
|
||||
<collision>Link6_collision</collision>
|
||||
</contact>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
|
|
@ -30,12 +30,12 @@
|
|||
<camera>
|
||||
<horizontal_fov>1.047</horizontal_fov>
|
||||
<image>
|
||||
<width>320</width>
|
||||
<height>240</height>
|
||||
<width>1920</width>
|
||||
<height>1080</height>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.1</near>
|
||||
<far>100</far>
|
||||
<far>3</far>
|
||||
</clip>
|
||||
</camera>
|
||||
<always_on>1</always_on>
|
||||
|
|
|
@ -55,7 +55,7 @@
|
|||
</light>
|
||||
|
||||
<include>
|
||||
<pose>-0.3 0.0 0 0 0 0</pose>
|
||||
<pose>-0.35 0.0 0 0 0 0</pose>
|
||||
<uri>model://shildik</uri>
|
||||
</include>
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue