This repository has been archived by the owner on Nov 9, 2021. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 29
/
lawn_tractor.urdf.xacro
99 lines (85 loc) · 2.54 KB
/
lawn_tractor.urdf.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
<?xml version="1.0"?>
<robot name="lawn_tractor" xmlns:xacro='http://www.ros.org/wiki/xacro'>
<!-- TODO: collision link element to be added -->
<!-- TODO: inertial link element to be added -->
<!-- define base link, center of rear axle for an ackermann vehicle -->
<link name="base_link">
<visual>
<origin xyz='0.55 0 0' rpy='0 0 ${pi}' />
<geometry>
<mesh filename="package://lawn_tractor_sim/meshes/lawn_tractor.dae" scale='1 1 1'/>
</geometry>
</visual>
</link>
<!-- define base footprint (virtual link) -->
<link name="base_footprint" />
<!-- define gps link -->
<link name="gps">
<visual>
<origin xyz='0 0 0' rpy='0 0 0' />
<geometry>
<sphere radius='0.05' />
</geometry>
<material name='red'>
<color rgba='1 0 0 0.5' />
</material>
</visual>
</link>
<!-- define camera link -->
<link name="camera">
<visual>
<origin xyz='0 0 0' rpy='0 0 0' />
<geometry>
<sphere radius='0.05' />
</geometry>
<material name='red'>
<color rgba='1 0 0 0.5' />
</material>
</visual>
</link>
<!-- define ultrasonic sensor link -->
<link name="base_laser_link">
<visual>
<origin xyz='0 0 0' rpy='0 0 0' />
<geometry>
<sphere radius='0.05' />
</geometry>
<material name='red'>
<color rgba='1 0 0 0.5' />
</material>
</visual>
</link>
<!-- xacro macro definition -->
<!-- default inertia -->
<xacro:macro name='default_inertia' params='mass x:=0 y:=0 z:=0'>
<inertial>
<origin xyz='${x} ${y} ${z}' />
<mass value='${mass}' />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
</inertial>
</xacro:macro>
<!-- define base footprint joint -->
<joint name="base_footprint_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0 0 0.25" rpy="0 0 0" />
</joint>
<!-- define gps joint -->
<joint name="gps_joint" type="fixed">
<parent link="base_link"/>
<child link="gps"/>
<origin xyz="1.25 0 1.0" rpy="0 0 0" />
</joint>
<!-- define camera joint -->
<joint name="camera_joint" type="fixed">
<parent link="base_link"/>
<child link="camera"/>
<origin xyz="1.5 0 0.5" rpy="${-pi/2} 0 ${-pi/2}" />
</joint>
<!-- define ultrasonic sensor joint -->
<joint name="range_joint" type="fixed">
<parent link="base_link"/>
<child link="base_laser_link"/>
<origin xyz="1.5 0 0.75" rpy="0 0 0" />
</joint>
</robot>