-
Notifications
You must be signed in to change notification settings - Fork 0
/
atrv.xacro
100 lines (93 loc) · 2.74 KB
/
atrv.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="atrv">
<xacro:property name="width" value=".39" />
<xacro:property name="len" value=".64" />
<xacro:property name="wradius" value=".15"/>
<xacro:property name="wthick" value=".1"/>
<link name="base_link">
<visual>
<geometry>
<box size="${len} ${width} .22"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="${len} ${width} .22"/>
</geometry>
</collision>
</link>
<link name="base_footprint">
<visual>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="top_cover">
<visual>
<geometry>
<box size="${len} ${width} .25"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="${len} ${width} .25"/>
</geometry>
</collision>
</link>
<joint name="base_to_top_cover" type="fixed">
<parent link="base_link"/>
<child link="top_cover"/>
<origin xyz="0 0 .1"/>
</joint>
<joint name="base_footprint_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.150"/>
<parent link="base_footprint"/>
<child link="base_link"/>
</joint>
<xacro:macro name="wheel" params="prefix fb lr">
<!-- note front => fb = 1, left => lr = 1 -->
<link name="${prefix}_wheel">
<visual>
<geometry>
<cylinder length="${wthick}" radius="${wradius}"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="${wthick}" radius="${wradius}"/>
</geometry>
</collision>
</link>
<joint name="base_to_${prefix}_wheel" type="continuous">
<parent link="base_link"/>
<child link="${prefix}_wheel"/>
<axis xyz="0 0 -1"/>
<origin rpy="1.57075 0 0" xyz="${fb*.19} ${lr*.25} -.05" />
<limit effort="5.0" velocity="5.0"/>
<joint_properties damping="2.0" friction="{steer_joint_friction}"/>
</joint>
<transmission name="${prefix}_joint_wheel_steer_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="$base_to_${prefix}_wheel"/>
<actuator name="${prefix}_joint_wheel_steer_motor">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>100.0</mechanicalReduction>
<motorTorqueConstant>1</motorTorqueConstant>
</actuator>
</transmission>
</xacro:macro>
<xacro:wheel prefix="front_left" fb="1" lr="1" />
<xacro:wheel prefix="front_right" fb="1" lr="-1" />
<xacro:wheel prefix="rear_left" fb="-1" lr="1" />
<xacro:wheel prefix="rear_right" fb="-1" lr="-1" />
</robot>