-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathmega3.xacro
142 lines (133 loc) · 5.19 KB
/
mega3.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
<?xml version="1.0"?>
<robot name="mega3" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find megarover_description)/urdf/materials.xacro" />
<xacro:include filename="$(find megarover_description)/urdf/mega3.gazebo" />
<!-- OPTION: LRF TG30 -->
<xacro:include filename="$(find vs_rover_options_description)/urdf/lrf/tg30_mega3.xacro" />
<!-- OPTION: bumper sensor -->
<xacro:include filename="$(find vs_rover_options_description)/urdf/bumper/bumper_mega3.xacro" />
<xacro:bumperbaseboard prefix="front" parent="base_link" xyz="0 0.19 0.02" z_dir="180" />
<xacro:bumperbaseboard prefix="back" parent="base_link" xyz="0 -0.19 0.02" z_dir="0" />
<!-- OPTION: camera stay -->
<xacro:include filename="$(find vs_rover_options_description)/urdf/cam_stay/cam_stay_mega3.xacro" />
<!-- OPTION: Intel Realsense depth camera D435i (camera stay required) -->
<xacro:include filename="$(find vs_rover_options_description)/urdf/depth_cam/_d435i.urdf.xacro" />
<xacro:sensor_d435i parent="cam_mount_link" use_nominal_extrinsics="true">
<origin xyz="0.0295 0 0.0095" rpy="0 0 0" />
</xacro:sensor_d435i>
<!-- OPTION: AMIR 740 (disabled by default because of interference with camera stay)-->
<!-- <xacro:include filename="$(find amir_description)/urdf/amir_for_rover.xacro" />
<joint name="base_fixed" type="fixed">
<origin xyz="0.0 0.03 0.398" rpy="0 0 0" />
<parent link="base_link" />
<child link="link0_1" />
</joint> -->
<link name="base_footprint" />
<joint name="base_joint" type="fixed">
<parent link="base_footprint" />
<child link="base_link" />
<origin xyz="-0.1 0 0" rpy="0 0 -1.5708" />
</joint>
<link name="base_link">
<inertial>
<origin xyz="-0.0001512201285105937 -3.420007213019073e-05 0.08388833658828038" rpy="0 0 0" />
<mass value="11.744482" />
<inertia ixx="0.091465" iyy="0.06435" izz="0.1253"
ixy="0.001018" iyz="-0.002369"
ixz="0.000233" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://megarover_description/meshes/mega3/base_link.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="silver" />
</visual>
<!-- <collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://megarover_description/meshes/mega3/base_link.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision> -->
<collision>
<origin xyz="0 0 0.095" rpy="0 0 0" />
<geometry>
<box size="0.21 0.328 0.11" />
</geometry>
</collision>
<collision>
<origin xyz="0 -0.15 0.033" rpy="0 -1.57 0" />
<geometry>
<cylinder radius="0.0325" length="0.02" />
</geometry>
</collision>
</link>
<joint name="left_wheel_joint" type="continuous">
<origin xyz="-0.136 0.1 0.07" rpy="0 -1.5708 0" />
<parent link="base_link" />
<child link="left_wheel_1" />
<axis xyz="0.0 0.0 1.0" />
</joint>
<link name="left_wheel_1">
<inertial>
<origin xyz="0.0 0.0 0.00213" rpy="0 1.5708 0" />
<mass value="1.239934" />
<inertia ixx="0.002474" iyy="0.00174" izz="0.00174"
ixy="0.000" iyz="0.000"
ixz="-0.000" />
</inertial>
<visual>
<origin xyz="-0.07 -0.1 -0.136" rpy="0 1.5708 0" />
<geometry>
<mesh filename="package://megarover_description/meshes/mega3/left_wheel_1.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="dark_grey" />
</visual>
<collision>
<origin xyz="-0.07 -0.1 -0.136" rpy="0 1.5708 0" />
<geometry>
<mesh filename="package://megarover_description/meshes/mega3/left_wheel_1.stl" scale="0.001 0.001 0.001" />
</geometry>
</collision>
<!-- <collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder radius="0.07" length="0.0435" />
</geometry>
</collision> -->
</link>
<joint name="right_wheel_joint" type="continuous">
<origin xyz="0.136 0.1 0.07" rpy="0 -1.5708 0" />
<parent link="base_link" />
<child link="right_wheel_1" />
<axis xyz="0.0 0.0 1.0" />
</joint>
<link name="right_wheel_1">
<inertial>
<origin xyz="0 0 -0.00213" rpy="0 1.5708 0" />
<mass value="1.239934" />
<inertia ixx="0.002474" iyy="0.00174" izz="0.00174"
ixy="-0.000" iyz="-0.000"
ixz="-0.000" />
</inertial>
<visual>
<origin xyz="-0.07 -0.1 0.136" rpy="0 1.5708 0" />
<geometry>
<mesh filename="package://megarover_description/meshes/mega3/right_wheel_1.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="dark_grey" />
</visual>
<collision>
<origin xyz="-0.07 -0.1 0.136" rpy="0 1.5708 0" />
<geometry>
<mesh filename="package://megarover_description/meshes/mega3/right_wheel_1.stl" scale="0.001 0.001 0.001" />
</geometry>
</collision>
<!-- <collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder radius="0.07" length="0.0435" />
</geometry>
</collision> -->
</link>
</robot>