]> rtime.felk.cvut.cz Git - hubacji1/simple-stage.git/blob - models/tx2-auto-3.model
Copy tx2 auto model from f1tenth repo
[hubacji1/simple-stage.git] / models / tx2-auto-3.model
1 # Stage simulator model of 'tx2-auto-3'
2 # Author: Jaroslav Klapálek
3
4 # Sensors (lidar)
5 define ust10lx ranger
6 (
7         sensor(
8                 range [ 0.0  10.0 ]
9                 fov 270.0
10                 samples 3243
11         )
12
13         color "orange"
14 )
15
16 # Sensors (camera)
17 define simcam camera
18 (
19         resolution [ 640 480 ]
20         range [ 0.2 40.0 ]
21         fov [ 69.0 42.0 ]
22         pantilt [ 0.0 0.0 ]
23
24         color "grey"
25 )
26
27 define car position
28 (
29         size [0.565 0.29 0.175]
30         origin [-0.165 0 0 0]
31         gui_nose 1
32
33         # model (tx2-auto-3)
34         block
35         (
36                 points 12
37                 point[0] [16.43 7.25]
38                 point[1] [16.43 9.71]
39                 point[2] [14 12.76]
40                 point[3] [14 16.25]
41                 point[4] [16.43 19.29]
42                 point[5] [16.43 21.75]
43                 point[6] [36.63 21.75]
44                 point[7] [39.35 17.86]
45                 point[8] [45 16.59]
46                 point[9] [45 12.41]
47                 point[10] [39.35 11.14]
48                 point[11] [36.63 7.25]
49                 z [1 8.5]
50         )
51
52         # Kola LZ
53         block
54         (
55                 points 4
56                 point[0] [7.5 0]
57                 point[1] [7.5 6]
58                 point[2] [18 6]
59                 point[3] [18 0]
60                 z [0 10.5]
61                 color "black"
62         )
63
64         # Kola PZ
65         block
66         (
67                 points 4
68                 point[0] [7.5 23]
69                 point[1] [7.5 29]
70                 point[2] [18 29]
71                 point[3] [18 23]
72                 z [0 10.5]
73                 color "black"
74         )
75
76         # Kola PP
77         block
78         (
79                 points 4
80                 point[0] [39.5 23]
81                 point[1] [39.5 29]
82                 point[2] [50 29]
83                 point[3] [50 23]
84                 z [0 10.5]
85                 color "black"
86         )
87
88         # Kola LP
89         block
90         (
91                 points 4
92                 point[0] [39.5 0]
93                 point[1] [39.5 6]
94                 point[2] [50 6]
95                 point[3] [50 0]
96                 z [0 10.5]
97                 color "black"
98         )
99
100         # Predni naraznik
101         block
102         (
103                 points 4
104                 point[0] [54.5 4.75]
105                 point[1] [54.5 24.25]
106                 point[2] [56.5 24.25]
107                 point[3] [56.5 4.75]
108                 z [9 12]
109                 color "black"
110         )
111
112         # Zadni naraznik
113         block
114         (
115                 points 4
116                 point[0] [0 6]
117                 point[1] [0 23]
118                 point[2] [0.5 23]
119                 point[3] [0.5 6]
120                 z [9 12]
121                 color "black"
122         )
123
124         # Podstavec lidaru (pod nim)
125         block
126         (
127                 points 4
128                 point[0] [28.5 12]
129                 point[1] [28.5 17]
130                 point[2] [33.5 17]
131                 point[3] [33.5 12]
132                 z [8.5 10.5]
133                 color "blue"
134         )
135
136         # Podstavec lidaru (cast lidaru)
137         block
138         (
139                 points 4
140                 point[0] [28.5 12]
141                 point[1] [28.5 17]
142                 point[2] [33.5 17]
143                 point[3] [33.5 12]
144                 z [10.5 14]
145                 color "black"
146         )
147
148         # lidar
149         block
150         (
151                 points 4
152                 point[0] [28.5 12]
153                 point[1] [28.5 17]
154                 point[2] [33.5 17]
155                 point[3] [33.5 12]
156                 z [14 17.5]
157                 color "orange"
158         )
159
160         drive "car"
161         wheelbase 0.32
162         localization "gps"
163         # gps = absolute
164         # odom = relative
165
166         # LiDAR
167         # pozice v metrech, musi se pripocitat i posun stredu otaceni
168         # a pocatecni poloha
169         ust10lx ( pose [ -0.12 0 0.1575 0 ] size [ 0.05 0.05 0.035 ] )
170
171         # Camera
172         simcam ( pose [ -0.1375 0 0.175 0 ] size [ 0.025 0.09 0.025 ] )
173
174         stack_children 0
175
176         # Omezeni na rychlost
177         # Pokud neni uvedeno, je to +-1 na xyz, +-90 na a.
178         # min, max
179         # x - dopredna rychlost
180         # y - lateralni rychlost (pro auto muze byt 0)
181         # z - taky 0
182         # a - zataceni (ve stupnich)
183         velocity_bounds [ -33 33 0 0 0 0 -90 90 ]
184 )