-
Notifications
You must be signed in to change notification settings - Fork 23
/
model_comparison_obstacles.launch
121 lines (83 loc) · 6.03 KB
/
model_comparison_obstacles.launch
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
<?xml version="1.0"?>
<launch>
<!--initialize the arguments-->
<arg name="world_number" default="0"/>
<arg name="car_name" default="racecar"/>
<arg name="gui" default="true" />
<arg name="velocity" default="1.0"/>
<!--random seed used to allocte obstacles within vehicle environment-->
<arg name="random_seed" default = "1516"/>
<!-- free space points within occupancy grid, this file is generated by gen_map.py
within the race package-->
<arg name="freespace_file" default ="porto_freespace.txt"/>
<!-- how many obstacles (cones) to allocate in the environment-->
<arg name="num_obstacles" default="5"/>
<!--flag for selecting the algorithm
0 is e2e
1 is SAC
2 is DDPG
-->
<!-- we have the option to reset after a collision-->
<arg name="reset_on_crash" default="false"/>
<!--network model utilized for end-to-end driving-->
<arg name="model_name" default="fnn_lidar_porto.hdf5"/>
<arg name="model_name2" default="fnn_lidar_all.hdf5"/>
<arg name="model_name3" default="fnn_lidar_barca.hdf5"/>
<arg name="model_name4" default="fnn_lidar_walker.hdf5"/>
<!--handles selecting a track-->
<arg name="world_name" if="$(eval arg('world_number')==0)" value="track_porto"/>
<arg name="world_name" if="$(eval arg('world_number')==1)" value="racecar_walker"/>
<arg name="world_name" if="$(eval arg('world_number')==2)" value="track_barca"/>
<arg name="world_name" if="$(eval arg('world_number')==3)" value="racecar_tunnel"/>
<arg name="world_name" if="$(eval arg('world_number')==4)" value="track_levine"/>
<arg name="algorithm" default="0"/>
<arg name="algorithm_name" if="$(eval arg('algorithm')==0)" value="e2e"/>
<arg name="algorithm_name" if="$(eval arg('algorithm')==1)" value="sac"/>
<arg name="algorithm_name" if="$(eval arg('algorithm')==2)" value="ddpg"/>
<arg name="algorithm_name" if="$(eval arg('algorithm')==3)" value="e2e_all"/>
<arg name="algorithm_name" if="$(eval arg('algorithm')==4)" value="e2e_barca"/>
<arg name="algorithm_name" if="$(eval arg('algorithm')==5)" value="e2e_walker"/>
<!-- name of collision log file-->
<arg name="collision_file" value ="collisions_$(arg algorithm_name)_$(arg world_name)_$(arg velocity)_cones.csv"/>
<!-- name of progress log file-->
<arg name="progression_file" value ="progress_$(arg algorithm_name)_$(arg world_name)_$(arg velocity)_cones.csv"/>
<!--Select the CSV file for the waypoints needed to track progress-->
<arg name="csv_filename" if="$(eval arg('world_number')==0)" default="track_porto_26780.csv"/>
<arg name="csv_filename" if="$(eval arg('world_number')==1)" default="racecar_walker_29418.csv"/>
<arg name="csv_filename" if="$(eval arg('world_number')==2)" default="track_barca_4676.csv"/>
<arg name="csv_filename" if="$(eval arg('world_number')==3)" default="racecar_tunnel_26520.csv"/>
<arg name="csv_filename" if="$(eval arg('world_number')==4)" default="levine-waypoints3.csv"/>
<!--how long to run each experiment before timeout-->
<arg name="timeout" default = "180"/>
<!--experiment_number this parameter helps associate collisions with particular experiments-->
<arg name="experiment_number" default="0"/>
<!--docker requirements-->
<arg name="use_sim_time" default = "true"/>
<arg name="verbose" default ="false"/>
<!--launch the simulator-->
<include file="$(find race)/launch/f1_tenth_devel.launch">
<arg name ="world_name" value="$(arg world_name)"/>
<arg name="verbose" value="$(arg verbose)"/>
<arg name="use_sim_time" default = "$(arg use_sim_time)"/>
<arg name="gui" value="$(arg gui)" />
</include>
<!--Timeout node-->
<node pkg="racecar_gazebo" type="kill_simulation.py" name="timeout" required="true" args = "$(arg timeout)" output="screen"/>
<!--collision logging-->
<node pkg = "race" name= "collision_logger_$(arg car_name)" output="screen" unless = "$(arg reset_on_crash)" required="true" type ="collision_logger.py" args="$(arg car_name) $(arg num_obstacles) $(arg random_seed) $(arg collision_file) $(arg experiment_number)"/>
<!--progress logging-->
<node pkg = "race" name= "progress_logger_$(arg car_name)" output="screen" unless = "$(arg reset_on_crash)" required="true" type ="compute_progress.py" args="$(arg car_name) $(arg csv_filename) $(arg progression_file) $(arg experiment_number)"/>
<!--End to end learning controller (porto)-->
<node pkg="race" type="lidar_classification_node.py" name="e2e" required='true' if="$(eval arg('algorithm')==0)" args="$(arg car_name) $(find race)/models/$(arg model_name) $(arg velocity)"/>
<!--reinforcement learning controllers-->
<node pkg="rl" name="sac_controller" type="sac_controller.py" if="$(eval arg('algorithm')==1)" args="$(arg car_name) $(arg velocity)" required="true" output="log"/>
<node pkg="rl" name="ddpg_controller" type="ddpg_controller.py" if="$(eval arg('algorithm')==2)" args="$(arg car_name) $(arg velocity)" required="true" output="log"/>
<!--End to end learning controller (all)-->
<node pkg="race" type="lidar_classification_node.py" name="e2e_all" required='true' if="$(eval arg('algorithm')==3)" args="$(arg car_name) $(find race)/models/$(arg model_name2) $(arg velocity)"/>
<!--End to end learning controller (barca)-->
<node pkg="race" type="lidar_classification_node.py" name="e2e_barca" required='true' if="$(eval arg('algorithm')==4)" args="$(arg car_name) $(find race)/models/$(arg model_name3) $(arg velocity)"/>
<!--End to end learning controller (walker)-->
<node pkg="race" type="lidar_classification_node.py" name="e2e_walker" required='true' if="$(eval arg('algorithm')==5)" args="$(arg car_name) $(find race)/models/$(arg model_name4) $(arg velocity)"/>
<!--generation of obtacles and visualization in rviz -->
<node pkg="racecar_gazebo" type="spawn_cone.py" name="spawn_cones" args = "$(arg random_seed) $(arg freespace_file) $(arg num_obstacles)" output="screen"/>
</launch>