-
Notifications
You must be signed in to change notification settings - Fork 55
/
launch_evaluation.bash
executable file
·71 lines (56 loc) · 1.39 KB
/
launch_evaluation.bash
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
#!/bin/bash
# Pass number of rollouts as argument
if [ $1 ]
then
N="$1"
else
N=10
fi
# Set Flightmare Path if it is not set
if [ -z $FLIGHTMARE_PATH ]
then
export FLIGHTMARE_PATH=$PWD/flightmare
fi
# Launch the simulator, unless it is already running
if [ -z $(pgrep visionsim_node) ]
then
roslaunch envsim visionenv_sim.launch render:=True &
ROS_PID="$!"
echo $ROS_PID
sleep 10
else
ROS_PID=""
fi
SUMMARY_FILE="evaluation.yaml"
"" > $SUMMARY_FILE
# Perform N evaluation runs
for i in $(eval echo {1..$N})
do
# Publish simulator reset
rostopic pub /kingfisher/dodgeros_pilot/off std_msgs/Empty "{}" --once
rostopic pub /kingfisher/dodgeros_pilot/reset_sim std_msgs/Empty "{}" --once
rostopic pub /kingfisher/dodgeros_pilot/enable std_msgs/Bool "data: true" --once
rostopic pub /kingfisher/dodgeros_pilot/start std_msgs/Empty "{}" --once
export ROLLOUT_NAME="rollout_""$i"
echo "$ROLLOUT_NAME"
cd ./envtest/ros/
python3 evaluation_node.py &
PY_PID="$!"
python3 run_competition.py &
COMP_PID="$!"
cd -
sleep 2.0
rostopic pub /kingfisher/start_navigation std_msgs/Empty "{}" --once
# Wait until the evaluation script has finished
while ps -p $PY_PID > /dev/null
do
sleep 1
done
cat "$SUMMARY_FILE" "./envtest/ros/summary.yaml" > "tmp.yaml"
mv "tmp.yaml" "$SUMMARY_FILE"
kill -SIGINT "$COMP_PID"
done
if [ $ROS_PID ]
then
kill -SIGINT "$ROS_PID"
fi