webstudio/web_p/robot_builder/robot.xml

346 lines
26 KiB
XML
Raw Normal View History

2024-07-03 15:25:51 +03:00
<robot name="rbs_arm">n <link name="world" />n <joint name="base_link_joint" type="fixed">n <origin
rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0" />n <parent
link="world" />n <child link="base_link" />n </joint>n <link name="base_link">n <collision
name="base_link_collision">n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.00000" />n <geometry>n <mesh
filename="start_link.stl"
scale="1.00000 1.00000 1.00000" />n </geometry>n </collision> n <inertial>n <inertia
ixx="0.00503302470272442" ixy="0.000343817346410954" ixz="-4.74990755448368E-06"
iyy="0.00337962410057753" iyz="-2.3099255620051E-05" izz="0.00405858207282473" />n <origin
rpy="0.00000 0.00000 0.00000"
xyz="-0.000297002857922682 0.0964721185617698 -0.000361033370053684" /> n <mass
value="1.88031044620482" />n </inertial>n <visual name="base_link_visual">n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.00000" />n <geometry> n <mesh
filename="start_link.dae"
scale="1.00000 1.00000 1.00000" />n </geometry>n </visual>n </link>n <gazebo
reference="base_link">n <visual>n <material>n <diffuse>0.8 0.8 0.8 1</diffuse>n <specular>0.6
0.6
0.6 1</specular>n <ambient>1.0 1.0 1.0</ambient>n <lighting>true</lighting>n <emissive>0
0 0
1</emissive>n <pbr>n <metal>n <albedo_map>
/base_link_d.png</albedo_map> n <normal_map>
/base_link_n.png</normal_map>
n <ambient_occlusion_map>
/base_link_ao.png</ambient_occlusion_map>
n <roughness_map>
/base_link_r.png</roughness_map>
n </metal>n </pbr>n </material>n </visual>n </gazebo>n <joint name="fork0_link_joint"
type="revolute">n <limit
effort="78" lower="-6.14159" upper="6.14159" velocity="0.52" />n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.17833" />n <parent link="base_link" />
n <child link="fork0_link" />n <axis xyz="0 0 1" />n </joint>n <link name="fork0_link">n <collision
name="fork0_link_collision">n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.00000 0.00000" />n <geometry>n <mesh
filename="fork_link.stl"
scale="1.00000 1.00000 1.00000" />n </geometry>n </collision> n <inertial>n <inertia
ixx="0.00367804533572758" ixy="1.04277925521833E-05" ixz="-0.00149971410403071"
iyy="0.00415208849477534" iyz="-0.00122" izz="0.00329" />n <origin
rpy="0.00000 0.00000 0.00000"
xyz="0.0472051139085306 0.00208890925682996 0.0557265410642575" /> n <mass
value="1.12472202892859" />n </inertial>n <visual name="fork0_link_visual">n <origin
rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 -0.00000 0.00000" />n <geometry> n <mesh
filename="fork_link.dae"
scale="1.00000 1.00000 1.00000" />n </geometry>n </visual>n </link>n <ros2_control
name="fork0_link_joint_hardware_interface" type="actuator">n <hardware>n <plugin>
ign_ros2_control/IgnitionSystem</plugin>n </hardware> n <joint name="fork0_link_joint">n <command_interface
name="position">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <command_interface
name="velocity">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <!-- WARN When this active a robot falls
down -->n <!-- <command_interface
name="effort"/> -->n <!-- <param name="p">${p}</param> -->n <!-- <param name="d">${d}</param> -->n <!-- <command_interface
name="effort"/> -->n <state_interface
name="position" />n <state_interface
name="velocity" />n <state_interface name="effort" />n </joint>n </ros2_control>n <gazebo
reference="fork0_link">n <visual>n <material>n <diffuse>0.8 0.8 0.8 1</diffuse>n <specular>0.6
0.6
0.6 1</specular>n <ambient>1.0 1.0 1.0</ambient>n <lighting>true</lighting>n <emissive>0
0 0
1</emissive>n <pbr>n <metal>n <albedo_map>
/fork_d.png</albedo_map>
n <normal_map>
/fork_n.png</normal_map>
n <ambient_occlusion_map>
/fork_ao.png</ambient_occlusion_map>
n <roughness_map>
/fork_r.png</roughness_map>
n </metal>n </pbr>n </material>n </visual>n </gazebo>n <joint name="main0_link_joint"
type="revolute">n <limit
effort="78" lower="-1.5708" upper="3.14159" velocity="0.52" />n <origin
rpy="-0.00000 0.00000 0.00000" xyz="0.10000 0.00000 0.09400" />n <parent
link="fork0_link" /> n <child link="main0_link" />n <axis xyz="0 1 0" />n </joint>n <link
name="main0_link">n <collision name="main0_link_collision">n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.00000" />n <geometry>n <mesh
filename="main_link.stl"
scale="1.00000 1.00000 1.00000" />n </geometry>n </collision> n <inertial>n <inertia
ixx="0.00315699373090845" ixy="2.84713820858537E-05" ixz="-7.01601261191721E-05"
iyy="0.00343729241263707" iyz="-0.000101485203138902" izz="0.00125534890134052" />n <origin
rpy="0.00000 0.00000 0.00000"
xyz="0.00186712264682627 -0.000412152188777604 0.0516389446895805" /> n <mass
value="1.58688811563124" />n </inertial>n <visual name="main0_link_visual">n <origin
rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 0.00000 0.00000" />n <geometry> n <mesh
filename="main_link.dae"
scale="1.00000 1.00000 1.00000" />n </geometry>n </visual>n </link>n <ros2_control
name="main0_link_joint_hardware_interface" type="actuator">n <hardware>n <plugin>
ign_ros2_control/IgnitionSystem</plugin>n </hardware> n <joint name="main0_link_joint">n <command_interface
name="position">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <command_interface
name="velocity">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <!-- WARN When this active a robot falls
down -->n <!-- <command_interface
name="effort"/> -->n <!-- <param name="p">${p}</param> -->n <!-- <param name="d">${d}</param> -->n <!-- <command_interface
name="effort"/> -->n <state_interface
name="position" />n <state_interface
name="velocity" />n <state_interface name="effort" />n </joint>n </ros2_control>n <gazebo
reference="main0_link">n <visual>n <material>n <diffuse>0.8 0.8 0.8 1</diffuse>n <specular>0.6
0.6
0.6 1</specular>n <ambient>1.0 1.0 1.0</ambient>n <lighting>true</lighting>n <emissive>0
0 0
1</emissive>n <pbr>n <metal>n <albedo_map>
/main_link_d.png</albedo_map>
n <normal_map>
/main_link_n.png</normal_map>
n <ambient_occlusion_map>
/main_link_ao.png</ambient_occlusion_map>
n <roughness_map>
/main_link_r.png</roughness_map>
n </metal>n </pbr>n </material>n </visual>n </gazebo>n <joint name="fork1_link_joint"
type="revolute">n <limit
effort="78" lower="-6.14159" upper="6.14159" velocity="0.52" />n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.13300" />n <parent
link="main0_link" /> n <child link="fork1_link" />n <axis xyz="0 0 1" />n </joint>n <link
name="fork1_link">n <collision name="fork1_link_collision">n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.00000 0.00000" />n <geometry>n <mesh
filename="fork_link.stl"
scale="1.00000 1.00000 1.00000" />n </geometry>n </collision> n <inertial>n <inertia
ixx="0.00367804533572758" ixy="1.04277925521833E-05" ixz="-0.00149971410403071"
iyy="0.00415208849477534" iyz="-0.00122" izz="0.00329" />n <origin
rpy="0.00000 0.00000 0.00000"
xyz="0.0472051139085306 0.00208890925682996 0.0557265410642575" /> n <mass
value="1.12472202892859" />n </inertial>n <visual name="fork1_link_visual">n <origin
rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 -0.00000 0.00000" />n <geometry> n <mesh
filename="fork_link.dae"
scale="1.00000 1.00000 1.00000" />n </geometry>n </visual>n </link>n <ros2_control
name="fork1_link_joint_hardware_interface" type="actuator">n <hardware>n <plugin>
ign_ros2_control/IgnitionSystem</plugin>n </hardware> n <joint name="fork1_link_joint">n <command_interface
name="position">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <command_interface
name="velocity">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <!-- WARN When this active a robot falls
down -->n <!-- <command_interface
name="effort"/> -->n <!-- <param name="p">${p}</param> -->n <!-- <param name="d">${d}</param> -->n <!-- <command_interface
name="effort"/> -->n <state_interface
name="position" />n <state_interface
name="velocity" />n <state_interface name="effort" />n </joint>n </ros2_control>n <gazebo
reference="fork1_link">n <visual>n <material>n <diffuse>0.8 0.8 0.8 1</diffuse>n <specular>0.6
0.6
0.6 1</specular>n <ambient>1.0 1.0 1.0</ambient>n <lighting>true</lighting>n <emissive>0
0 0
1</emissive>n <pbr>n <metal>n <albedo_map>
/fork_d.png</albedo_map>
n <normal_map>
/fork_n.png</normal_map>
n <ambient_occlusion_map>
/fork_ao.png</ambient_occlusion_map>
n <roughness_map>
/fork_r.png</roughness_map>
n </metal>n </pbr>n </material>n </visual>n </gazebo>n <joint name="main1_link_joint"
type="revolute">n <limit
effort="78" lower="-1.5708" upper="3.14159" velocity="0.52" />n <origin
rpy="-0.00000 0.00000 0.00000" xyz="0.10000 0.00000 0.09400" />n <parent
link="fork1_link" /> n <child link="main1_link" />n <axis xyz="0 1 0" />n </joint>n <link
name="main1_link">n <collision name="main1_link_collision">n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.00000" />n <geometry>n <mesh
filename="main_link.stl"
scale="1.00000 1.00000 1.00000" />n </geometry>n </collision> n <inertial>n <inertia
ixx="0.00315699373090845" ixy="2.84713820858537E-05" ixz="-7.01601261191721E-05"
iyy="0.00343729241263707" iyz="-0.000101485203138902" izz="0.00125534890134052" />n <origin
rpy="0.00000 0.00000 0.00000"
xyz="0.00186712264682627 -0.000412152188777604 0.0516389446895805" /> n <mass
value="1.58688811563124" />n </inertial>n <visual name="main1_link_visual">n <origin
rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 0.00000 0.00000" />n <geometry> n <mesh
filename="main_link.dae"
scale="1.00000 1.00000 1.00000" />n </geometry>n </visual>n </link>n <ros2_control
name="main1_link_joint_hardware_interface" type="actuator">n <hardware>n <plugin>
ign_ros2_control/IgnitionSystem</plugin>n </hardware> n <joint name="main1_link_joint">n <command_interface
name="position">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <command_interface
name="velocity">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <!-- WARN When this active a robot falls
down -->n <!-- <command_interface
name="effort"/> -->n <!-- <param name="p">${p}</param> -->n <!-- <param name="d">${d}</param> -->n <!-- <command_interface
name="effort"/> -->n <state_interface
name="position" />n <state_interface
name="velocity" />n <state_interface name="effort" />n </joint>n </ros2_control>n <gazebo
reference="main1_link">n <visual>n <material>n <diffuse>0.8 0.8 0.8 1</diffuse>n <specular>0.6
0.6
0.6 1</specular>n <ambient>1.0 1.0 1.0</ambient>n <lighting>true</lighting>n <emissive>0
0 0
1</emissive>n <pbr>n <metal>n <albedo_map>
/main_link_d.png</albedo_map>
n <normal_map>
/main_link_n.png</normal_map>
n <ambient_occlusion_map>
/main_link_ao.png</ambient_occlusion_map>
n <roughness_map>
/main_link_r.png</roughness_map>
n </metal>n </pbr>n </material>n </visual>n </gazebo>n <joint name="fork2_link_joint"
type="revolute">n <limit
effort="78" lower="-6.14159" upper="6.14159" velocity="0.52" />n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 0.00000 0.13300" />n <parent
link="main1_link" /> n <child link="fork2_link" />n <axis xyz="0 0 1" />n </joint>n <link
name="fork2_link">n <collision name="fork2_link_collision">n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.00000 0.00000" />n <geometry>n <mesh
filename="fork_link.stl"
scale="1.00000 1.00000 1.00000" />n </geometry>n </collision> n <inertial>n <inertia
ixx="0.00367804533572758" ixy="1.04277925521833E-05" ixz="-0.00149971410403071"
iyy="0.00415208849477534" iyz="-0.00122" izz="0.00329" />n <origin
rpy="0.00000 0.00000 0.00000"
xyz="0.0472051139085306 0.00208890925682996 0.0557265410642575" /> n <mass
value="1.12472202892859" />n </inertial>n <visual name="fork2_link_visual">n <origin
rpy="0.00000 -0.00000 -0.00000" xyz="0.00000 -0.00000 0.00000" />n <geometry> n <mesh
filename="fork_link.dae"
scale="1.00000 1.00000 1.00000" />n </geometry>n </visual>n </link>n <ros2_control
name="fork2_link_joint_hardware_interface" type="actuator">n <hardware>n <plugin>
ign_ros2_control/IgnitionSystem</plugin>n </hardware> n <joint name="fork2_link_joint">n <command_interface
name="position">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <command_interface
name="velocity">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <!-- WARN When this active a robot falls
down -->n <!-- <command_interface
name="effort"/> -->n <!-- <param name="p">${p}</param> -->n <!-- <param name="d">${d}</param> -->n <!-- <command_interface
name="effort"/> -->n <state_interface
name="position" />n <state_interface
name="velocity" />n <state_interface name="effort" />n </joint>n </ros2_control>n <gazebo
reference="fork2_link">n <visual>n <material>n <diffuse>0.8 0.8 0.8 1</diffuse>n <specular>0.6
0.6
0.6 1</specular>n <ambient>1.0 1.0 1.0</ambient>n <lighting>true</lighting>n <emissive>0
0 0
1</emissive>n <pbr>n <metal>n <albedo_map>
/fork_d.png</albedo_map>
n <normal_map>
/fork_n.png</normal_map>
n <ambient_occlusion_map>
/fork_ao.png</ambient_occlusion_map>
n <roughness_map>
/fork_r.png</roughness_map>
n </metal>n </pbr>n </material>n </visual>n </gazebo>n <joint name="ee_link_joint"
type="revolute">n <limit
effort="78" lower="-1.5708" upper="3.14159" velocity="0.52" />n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.10000 0.00000 0.09473" />n <parent
link="fork2_link" /> n <child link="ee_link" />n <axis xyz="0 1 0" />n </joint>n <joint
name="tool0_joint" type="fixed">n <origin rpy="0.00000 0.00000 0.00000"
xyz="0.00000 0.00000 0.11000" />n <parent link="ee_link" />n <child link="tool0" />n </joint>
n <link name="tool0" />n <link
name="ee_link">n <collision name="ee_link_collision">n <origin
rpy="-0.00000 0.00000 -0.00000" xyz="0.00000 -0.00000 0.00000" />n <geometry>n <mesh
filename="ee_link.stl"
scale="1.00000 1.00000 1.00000" />n </geometry>n </collision>n <inertial>n <inertia
ixx="0.00147695259043549" ixy="-2.66894744420299E-05"
ixz="-4.40871314563273E-05" iyy="0.00135500487881796" iyz="-3.19001462979333E-05"
izz="0.00087582892706912" />n <origin rpy="0.00000 0.00000 0.00000"
xyz="-9.7531539777207E-06 -0.000888494418875867 0.0342332199538358" />n <mass
value="1.88031044620482" />n </inertial> n <visual name="ee_link_visual">n <origin
rpy="0.00000 0.00000 0.00000" xyz="0.00000 -0.00000 0.00000" />n <geometry>n <mesh
filename="ee_link.dae"
scale="1.00000 1.00000 1.00000" />n </geometry> n </visual>n </link>n <ros2_control
name="ee_link_joint_hardware_interface" type="actuator">n <hardware>n <plugin>
ign_ros2_control/IgnitionSystem</plugin>n </hardware>n <joint name="ee_link_joint">n <command_interface
name="position">n <!-- <param name="min">-1</param> -->n <!-- <param name="max">1</param> -->n </command_interface>n <command_interface name="velocity">n <!--
<param
name="min">-1</param> -->n <!--
<param
name="max">1</param> -->n </command_interface>
n <!-- WARN When this active a robot falls down -->n <!-- <command_interface name="effort"/> -->n <!-- <param name="p">${p}</param> -->n <!-- <param name="d">${d}</param> -->n <!-- <command_interface name="effort"/> -->n <state_interface name="position" />n <state_interface name="velocity" />n <state_interface
name="effort" />n </joint>n </ros2_control>n <gazebo reference="ee_link">n <visual>n <material>
n <diffuse>0.8 0.8 0.8 1</diffuse>n <specular>0.6 0.6 0.6 1</specular>n <ambient>1.0
1.0 1.0</ambient>n <lighting>true</lighting>n <emissive>0 0 0 1</emissive>n <pbr>
n <metal>n <albedo_map>
/ee_link_d.png</albedo_map>
n <normal_map>
/ee_link_n.png</normal_map>
n <ambient_occlusion_map>
/ee_link_ao.png</ambient_occlusion_map>
n <roughness_map>
/ee_link_r.png</roughness_map>
n </metal>n </pbr>n </material>n </visual>n </gazebo>n <!-- END robot description -->n <ros2_control name="rbs_gripper_gazebo"
type="system">n <!-- Plugins -->n <hardware>n <plugin>ign_ros2_control/IgnitionSystem</plugin>n </hardware>n <!--
Joint interfaces -->
n <joint name="rbs_gripper_rot_base_joint">n <state_interface name="position">n <param
name="initial_value">0.000</param>n </state_interface> n <command_interface
name="position" />n <command_interface name="velocity" />n <command_interface
name="effort" />n <state_interface name="velocity" />n <state_interface
name="effort" />n </joint>n <joint
name="rbs_gripper_r_finger_joint">n <state_interface name="position">n <param
name="initial_value">0.000</param>n </state_interface> n <command_interface
name="position" />n <command_interface name="velocity" />n <command_interface
name="effort" />n <state_interface name="velocity" />n <state_interface
name="effort" />n </joint>n <joint
name="rbs_gripper_l_finger_joint">n <param name="mimic">rbs_gripper_r_finger_joint</param>
n <param name="multiplier">1</param> n </joint>n </ros2_control>n <joint
name="rbs_gripper_gripper_base_joint" type="fixed">n <origin rpy="0 0 0" xyz="0 0 0" />n <parent
link="tool0" />n <child link="rbs_gripper_gripper_base_link" />n </joint>n <link
name="rbs_gripper_gripper_base_link">n <inertial>n <origin rpy="0 0 0"
xyz="0.000364704367134063 0.0336387482840125 0.0593891203954369" />n <mass
value="1.13983632906086" />n <inertia ixx="0.00107738806534129"
ixy="-1.09841172461737E-05" ixz="2.62750043451545E-06" iyy="0.000717388573992299"
iyz="-2.95426438182787E-05" izz="0.00115777179755934" /> n </inertial>n <visual>n <origin
rpy="0 0 0" xyz="0 0 0" />n <geometry>n <mesh
filename="base.dae" /> n </geometry> n <material name="rbs_gripper_material">n <color
rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />n </material>n </visual>
n <collision>n <origin
rpy="0 0 0" xyz="0 0 0" />n <geometry>n <mesh
filename="base.stl" /> n </geometry>n </collision>n </link> n <link
name="rbs_gripper_rot_base_link">n <inertial>n <origin
rpy="0 0 0" xyz="6.79110135283868E-11 -3.80956832067611E-10 0.00775394473595793" />n <mass
value="0.161003401535982" />n <inertia ixx="0.00011089089949771"
ixy="5.01335040610636E-06" ixz="1.74608448389267E-14" iyy="0.000105515893695012"
iyz="-2.03282362854432E-14" izz="0.000206912001661452" />n </inertial>n <visual>n <origin
rpy="0 0 0"
xyz="0 0 0" />n <geometry>n <mesh
filename="rotor.dae" /> n </geometry>n <material name="rbs_gripper_material">n <color
rgba="0.250980392156863 0.250980392156863 0.250980392156863 1" />n </material>n </visual>
n <collision>n <origin rpy="0 0 0" xyz="0 0 0" />n <geometry> n <mesh
filename="rotor.stl" /> n </geometry>n </collision>n </link>n <joint
name="rbs_gripper_rot_base_joint" type="revolute"> n <origin
rpy="0 0 0" xyz="0 0 0.10861" />n <parent link="rbs_gripper_gripper_base_link" />n <child
link="rbs_gripper_rot_base_link" />n <axis xyz="0 0 1" />n <limit
effort="78" lower="-3.14159" upper="3.14159" velocity="0.52" />n </joint>n <link
name="rbs_gripper_l_finger_link">n <inertial>n <origin
rpy="0 0 0" xyz="0.00399878118534129 0.0187296413885176 -0.0777776233934166" />n <mass
value="0.0601996441483964" />n <inertia ixx="4.18533281165612E-05"
ixy="-7.11657995951147E-06" ixz="1.81029223490065E-05" iyy="7.89886367868258E-05"
iyz="1.20542845942065E-05"
izz="5.16740841307935E-05" />n </inertial>n <visual>n <origin rpy="0 0 0"
xyz="0 0 0" />n <geometry>n <mesh
filename="finger.dae" /> n </geometry>n <material name="rbs_gripper_material">n <color
rgba="0.752941176470588 0 0 1" />n </material> n </visual>n <collision>n <origin
rpy="0 0 0" xyz="0 0 0" />n <geometry>n <mesh
filename="finger.stl" /> n </geometry> n </collision>n </link>n <joint
name="rbs_gripper_l_finger_joint" type="prismatic"> n <origin rpy="0 0 1.5708"
xyz="0 0 0.1071" />n <parent
link="rbs_gripper_rot_base_link" />n <child link="rbs_gripper_l_finger_link" />n <axis
xyz="-1 0 0" />n <limit effort="10" lower="0" upper="0.064"
velocity="0.53" />n <mimic joint="rbs_gripper_r_finger_joint" multiplier="1" />n </joint>
n <link name="rbs_gripper_r_finger_link">n <inertial> n <origin rpy="0 0 0"
xyz="0.0039988 -0.077778 -0.01873" />n <mass value="0.0602" />n <inertia
ixx="4.1853E-05" ixy="1.8103E-05" ixz="7.1166E-06" iyy="5.1674E-05"
iyz="-1.2054E-05" izz="7.8989E-05" />n </inertial>n <visual>n <origin rpy="0 0 0"
xyz="0 0 0" />n <geometry>n <mesh
filename="finger.dae" /> n </geometry>n <material name="rbs_gripper_material">n <color
rgba="0.75294 0 0 1" />n </material> n </visual>n <collision>n <origin
rpy="0 0 0" xyz="0 0 0" />n <geometry>n <mesh
filename="finger.stl" /> n </geometry> n </collision>n </link>n <joint
name="rbs_gripper_r_finger_joint" type="prismatic"> n <origin rpy="0 0 -1.5708"
xyz="0 0 0.1071" />n <parent
link="rbs_gripper_rot_base_link" />n <child link="rbs_gripper_r_finger_link" />n <axis
xyz="-1 0 0" />n <limit effort="10" lower="0" upper="0.064"
velocity="0.53" />n </joint>n <link name="gripper_grasp_point" />n <joint
name="rbs_gripper_gripper_tool0_joint" type="fixed">n <origin rpy="0 0 0"
xyz="0 0 0.09139" />n <parent link="rbs_gripper_rot_base_link" />n <child
link="gripper_grasp_point" />n </joint>n <ros2_control name="fts_sensor"
type="sensor">n <hardware>n <plugin>ign_ros2_control/IgnitionFts</plugin>n </hardware>n <sensor
name="fts_sensor">n <state_interface name="force.x" />n <state_interface name="force.y" />
n <state_interface
name="force.z" />n <state_interface name="torque.x" />n <state_interface
name="torque.y" />n <state_interface
name="torque.z" />n </sensor>n </ros2_control>n <gazebo reference="tool0_joint">n <preserveFixedJoint>
true</preserveFixedJoint>n <sensor name="fts_sensor" type="force_torque">n <always_on>true</always_on>
n <update_rate>
50</update_rate>n <visualize>true</visualize>n <topic>ft_data</topic>n <force_torque>
n <frame>
sensor</frame>n <measure_direction>child_to_parent</measure_direction>n </force_torque>
n </sensor> n </gazebo>n <gazebo>n <plugin filename="libign_ros2_control-system.so"
name="ign_ros2_control::IgnitionROS2ControlPlugin">n <parameters>
/home/idontsudo/robossembler_ws/install/rbs_arm/share/rbs_arm/config/rbs_arm0_controllers.yaml</parameters>
n <ros>n <namespace></namespace>n </ros>n </plugin>n </gazebo>n</robot>