Browse Source

Mitski URDF xacros corrected

pull/75/head
Mohamed Fazil 2 years ago
parent
commit
afad147580
6 changed files with 80 additions and 29 deletions
  1. +4
    -4
      stretch_description/urdf/stretch_aruco.xacro
  2. +1
    -0
      stretch_description/urdf/stretch_d435i.xacro
  3. +1
    -1
      stretch_description/urdf/stretch_description.xacro
  4. +2
    -2
      stretch_description/urdf/stretch_laser_range_finder.xacro
  5. +57
    -7
      stretch_description/urdf/stretch_mitski.xacro
  6. +15
    -15
      stretch_description/urdf/stretch_respeaker.xacro

+ 4
- 4
stretch_description/urdf/stretch_aruco.xacro View File

@ -5,7 +5,7 @@
name="link_aruco_right_base">
<inertial>
<origin
xyz="0 0 -5.00000000014378E-07"
xyz="1.3878E-17 0 -0.000125"
rpy="0 0 0" />
<mass
value="3.59999999990368E-06" />
@ -46,7 +46,7 @@
name="joint_aruco_right_base"
type="fixed">
<origin
xyz="-0.00500000000000014 -0.1304972 0.1597482"
xyz="-0.0015028 -0.1304972 0.1597482"
rpy="0 0 -1.5707963267949" />
<parent
link="base_link" />
@ -61,7 +61,7 @@
name="link_aruco_left_base">
<inertial>
<origin
xyz="0 0 -5.00000000014378E-07"
xyz="2.7756E-17 0 -0.000125"
rpy="0 0 0" />
<mass
value="3.59999999990368E-06" />
@ -171,7 +171,7 @@
name="link_aruco_top_wrist">
<inertial>
<origin
xyz="1.11022302462516E-16 3.05311331771918E-16 -0.00012499999999821"
xyz="-1.3531E-15 -3.4972E-15 -0.000125"
rpy="0 0 0" />
<mass
value="0" />

+ 1
- 0
stretch_description/urdf/stretch_d435i.xacro View File

@ -15,6 +15,7 @@
xyz="0.03 -0.0122 0.0182"
rpy="0.0 0.0 0.0" />
</xacro:sensor_d435i>
</robot>

+ 1
- 1
stretch_description/urdf/stretch_description.xacro View File

@ -5,7 +5,7 @@
<!--<xacro:include filename="stretch_gripper_with_puller.xacro" />-->
<!--<xacro:include filename="stretch_dry_erase_marker.xacro" />-->
<!--<xacro:include filename="stretch_main.xacro" />-->
<!-- <xacro:include filename="stretch_main.xacro" />-->
<xacro:include filename="stretch_mitski.xacro" />
<xacro:include filename="stretch_aruco.xacro" />
<xacro:include filename="stretch_d435i.xacro" />

+ 2
- 2
stretch_description/urdf/stretch_laser_range_finder.xacro View File

@ -46,8 +46,8 @@
name="joint_laser"
type="fixed">
<origin
xyz="0.000502800000000914 0 0.1664"
rpy="0 0 -3.14159265358979" />
xyz="0.004 0 0.1664"
rpy="0 0 3.1416" />
<parent
link="base_link" />
<child

stretch_description/urdf/stretch_mitsksi.xacro → stretch_description/urdf/stretch_mitski.xacro View File

@ -90,7 +90,7 @@
<joint
name="joint_right_wheel"
type="revolute">
type="continuous">
<origin
xyz="0 -0.17035 0.0508"
rpy="-1.5708 1.2717E-16 4.8006E-17" />
@ -146,7 +146,7 @@
<joint
name="joint_left_wheel"
type="revolute">
type="continuous">
<origin
xyz="0 0.17035 0.0508"
rpy="-1.5708 2.6317E-16 -8.2057E-19" />
@ -159,6 +159,57 @@
<dynamics damping="${joint_damping}" friction="${joint_friction}" spring_reference="${joint_spring_reference}" spring_stiffness="{joint_spring_stiffness}"/>
</joint>
<link name="caster_link">
<collision>
<geometry>
<sphere radius="0.032"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/omni_wheel_m.STL" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
</material>
</visual>
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia
ixx="0.001"
ixy="0"
ixz="0"
iyy="0.001"
iyz="0"
izz="0.001" />
</inertial>
</link>
<joint name="caster_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_link"/>
<origin xyz="-0.245 0.0 0.032" rpy="${-M_PI/2} 0 0"/>
<axis xyz="0 0 1" />
</joint>
<link
name="link_mast">
<inertial>
@ -260,7 +311,7 @@
type="prismatic">
<origin
xyz="-0.037385 0.1666 0"
rpy="1.5708 1.5708 0" />
rpy="-1.5708 1.5708 0" />
<parent
link="link_mast" />
<child
@ -381,7 +432,7 @@
link="link_arm_l3" />
<axis
xyz="0 0 1" />
<!-- 0.13 = 0.52/4-->
<!-- 0.13 = 0.52/4-->
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
</joint>
@ -556,7 +607,6 @@
<limit effort="100" lower="0.0" upper="0.13" velocity="1.0"/>
</joint>
<link
name="link_wrist_yaw">
<inertial>
@ -603,7 +653,7 @@
type="revolute">
<origin
xyz="0.0830000000000654 -0.0307500000000129 0"
rpy="-1.5707963267949 -6.34174103868745E-15 3.14159265358978" />
rpy="1.5708 4.2595E-14 2.6415E-15"/>
<parent
link="link_arm_l0" />
<child
@ -665,7 +715,7 @@
type="fixed">
<origin
xyz="0 1.33 0"
rpy="1.5707963267949 -1.5707963267949 0" />
rpy="1.5707963267949 -1.5707963267949 3.1416" />
<parent
link="link_mast" />
<child

+ 15
- 15
stretch_description/urdf/stretch_respeaker.xacro View File

@ -1,20 +1,21 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_respeaker">
<link name="respeaker_base">
<link
name="respeaker_base">
<inertial>
<origin
xyz="-0.00078082896792734 0.00765742173486017 -0.0042488298301937"
xyz="-0.003809 -0.0023075 -0.012854"
rpy="0 0 0" />
<mass
value="0.00969129410417277" />
value="0.015643" />
<inertia
ixx="8.95656300428405E-07"
ixy="2.67330745809535E-08"
ixz="-3.84519793580934E-08"
iyy="4.0421099617056E-07"
iyz="3.15533542838673E-07"
izz="7.08282597118018E-07" />
ixx="1.0075E-06"
ixy="-5.4396E-08"
ixz="-2.8652E-07"
iyy="1.0569E-06"
iyz="-1.8463E-07"
izz="1.1947E-07" />
</inertial>
<visual>
<origin
@ -22,12 +23,12 @@
rpy="0 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/link_respeaker.STL" />
filename="package://stretch_description/meshes/respeaker_base.STL" />
</geometry>
<material
name="">
<color
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
@ -36,7 +37,7 @@
rpy="0 0 0" />
<geometry>
<mesh
filename="package://stretch_description/meshes/link_respeaker.STL" />
filename="package://stretch_description/meshes/respeaker_base.STL" />
</geometry>
</collision>
</link>
@ -44,10 +45,9 @@
<joint
name="joint_respeaker"
type="fixed">
<!-- rpy=" ? rotate_sound_source_direction ? " -->
<origin
xyz="1.09074743137871E-05 1.36992 0.00303572796911382"
rpy="1.57079632679553 0.0 3.14159265358916" />
xyz="0 1.37236408874452 0.00303065898329655"
rpy="-1.5707963267949 -0.698131700797725 4.93295812652799E-16" />
<parent
link="link_mast" />
<child

Loading…
Cancel
Save