From 3f385a009b7d747676a5664a48749c9644338b23 Mon Sep 17 00:00:00 2001 From: Jiri Vlasak Date: Tue, 15 Jun 2021 12:39:58 +0200 Subject: [PATCH] Copy tx2 auto model from f1tenth repo --- models/tx2-auto-3.model | 184 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 184 insertions(+) create mode 100644 models/tx2-auto-3.model diff --git a/models/tx2-auto-3.model b/models/tx2-auto-3.model new file mode 100644 index 0000000..1f5a6e5 --- /dev/null +++ b/models/tx2-auto-3.model @@ -0,0 +1,184 @@ +# Stage simulator model of 'tx2-auto-3' +# Author: Jaroslav Klapálek + +# Sensors (lidar) +define ust10lx ranger +( + sensor( + range [ 0.0 10.0 ] + fov 270.0 + samples 3243 + ) + + color "orange" +) + +# Sensors (camera) +define simcam camera +( + resolution [ 640 480 ] + range [ 0.2 40.0 ] + fov [ 69.0 42.0 ] + pantilt [ 0.0 0.0 ] + + color "grey" +) + +define car position +( + size [0.565 0.29 0.175] + origin [-0.165 0 0 0] + gui_nose 1 + + # model (tx2-auto-3) + block + ( + points 12 + point[0] [16.43 7.25] + point[1] [16.43 9.71] + point[2] [14 12.76] + point[3] [14 16.25] + point[4] [16.43 19.29] + point[5] [16.43 21.75] + point[6] [36.63 21.75] + point[7] [39.35 17.86] + point[8] [45 16.59] + point[9] [45 12.41] + point[10] [39.35 11.14] + point[11] [36.63 7.25] + z [1 8.5] + ) + + # Kola LZ + block + ( + points 4 + point[0] [7.5 0] + point[1] [7.5 6] + point[2] [18 6] + point[3] [18 0] + z [0 10.5] + color "black" + ) + + # Kola PZ + block + ( + points 4 + point[0] [7.5 23] + point[1] [7.5 29] + point[2] [18 29] + point[3] [18 23] + z [0 10.5] + color "black" + ) + + # Kola PP + block + ( + points 4 + point[0] [39.5 23] + point[1] [39.5 29] + point[2] [50 29] + point[3] [50 23] + z [0 10.5] + color "black" + ) + + # Kola LP + block + ( + points 4 + point[0] [39.5 0] + point[1] [39.5 6] + point[2] [50 6] + point[3] [50 0] + z [0 10.5] + color "black" + ) + + # Predni naraznik + block + ( + points 4 + point[0] [54.5 4.75] + point[1] [54.5 24.25] + point[2] [56.5 24.25] + point[3] [56.5 4.75] + z [9 12] + color "black" + ) + + # Zadni naraznik + block + ( + points 4 + point[0] [0 6] + point[1] [0 23] + point[2] [0.5 23] + point[3] [0.5 6] + z [9 12] + color "black" + ) + + # Podstavec lidaru (pod nim) + block + ( + points 4 + point[0] [28.5 12] + point[1] [28.5 17] + point[2] [33.5 17] + point[3] [33.5 12] + z [8.5 10.5] + color "blue" + ) + + # Podstavec lidaru (cast lidaru) + block + ( + points 4 + point[0] [28.5 12] + point[1] [28.5 17] + point[2] [33.5 17] + point[3] [33.5 12] + z [10.5 14] + color "black" + ) + + # lidar + block + ( + points 4 + point[0] [28.5 12] + point[1] [28.5 17] + point[2] [33.5 17] + point[3] [33.5 12] + z [14 17.5] + color "orange" + ) + + drive "car" + wheelbase 0.32 + localization "gps" + # gps = absolute + # odom = relative + + # LiDAR + # pozice v metrech, musi se pripocitat i posun stredu otaceni + # a pocatecni poloha + ust10lx ( pose [ -0.12 0 0.1575 0 ] size [ 0.05 0.05 0.035 ] ) + + # Camera + simcam ( pose [ -0.1375 0 0.175 0 ] size [ 0.025 0.09 0.025 ] ) + + stack_children 0 + + # Omezeni na rychlost + # Pokud neni uvedeno, je to +-1 na xyz, +-90 na a. + # min, max + # x - dopredna rychlost + # y - lateralni rychlost (pro auto muze byt 0) + # z - taky 0 + # a - zataceni (ve stupnich) + velocity_bounds [ -33 33 0 0 0 0 -90 90 ] +) -- 2.39.2